DiffBot VESC CAN (Differential Mobile Robot with VESC CAN Control) is a complete ros2_control implementation for differential drive robots using VESC motor controllers over CAN bus. This package provides a self-contained, independent implementation with no external dependencies.
- ✅ VESC CAN Integration: Direct interface with VESC motor controllers via CAN bus
- ✅ Complete Independence: No external dependencies - fully self-contained package
- ✅ Differential Drive Control: Proper implementation of diff drive kinematics
- ✅ Hardware Interface: Real VESC hardware integration with fallback to mock hardware
- ✅ RViz Visualization: Real-time robot visualization with independent URDF and materials
- ✅ Odometry Publishing: Accurate pose estimation and velocity tracking
- ✅ TwistStamped Commands: Modern ROS2 message interface with timestamp support
- ✅ Joint State Broadcasting: Real-time wheel position and velocity feedback
- ✅ Production Ready: Clean, tested implementation for real robot deployment
- DiffBotSystemHardware: Implements
hardware_interface::SystemInterface
for VESC CAN - State Interfaces: Position and velocity for each wheel joint
- Command Interfaces: Velocity commands sent directly to VESC controllers
- CAN Communication: Direct interface with VESC motor controllers
- Lifecycle Management: Proper activation/deactivation with VESC initialization
- diff_drive_controller: Converts Twist commands to wheel velocities
- joint_state_broadcaster: Publishes joint states for visualization
/cmd_vel
(geometry_msgs/TwistStamped): Robot velocity commands/diffbot_base_controller/odom
(nav_msgs/Odometry): Robot pose and twist/joint_states
(sensor_msgs/JointState): Wheel positions and velocities/tf
and/tf_static
: Transform tree for visualization
cd /home/robot/robot_ws
colcon build --packages-select diff_vesc_can_ros2_control
source install/setup.bash
ros2 launch diff_vesc_can_ros2_control view_robot.launch.py
ros2 launch diff_vesc_can_ros2_control diffbot.launch.py
# Send velocity commands (linear.x = 0.2 m/s, angular.z = 0.1 rad/s)
# ************************ WORKS *********************************
ros2 topic pub /cmd_vel geometry_msgs/msg/TwistStamped \
"{header: {stamp: now, frame_id: base_link}, \
twist: {linear: {x: 0.2, y: 0.0, z: 0.0}, \
angular: {x: 0.0, y: 0.0, z: 0.1}}}" --rate 1
# Stop the robot
ros2 topic pub /cmd_vel geometry_msgs/msg/TwistStamped \
"{header: {stamp: now, frame_id: base_link}, \
twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, \
angular: {x: 0.0, y: 0.0, z: 0.0}}}" --once
diff_vesc_can_ros2_control/
├── bringup/
│ ├── config/
│ │ └── diffbot_controllers.yaml # Controller configuration
│ └── launch/
│ └── diffbot.launch.py # Main system launch
├── description/
│ ├── launch/
│ │ └── view_robot.launch.py # Robot visualization
│ ├── ros2_control/
│ │ └── diffbot.ros2_control.xacro # Hardware interface config
│ └── urdf/
│ ├── diffbot.urdf.xacro # Robot description
│ ├── diffbot_description.urdf.xacro
│ └── diffbot.materials.xacro # Visual materials
├── hardware/
│ ├── include/diff_vesc_can_ros2_control/
│ │ └── diffbot_system.hpp # Hardware interface header
│ └── diffbot_system.cpp # VESC hardware implementation
├── rviz/
│ ├── diffbot.rviz # RViz configuration
│ └── diffbot_view.rviz # Visualization config
└── README.md # This file
This will start:
- Controller manager with VESC CAN interface
- Hardware interface (real VESC or mock)
- Differential drive controller
- Joint state broadcaster
- RViz visualization
- Robot state publisher
Forward Movement:
ros2 topic pub /cmd_vel geometry_msgs/msg/TwistStamped \
"{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''},
twist: {linear: {x: 0.5, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}}" -r 10
Rotation:
ros2 topic pub /cmd_vel geometry_msgs/msg/TwistStamped \
"{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''},
twist: {linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.5}}}" -r 10
Combined Movement (Arc):
ros2 topic pub /cmd_vel geometry_msgs/msg/TwistStamped \
"{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''},
twist: {linear: {x: 0.3, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.2}}}" -r 10
Joint States:
ros2 topic echo /joint_states
Odometry:
ros2 topic echo /diffbot_base_controller/odom
Controller Status:
ros2 control list_controllers
This package serves as a reference for implementing real hardware interfaces. In our workspace, we have:
diff_vesc_can_ros2_pkg_cpp
: Production VESC CAN communicationmodular_diffbot_control
: Real robot control implementation
- Hardware Interface Pattern: Study
hardware/diffbot_system.cpp
for proper lifecycle management - Command Processing: See how
write()
method handles velocity commands - State Publishing: Understand how
read()
method updates joint states - Controller Configuration: Review the YAML configuration patterns
- Launch File Structure: Analyze the launch file organization
ros2_control_diffbot_original/
├── CMakeLists.txt # Build configuration
├── package.xml # Package dependencies
├── README.md # This file
├── hardware/
│ ├── diffbot_system.cpp # Hardware interface implementation
│ └── include/
│ └── ros2_control_diffbot_original/
│ └── diffbot_system.hpp
├── bringup/
│ ├── launch/
│ │ ├── diffbot.launch.py # Main launch file
│ │ └── view_robot.launch.py
│ └── config/
│ └── diffbot_controllers.yaml
├── description/
│ └── urdf/
│ ├── diffbot_description.urdf.xacro
│ └── diffbot.ros2_control.xacro
└── ros2_control_diffbot_original.xml # Plugin declaration
This package demonstrates:
- ros2_control Framework: Complete implementation from hardware interface to visualization
- Differential Drive Kinematics: Mathematical model to wheel commands
- ROS2 Best Practices: Proper package structure, lifecycle management, and communication patterns
- Real-time Control: High-frequency control loops and state updates
- Simulation to Reality: Bridge between simulated and real hardware
# List all nodes
ros2 node list
# Check controller status
ros2 control list_controllers
# Monitor topics
ros2 topic list
ros2 topic hz /joint_states
ros2 topic hz /diffbot_base_controller/odom
- Control Frequency: 100Hz (configurable)
- Joint State Publishing: 100Hz
- Odometry Publishing: 100Hz
- Command Processing: Real-time response
- diff_vesc_can_ros2_pkg_cpp: Real VESC hardware interface with CAN communication
- modular_diffbot_control: Production robot control system
- ros2_control_demo_description: Robot URDF descriptions
- Study the Code: Understand the hardware interface implementation
- Modify Parameters: Experiment with wheel radius, base width, etc.
- Extend Functionality: Add sensors, implement custom controllers
- Hardware Integration: Use this as a template for real VESC implementation
Status: ✅ Fully functional and tested