odriverobotics / ros_odrive

MIT License
53 stars 32 forks source link

Full CAN Interface Support #23

Open daisukes opened 2 weeks ago

daisukes commented 2 weeks ago

Hello @samuelsadok,

Thank you for providing ROS2/CAN support for Odrive!

We have been developing robots with Pro and S1 connected through CAN and wanted to use SetVelGain and Arbitrary Parameter Access, but it looks like the current implementation supports a part of the interface.

Do you plan to support all CAN interfaces listed in the link?

samuelsadok commented 2 weeks ago

Currently this is not on our roadmap, but we're open to suggestions. Can you tell us more about your use case?

Are you using the standalone odrive_node or the odrive_ros2_control plugin?

For the standalone odrive_node, to support SetVelGain, we'd need to add a corresponding (optional) field to ControlMessage.msg. This is however perhaps not the most scalable to do for all messages. For Arbitrary Parameter Access, I think a higher level approach is needed. Ideally, the parameters are identified by string and a user ROS node can simply do "write axis0.config.torque_soft_max = 1.0" and "subscribe to axis0.pos_estimate and axis0.vel_estimate at 10Hz" (for example). I haven't looked into how this would be expressed in terms of ROS messages yet.

For the odrive_ros2_control plugin, the feature set is defined by the standard ROS control interface, and I'm not sure yet what the best way is to add device-specific features. Maybe the plugin can simultaneously publish itself as a node and in this way provide a "side-channel" that bypasses ros2_control. It would be helpful if people with more ros2_control experience chime in on what the recommended approach is.

If you only need it at startup, the approach could be based on a config file.

daisukes commented 5 days ago

We currently use the standalone node and have implemented a "side-channel" node to send SetVelGain frame to change vel_gain/vel_integrator_gain. It is not a continuous control and will change when we switch the robot's mode.

For the standalone odrive_node, to support SetVelGain, we'd need to add a corresponding (optional) field to ControlMessage.msg. This is however perhaps not the most scalable to do for all messages.

I thought it would be helpful for us if the odrive_node supports such value change through ROS2 parameters. (Set_Traj_Vel_Limit, Set_Traj_Accel_Limits, Set_Traj_Intertia, Set_Pos_Gain, Set_Vel_Gains) One drawback is that it is not straightforward to get the initial value of those settings from the ODrive board. We may use the "unset" state to indicate the value on the board is used.

For the odrive_ros2_control plugin

I am unfamiliar with ROS2 control, but GPIO interfaces can be used.

https://control.ros.org/rolling/doc/ros2_control_demos/example_10/doc/userdoc.html#ros2-control-demos-example-10-userdoc