Roboteq Motor Controller Driver for ROS2 (Humble)
/roboteq_motor_controller_node:
ros__parameters:
roboteq_motor_controller:
port_name: "/dev/ttyACM0" # Port name of left motor controller serial port.
frame_id: "roboteq_motor_controller" # Frame ID
baudrate: 115200 # Baudrate of the roboteq motor controller serial port.
left_motor_direction: 1 # Left motor direction, it can be 1 or -1
right_motor_direction: 1 # Right motor direction, it can be 1 or -1
motor_acceleration: 1.0 # Acceleration of left and right motors.
motor_deceleration: 1.0 # Deceleration of left and right motors.
cd ~ros2_ws/src && git clone https://github.com/furkansariyildiz/roboteq_motor_controller_driver.git
cd ~ros2_ws && colcon build --symlink-install --packages-select roboteq_motor_controller
ros2 launch roboteq_motor_controller roboteq_motor_controller.launch.py
This package subscribes /roboteq_motor_controller/motors_rpm topic for getting desired RPM values. After getting this message, package sends RPM values to motor controller for left and right motors.
roboteq_motor_controller::msg::RPM
std_msgs/Header header
std_msgs/Float64 left_motor_rpm
std_msgs/Float64 right_motor_rpm
Package publishes motor RPM values to /roboteq_motor_controller/motors_rpm_output topic which are readed from motor controller with roboteq_motor_controller::msg::RPM type.
roboteq_motor_controller::msg::RPM
std_msgs/Header header
std_msgs/Float64 left_motor_rpm
std_msgs/Float64 right_motor_rpm
Package publsihes motor controller flags to /roboteq_motor_controller/motor_controller_flags topic with roboteq_motor_controller::msg::MotorControllerFlags type.
roboteq_motor_controller::msg::MotorControllerFlags
std_msgs/Header header
string[] fault_flags
string[] left_motor_flags
string[] right_motor_flags
string[] status_flags
fault_flags: String array for motor and motor controller faults. Fault flag can contains following values;
{"DefaultConfigLoaded", "MosfetFail", "MotorSensorSetupFault", "EmergencyStop", "ShotCircuit", "UnderVoltage", "OverVoltage", "OverHeat"}
left_motor_flags: String array for left motor. Motor flags can contain following values;
{"AmpsTriggerActivated", "ReverseLimitTriggered", "ForwardLimitTriggered", "SafetyStopActive", "LoopErrorDetected", "MotorStalled", "AmpsLimitCurrentlyActive"}
right_motor_flags: String array for left motor. Motor flags can contain following values;
{"AmpsTriggerActivated", "ReverseLimitTriggered", "ForwardLimitTriggered", "SafetyStopActive", "LoopErrorDetected", "MotorStalled", "AmpsLimitCurrentlyActive"}
status_flags: String array for motor controller status flags. It can contain following values;
{"Setup", "RunScript", "STO", "AtLimit", "StallDetected", "PowerStageOff", "AnalogMode", "PulseMode", "SerialMode"},
Package publishes motor RPM values to /roboteq_motor_controller/motor_controller_status topic which are readed from motor controller with roboteq_motor_controller::msg::MotorControllerStatus type.
roboteq_motor_controller::msg::MotorControllerStatus
std_msgs/Header header
roboteq_motor_controller/MotorStatus left_motor_status
roboteq_motor_controller/MotorStatus right_motor_status
-
roboteq_motor_controller/MotorStatus
std_msgs/Header header roboteq_motor_controller/MotorCurrent current roboteq_motor_controller/MotorTemperature temperature
-
roboteq_motor_controller/MotorCurrent
std_msgs/Float64 amper
-
roboteq_motor_controller/MotorTemperature
std_msgs/Float64 celsius
-