mc_rtc::Configuration
general purpose configurationROS, the Robot Operating System, is a very popular middleware in robotics and many tools in the domain are able to communicate (sometimes solely) using ROS. However, ROS was not designed for real-time applications and thus this should be taken into account when integrating ROS products with mc_rtc. The remainder of this document assumes the reader has some level of familiarity with ROS principles.
Depending on the options provided, mc_rtc can publish:
The first is published in the control
namespace while the second is published in the real
namespace.
Everything else is up to the controller code. In particular, mc_rtc will not take care of spinning.
For external tools, the mc_rtc::RobotPublisher
class is provided to publish a robot’s state to ROS.
The following code will give you access to the ros::NodeHandle
created by mc_rtc:
#include <mc_rtc/ros.h>
std::shared_ptr<ros::NodeHandle> nh = mc_rtc::ROSBridge::get_node_handle();
Note that the returned pointer is null if mc_rtc was built without ROS support or if ROS was unable to initialize (usually because the master is not available).
The main caveat when working with ROS (in mc_rtc) is the absence of real-time support. As such, you are strongly encourage not to use ROS functions within:
reset()
functionrun()
functionBoth these functions will occur in the real-time loop or real-time sensitive context. A good scheme is to leave all ROS operations in a separate thread. The synchronization issue is out of the scope of this document but C++11 and further provide many tools to that effect.