mc_rtc  2.13.0
ros.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015-2019 CNRS-UM LIRMM, CNRS-AIST JRL
3  */
4 
5 #pragma once
6 
7 #include <mc_rtc_ros/api.h>
8 
9 #include <mc_rtc/config.h>
10 
11 #include <mc_rbdyn/Robots.h>
12 
13 #include <SpaceVecAlg/SpaceVecAlg>
14 
15 #include <Eigen/Geometry>
16 #include <map>
17 #include <memory>
18 #include <string>
19 #include <vector>
20 
21 #ifdef MC_RTC_ROS_IS_ROS2
22 namespace rclcpp
23 {
24 class Node;
25 }
26 #else
27 namespace ros
28 {
29 class NodeHandle;
30 }
31 #endif
32 
33 namespace mc_rbdyn
34 {
35 struct Robot;
36 }
37 
38 namespace mc_control
39 {
40 struct MCGlobalController;
41 } // namespace mc_control
42 
43 namespace mc_rtc
44 {
45 
46 struct ROSBridgeImpl;
47 
48 #ifdef MC_RTC_ROS_IS_ROS2
49 using NodeHandlePtr = std::shared_ptr<rclcpp::Node>;
50 #else
51 using NodeHandlePtr = std::shared_ptr<ros::NodeHandle>;
52 #endif
53 
56 {
64 
70  static void set_publisher_timestep(double timestep);
71 
83  static void init_robot_publisher(const std::string & publisher,
84  double dt,
85  const mc_rbdyn::Robot & robot,
86  bool use_real = false);
87 
97  static void update_robot_publisher(const std::string & publisher, double dt, const mc_rbdyn::Robot & robot);
98 
103  static void stop_robot_publisher(const std::string & publisher);
104 
109  static void remove_extra_robot_publishers(const mc_rbdyn::Robots & robots);
110 
112  static void shutdown();
113 
114 private:
115  static ROSBridgeImpl & impl_();
116 };
117 
118 struct RobotPublisherImpl;
119 
127 {
128 public:
140  RobotPublisher(const std::string & prefix, double rate, double dt);
141 
144 
146  void init(const mc_rbdyn::Robot & robot, bool use_real = false);
147 
149  void update(double dt, const mc_rbdyn::Robot & robot);
150 
152  void set_rate(double rate);
153 
154 private:
155  std::unique_ptr<RobotPublisherImpl> impl;
156 };
157 
158 } // namespace mc_rtc
Definition: CompletionCriteria.h:11
Definition: generic_gripper.h:15
auto Robot(const std::string &name, GetT get_fn)
Definition: Robot.h:56
Definition: Contact.h:88
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Definition: ros.h:51
Definition: ros.h:28
#define MC_RTC_ROS_DLLAPI
Definition: api.h:50
Definition: Robot.h:63
Definition: Robots.h:16
Allows to access ROS functionalities within mc_rtc without explicit ROS dependencies.
Definition: ros.h:56
static void update_robot_publisher(const std::string &publisher, double dt, const mc_rbdyn::Robot &robot)
static NodeHandlePtr get_node_handle()
Get a ros::NodeHandle/rclcpp::Node.
static void stop_robot_publisher(const std::string &publisher)
static void remove_extra_robot_publishers(const mc_rbdyn::Robots &robots)
static void init_robot_publisher(const std::string &publisher, double dt, const mc_rbdyn::Robot &robot, bool use_real=false)
static void shutdown()
Stop ROS.
static void set_publisher_timestep(double timestep)
This structure is able to publish a Robot's state to ROS.
Definition: ros.h:127
void init(const mc_rbdyn::Robot &robot, bool use_real=false)
Initialize the publisher.
void set_rate(double rate)
Reset the publishing rate.
~RobotPublisher()
Destructor.
RobotPublisher(const std::string &prefix, double rate, double dt)
void update(double dt, const mc_rbdyn::Robot &robot)
Update the publisher.