https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html
sudo apt install ros-rolling-ros2-control
https://github.com/PickNikRobotics/topic_based_ros2_control/tree/main?tab=readme-ov-file
sudo apt install ros-humble-topic-based-ros2-control
pip3 install python-can
pip3 install pyserial
pip3 install numpy
sudo rosdep init
sudo rosdep update
sudo rosdep install --from-paths ./ -i -y --rosdistro ${ROS_DISTRO}
Navigate to the control ros2 control .xacro file and in the <hardware> section include topic based plugin together with topic definition for state and command:
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
<param name="joint_commands_topic">/mks_servo_joints_cmd</param>
<param name="joint_states_topic">/mks_servo_joints</param>
Topics use sensor_msgs/JointState.msg format
In src/python_driver/python_driver/driver.py file specify joint count of your robot by modifying JOINT_CNT variable. Interfaces with servos are created automatically with IDs in ascending order and starting with ID 1.
self.servos = [ MksServo(self.bus, self.notifier, i+1) for i in range(self.JOINT_CNT) ]
with:
self.servos = [
MksServo(self.bus, self.notifier, 1),
MksServo(self.bus, self.notifier, 5)
]
where the last argument specifies servo CAN ID.
It is also impartant to specify usb device path of your can usb interface by changing channel argument:
self.bus = can.interface.Bus(interface='slcan', channel='/dev/ttyACM0', bitrate=125000)
In workspace root
colcon build
source install/setup.bash
ros2 run python_driver mks_interface
In case of permision denied error, update usb device permissions by running:
sudo chmod 666 /dev/ttyACM0
By default, the driver is in standby mode (mode 0). In this mode joint states are published and all commands are ignored.
Mode can be changed by calling mks_servo_change_mode service:
ros2 service call /mks_servo_change_mode python_driver_interfaces/srv/ChangeMode "{mode: 1}"
Don't forget to source the workspace before running the command.
- 0 - Standby (joint states are published, command are ignored)
- 1 - Position (joint states are published, position commands are used)
- 2 - Speed (joint states are published, velocity commands are used)
ros2 service call /mks_servo_reset_axis python_driver_interfaces/srv/ResetAxis
This demo works with at least 2 servos connected i.e. JOINT_CNT in driver should be 2.
ros2 launch ros2_control_demo_example_1 rrbot.launch.py
During testing we have observed that servos continue to run even when the communitacion is lost.