ros_odrive
ros_odrive copied to clipboard
feat: multi-ODrive support with node_id + timestamp in odrive status message
Summary
This PR extends odrive_status.msg and updates the odrive_can_node implementation to support multi-ODrive setups by disambiguating messages and adding temporal context.
Motivation
The existing implementation works for a single ODrive but makes it impossible to distinguish messages when multiple ODrives are connected. Additionally, messages lacked a timestamp, complicating debugging, logging, and synchronization with other ROS data streams.
These changes:
- Enable reliable use of multiple ODrives in one ROS system.
- Improve traceability and debugging with accurate timestamps.
- Reduce overhead by defining
node_idonce.
This inspiration comes from working on a system with multiple ODrives, such as a quadruped robot.
Changes
-
Message definition
- Added
std_msgs/Header header(providesstamp). - Added
uint32 node_idfield to uniquely identify each ODrive device.
- Added
-
Publisher logic (
odrive_can_node.cpp)header.stampis now assigned immediately before current and voltage measurements are taken, ensuring accurate timing of values.node_idis defined once at initialization, rather than being re-set in every loop iteration.
Testing
- Verified build with
colcon build. - Ran
ros2 topic echo /odrive_axis*/odrive_statuswith two ODrives connected:- Confirmed each message contains the correct
node_id. - Confirmed
header.stampupdates consistently at each publish cycle.
- Confirmed each message contains the correct
Notes
- This is a message definition change. Downstream packages depending on
odrive_status.msgmust be rebuilt. - Maintainers: please confirm if
uint32is suitable fornode_idor if a smaller type is preferred.