diff --git a/clearpath_motor_msgs/CMakeLists.txt b/clearpath_motor_msgs/CMakeLists.txt new file mode 100644 index 0000000..87003a5 --- /dev/null +++ b/clearpath_motor_msgs/CMakeLists.txt @@ -0,0 +1,28 @@ +cmake_minimum_required(VERSION 3.5) +project(clearpath_motor_msgs) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(action_msgs REQUIRED) +find_package(ament_cmake REQUIRED) +find_package(builtin_interfaces REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(std_msgs REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + msg/PumaFeedback.msg + msg/PumaStatus.msg + msg/PumaMultiFeedback.msg + msg/PumaMultiStatus.msg + DEPENDENCIES action_msgs std_msgs builtin_interfaces +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/clearpath_motor_msgs/msg/PumaFeedback.msg b/clearpath_motor_msgs/msg/PumaFeedback.msg new file mode 100644 index 0000000..743a64b --- /dev/null +++ b/clearpath_motor_msgs/msg/PumaFeedback.msg @@ -0,0 +1,24 @@ +# Number on the bus (CAN ID). +uint8 device_number + +# Name of joint controlled, or other identifier. +string device_name + +# Duty cycle of the h-bridge driver (-1..1). +float32 duty_cycle + +# Current consumed (amps). +float32 current + +# Travel as measured by the encoder (rad). +float64 travel + +# Angular velocity as measured by the encoder (rad/s). +float64 speed + +# The reported setpoint value of the on-board controller for the given mode. +# In voltage control, duty cycle of the h-bridge driver (-1..1). +# In speed control, angular velocity setpoint of the on-board controller (rad/s). +# In position control, travel as measured by the encoder (rad). +# In current control, the current consumed (amps). +float64 setpoint diff --git a/clearpath_motor_msgs/msg/PumaMultiFeedback.msg b/clearpath_motor_msgs/msg/PumaMultiFeedback.msg new file mode 100644 index 0000000..6dfe874 --- /dev/null +++ b/clearpath_motor_msgs/msg/PumaMultiFeedback.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +clearpath_motor_msgs/PumaFeedback[] drivers_feedback diff --git a/clearpath_motor_msgs/msg/PumaMultiStatus.msg b/clearpath_motor_msgs/msg/PumaMultiStatus.msg new file mode 100644 index 0000000..45c6600 --- /dev/null +++ b/clearpath_motor_msgs/msg/PumaMultiStatus.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +clearpath_motor_msgs/PumaStatus[] drivers diff --git a/clearpath_motor_msgs/msg/PumaStatus.msg b/clearpath_motor_msgs/msg/PumaStatus.msg new file mode 100644 index 0000000..57ace40 --- /dev/null +++ b/clearpath_motor_msgs/msg/PumaStatus.msg @@ -0,0 +1,33 @@ +# Number on the bus (CAN ID). +uint8 device_number + +# Name of joint controlled, or other identifier. +string device_name + +# Input terminal voltage (volts). +float32 bus_voltage + +# Internal driver temperature (degC). +float32 temperature + +# Voltage as output to the motor (volts). +float32 output_voltage + +# Value of the auxiliary ADC (volts). +float32 analog_input + +# Available control modes, not all of which are broken out to +# this ROS driver. +uint8 MODE_VOLTAGE=0 +uint8 MODE_CURRENT=1 +uint8 MODE_SPEED=2 +uint8 MODE_POSITION=3 +uint8 MODE_VCOMP=4 +uint8 mode + +# Fault states which could cause the driver to be immobilized. +uint8 FAULT_CURRENT=1 +uint8 FAULT_TEMPERATURE=2 +uint8 FAULT_BUS_VOLTAGE=4 +uint8 FAULT_BRIDGE_DRIVER=8 +uint8 fault diff --git a/clearpath_motor_msgs/package.xml b/clearpath_motor_msgs/package.xml new file mode 100644 index 0000000..6afbb8d --- /dev/null +++ b/clearpath_motor_msgs/package.xml @@ -0,0 +1,29 @@ + + + + clearpath_motor_msgs + 0.3.0 + Messages for Clearpath Motor Drivers. + BSD + + Mike Purvis + + Roni Kreinin + Tony Baltovski + + ament_cmake + + action_msgs + std_msgs + builtin_interfaces + + rosidl_default_generators + + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + +