Skip to content

Commit

Permalink
A few changes to CMake, motor_node.cc and motor_hardware.h
Browse files Browse the repository at this point in the history
  • Loading branch information
GreTimotej committed Aug 13, 2024
1 parent f938f99 commit a4448c3
Show file tree
Hide file tree
Showing 12 changed files with 785 additions and 1,755 deletions.
96 changes: 66 additions & 30 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,49 +1,85 @@
cmake_minimum_required(VERSION 3.8)
cmake_minimum_required(VERSION 3.5)
project(ubiquity_motor_ros2)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
# Find dependencies
find_package(ament_cmake REQUIRED)
#find_package(message_generation REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclpy REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(controller_manager REQUIRED)
find_package(ros2_control REQUIRED)
find_package(diagnostic_updater REQUIRED)
#find_package(dynamic_reconfigure REQUIRED) - does not exist in ROS2

#find_package(Boost REQUIRED)
#find_package(thread REQUIRED)
#find_package(atomic REQUIRED)

add_library(ubiquity_motor
src/motor_message.cc src/motor_serial.cc src/motor_hardware.cc

# ROS 2 message generation
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/MotorState.msg"
DEPENDENCIES std_msgs
)

install(PROGRAMS
scripts/upgrade_firmware.py
scripts/test_motor_board.py
scripts/test_pi_gpio.py
DESTINATION lib/${PROJECT_NAME}
# Include directories
include_directories(
include
)


if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
# Build the library containing reusable code
# add_library(ubiquity_motor
# src/motor_message.cc
# src/motor_serial.cc
# src/motor_hardware.cc
# )

# Link the generated messages to the library
# ament_target_dependencies(ubiquity_motor
# "rclcpp"
# "std_msgs"
# "sensor_msgs"
# "hardware_interface"
# "ros2_control"
# "diagnostic_updater"
# )

# Add executable
add_executable(motor_node src/motor_node.cc)

# add_dependencies(motor_node ${PROJECT_NAME}_interfaces)

# Link the generated messages and the library to the executable
# target_link_libraries(motor_node ubiquity_motor)

ament_target_dependencies(motor_node
"rclcpp"
"std_msgs"
"sensor_msgs"
"hardware_interface"
"ros2_control"
"diagnostic_updater"
)

ament_export_dependencies(rosidl_default_runtime)

# # Install the library and executable
install(TARGETS
motor_node
#ubiquity_motor
DESTINATION lib/${PROJECT_NAME}
)

# # Install any Python scripts (if any)
# install(PROGRAMS
# scripts/upgrade_firmware.py
# scripts/test_motor_board.py
# scripts/test_pi_gpio.py
# DESTINATION lib/${PROJECT_NAME}
# )

# Finish up the package
ament_package()
90 changes: 90 additions & 0 deletions CMakeLists_old.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
cmake_minimum_required(VERSION 3.5)
project(ubiquity_motor_ros2)

set(CMAKE_CXX_STANDARD 14) # use C++14

# Compiler flags for warnings
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# Find dependencies
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(ros2_control REQUIRED)
find_package(diagnostic_updater REQUIRED)

# ROS 2 message generation
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/MotorState.msg"
)

# Add library
add_library(ubiquity_motor
#src/motor_message.cc src/motor_serial.cc src/motor_hardware.cc
src/motor_node.cc
)

# Include directories for library
target_include_directories(ubiquity_motor
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

ament_target_dependencies(ubiquity_motor
"rclcpp"
"std_msgs"
"sensor_msgs"
"hardware_interface"
"ros2_control"
"diagnostic_updater"
)

# Add executable
add_executable(motor_node src/motor_node.cc)

# Include directories for executable
target_include_directories(motor_node
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
)

ament_target_dependencies(motor_node
"rclcpp"
"std_msgs"
"sensor_msgs"
"hardware_interface"
"ros2_control"
"diagnostic_updater"
)

# Install targets
install(TARGETS
motor_node
ubiquity_motor
DESTINATION lib/${PROJECT_NAME}
)

# Install scripts
install(PROGRAMS
scripts/upgrade_firmware.py
scripts/test_motor_board.py
scripts/test_pi_gpio.py
DESTINATION lib/${PROJECT_NAME}
)

# Test dependencies
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()
33 changes: 17 additions & 16 deletions include/ubiquity_motor/motor_hardware.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,22 +31,23 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef MOTORHARDWARE_H
#define MOTORHARDWARE_H

#include "hardware_interface/joint_command_interface.h"
#include "hardware_interface/joint_state_interface.h"
#include "hardware_interface/robot_hw.h"
#include "ros/ros.h"
#include "sensor_msgs/JointState.h"

#include "std_msgs/Int32.h"
#include "std_msgs/UInt32.h"
#include "std_msgs/Float32.h"
#include "std_msgs/Bool.h"
#include "std_msgs/String.h"
#include "sensor_msgs/BatteryState.h"
#include "ubiquity_motor/MotorState.h"

#include <diagnostic_updater/update_functions.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include "rclcpp/rclcpp.hpp"
// #include "hardware_interface/joint_command_interface.h"
// #include "hardware_interface/joint_state_interface.hpp"
// #include "hardware_interface/robot_hw.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "sensor_msgs/msg/joint_state.hpp"

#include "std_msgs/msg/int32.hpp"
#include "std_msgs/msg/u_int32.hpp"
#include "std_msgs/msg/float32.hpp"
#include "std_msgs/msg/bool.hpp"
#include "std_msgs/msg/string.hpp"
#include "sensor_msgs/msg/battery_state.hpp"
#include "ubiquity_motor_ros2/msg/motor_state.hpp"

#include <diagnostic_updater/update_functions.hpp>
#include <diagnostic_updater/diagnostic_updater.hpp>

#include <ubiquity_motor/motor_parameters.h>
#include <ubiquity_motor/motor_serial.h>
Expand Down
2 changes: 1 addition & 1 deletion include/ubiquity_motor/motor_parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef UBIQUITY_MOTOR_MOTOR_PARMETERS_H
#define UBIQUITY_MOTOR_MOTOR_PARMETERS_H

#include <ros/ros.h>
#include <rclcpp/rclcpp.hpp>

// These defines are for a high level topic for control of the motor node at a system level
#define ROS_TOPIC_SYSTEM_CONTROL "system_control" // A topic for system level control commands
Expand Down
4 changes: 2 additions & 2 deletions include/ubiquity_motor/motor_serial.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
#ifndef MOTORSERIAL_H
#define MOTORSERIAL_H

#include <ros/ros.h>
#include <serial/serial.h>
#include <rclcpp/rclcpp.hpp>
#include <serial/serial.hpp>
#include <ubiquity_motor/motor_message.h>
#include <ubiquity_motor/shared_queue.h>
#include <boost/thread.hpp>
Expand Down
2 changes: 2 additions & 0 deletions msg/Leds.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
bool led1
bool led2
9 changes: 9 additions & 0 deletions msg/MotorState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
std_msgs/Header header
float64 left_position
float64 right_position
float64 left_rotate_rate
float64 right_rotate_rate
float32 left_current
float32 right_current
int32 left_pwm_drive
int32 right_pwm_drive
7 changes: 7 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,13 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<build_depend>rosidl_default_generators</build_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>

<depend>hardware_interface</depend>


<export>
<build_type>ament_cmake</build_type>
</export>
Expand Down
Loading

0 comments on commit a4448c3

Please sign in to comment.