mujoco_ros_utils
PosePublisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 #include <tf2_ros/transform_broadcaster.h>
5 
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
10 
11 #include <string>
12 
13 namespace MujocoRosUtils
14 {
15 
18 {
19 public:
21  static void RegisterPlugin();
22 
28  static PosePublisher * Create(const mjModel * m, mjData * d, int plugin_id);
29 
30 public:
32  PosePublisher(PosePublisher &&) = default;
33 
38  void reset(const mjModel * m, int plugin_id);
39 
45  void compute(const mjModel * m, mjData * d, int plugin_id);
46 
47 protected:
59  PosePublisher(const mjModel * m,
60  mjData * d,
61  int sensor_id,
62  const std::string & frame_id,
63  const std::string & pose_topic_name,
64  const std::string & vel_topic_name,
65  mjtNum publish_rate,
66  bool output_tf,
67  const std::string & tf_child_frame_id);
68 
69 protected:
71  int sensor_id_ = -1;
72 
74  int body_id_ = -1;
75 
77  std::shared_ptr<ros::NodeHandle> nh_;
78 
80  ros::Publisher pose_pub_;
81 
83  ros::Publisher vel_pub_;
84 
86  std::shared_ptr<tf2_ros::TransformBroadcaster> tf_br_;
87 
89  std::string frame_id_;
90 
92  std::string pose_topic_name_;
93 
95  std::string vel_topic_name_;
96 
98  int publish_skip_ = 0;
99 
101  bool output_tf_ = false;
102 
104  std::string tf_child_frame_id_;
105 
107  int sim_cnt_ = 0;
108 };
109 
110 } // namespace MujocoRosUtils
MujocoRosUtils::PosePublisher::PosePublisher
PosePublisher(PosePublisher &&)=default
Copy constructor.
MujocoRosUtils::PosePublisher::sensor_id_
int sensor_id_
Sensor ID.
Definition: PosePublisher.h:71
MujocoRosUtils::PosePublisher::RegisterPlugin
static void RegisterPlugin()
Register plugin.
Definition: PosePublisher.cpp:14
MujocoRosUtils::PosePublisher::nh_
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
Definition: PosePublisher.h:77
MujocoRosUtils::PosePublisher::output_tf_
bool output_tf_
Whether to broadcast TF.
Definition: PosePublisher.h:101
MujocoRosUtils::PosePublisher::tf_child_frame_id_
std::string tf_child_frame_id_
Child frame ID for TF.
Definition: PosePublisher.h:104
MujocoRosUtils::PosePublisher::compute
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
Definition: PosePublisher.cpp:215
MujocoRosUtils::PosePublisher::Create
static PosePublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
Definition: PosePublisher.cpp:73
MujocoRosUtils::PosePublisher
Plugin to publish topics or broadcast TF of pose and velocity of the body.
Definition: PosePublisher.h:17
MujocoRosUtils::PosePublisher::sim_cnt_
int sim_cnt_
Iteration count of simulation.
Definition: PosePublisher.h:107
MujocoRosUtils::PosePublisher::pose_topic_name_
std::string pose_topic_name_
Topic name of pose.
Definition: PosePublisher.h:92
MujocoRosUtils::PosePublisher::tf_br_
std::shared_ptr< tf2_ros::TransformBroadcaster > tf_br_
TF broadcaster.
Definition: PosePublisher.h:86
MujocoRosUtils::PosePublisher::reset
void reset(const mjModel *m, int plugin_id)
Reset.
Definition: PosePublisher.cpp:209
MujocoRosUtils::PosePublisher::vel_pub_
ros::Publisher vel_pub_
ROS publisher for velocity.
Definition: PosePublisher.h:83
MujocoRosUtils::PosePublisher::frame_id_
std::string frame_id_
Frame ID of topics header or TF parent.
Definition: PosePublisher.h:89
MujocoRosUtils::PosePublisher::body_id_
int body_id_
Body ID.
Definition: PosePublisher.h:74
MujocoRosUtils::PosePublisher::pose_pub_
ros::Publisher pose_pub_
ROS publisher for pose.
Definition: PosePublisher.h:80
MujocoRosUtils::PosePublisher::publish_skip_
int publish_skip_
Iteration interval to skip ROS publish.
Definition: PosePublisher.h:98
MujocoRosUtils::PosePublisher::vel_topic_name_
std::string vel_topic_name_
Topic name of velocity.
Definition: PosePublisher.h:95
MujocoRosUtils
Definition: ActuatorCommand.cpp:7