ros-industrial / ros_canopen

CANopen driver framework for ROS (http://wiki.ros.org/ros_canopen)
GNU Lesser General Public License v3.0
332 stars 270 forks source link

Services Not Quick Enough For Loop #410

Closed connoranderson closed 3 years ago

connoranderson commented 3 years ago

I'm currently using canopen_chain_node to interface with some motor controllers (not using 402 pkg yet). Before this, I had a basic prototype working with the bridge node connected to my controller, which published the RPDO messages directly to the controller.

Now that I am using the chain node, my question is what are the best ways to achieve low-latency control loops using this package (in a production setting)? It seems like there are a few options:

  1. publish to socketcan bridge node /sent_messages
  2. canopen_chain_node /driver/set_object method
  3. use socketcan_interface library directly to send message

I've tried mocking out the /set_object implementation, but I'm finding that the execution time is around 8-9ms per service call & SDO response. This isn't acceptable for our application, so I'm curious how others are achieving decent loop rates with that amount of blocking routine? Are service calls the recommended way to interface with the chain nodes?

Can someone with experience on this shed some light on the best-practice here? I realize a lot of people are probably relying on ros_control, so maybe there are some parallels there.

mathias-luedtke commented 3 years ago

Can someone with experience on this shed some light on the best-practice here?

In general, I would recommend:

  1. Subclass canopen::RosChain (from canopen_chain_node) and canopen::Node (from canopen_master) to support your device properly, because this gives you full control.

I've tried mocking out the /set_object implementation, but I'm finding that the execution time is around 8-9ms per service call & SDO response.

set_object is mostly meant for debugging and bound to the update rate (= the call does not get process faster). Please keep in mind that non-persistent service clients have to establish the connection first. In additon, SDOs are very slow for some devices. To use PDOs instead, just map the object.

connoranderson commented 3 years ago

@ipa-mdl thank you for the speedy and detailed response. Using a persistent connection brought the update from 9ms to 2ms average.

So, in general, most people are building wrapper nodes around these classes for their own implementation? Are there any ways to do this through ROS interfaces (for instance if the calling function is in python)? Also, recommendations for high-speed multi-node bus access?

connoranderson commented 3 years ago

Going to mark this as closed since the initial question was answered. If anyone has answers to the follow-on questions, it's much appreciated.