mujoco_ros_utils
SensorPublisher.cpp
Go to the documentation of this file.
1 #include "SensorPublisher.h"
2 
3 #include <geometry_msgs/PointStamped.h>
4 #include <geometry_msgs/QuaternionStamped.h>
5 #include <geometry_msgs/Vector3Stamped.h>
6 
7 #include <mujoco/mujoco.h>
8 
9 #include <iostream>
10 #include <mujoco_ros_utils/ScalarStamped.h>
11 
12 namespace MujocoRosUtils
13 {
14 
16 {
17  mjpPlugin plugin;
18  mjp_defaultPlugin(&plugin);
19 
20  plugin.name = "MujocoRosUtils::SensorPublisher";
21  plugin.capabilityflags |= mjPLUGIN_SENSOR;
22 
23  const char * attributes[] = {"sensor_name", "frame_id", "topic_name", "publish_rate"};
24 
25  plugin.nattribute = sizeof(attributes) / sizeof(attributes[0]);
26  plugin.attributes = attributes;
27 
28  plugin.nstate = +[](const mjModel *, // m
29  int // plugin_id
30  ) { return 0; };
31 
32  plugin.nsensordata = +[](const mjModel *, // m
33  int, // plugin_id
34  int // sensor_id
35  ) { return 0; };
36 
37  // Can only run after forces have been computed
38  plugin.needstage = mjSTAGE_ACC;
39 
40  plugin.init = +[](const mjModel * m, mjData * d, int plugin_id)
41  {
42  auto * plugin_instance = SensorPublisher::Create(m, d, plugin_id);
43  if(!plugin_instance)
44  {
45  return -1;
46  }
47  d->plugin_data[plugin_id] = reinterpret_cast<uintptr_t>(plugin_instance);
48  return 0;
49  };
50 
51  plugin.destroy = +[](mjData * d, int plugin_id)
52  {
53  delete reinterpret_cast<SensorPublisher *>(d->plugin_data[plugin_id]);
54  d->plugin_data[plugin_id] = 0;
55  };
56 
57  plugin.reset = +[](const mjModel * m, double *, // plugin_state
58  void * plugin_data, int plugin_id)
59  {
60  auto * plugin_instance = reinterpret_cast<class SensorPublisher *>(plugin_data);
61  plugin_instance->reset(m, plugin_id);
62  };
63 
64  plugin.compute = +[](const mjModel * m, mjData * d, int plugin_id, int // capability_bit
65  )
66  {
67  auto * plugin_instance = reinterpret_cast<class SensorPublisher *>(d->plugin_data[plugin_id]);
68  plugin_instance->compute(m, d, plugin_id);
69  };
70 
71  mjp_registerPlugin(&plugin);
72 }
73 
74 SensorPublisher * SensorPublisher::Create(const mjModel * m, mjData * d, int plugin_id)
75 {
76  // sensor_name
77  const char * sensor_name_char = mj_getPluginConfig(m, plugin_id, "sensor_name");
78  if(strlen(sensor_name_char) == 0)
79  {
80  mju_error("[SensorPublisher] `sensor_name` is missing.");
81  return nullptr;
82  }
83  int sensor_id = 0;
84  for(; sensor_id < m->nsensor; sensor_id++)
85  {
86  if(strcmp(sensor_name_char, mj_id2name(m, mjOBJ_SENSOR, sensor_id)) == 0)
87  {
88  break;
89  }
90  }
91  if(sensor_id == m->nsensor)
92  {
93  mju_error("[SensorCommand] The sensor with the specified name not found.");
94  return nullptr;
95  }
96 
97  // msg_type
98  MessageType msg_type;
99  int sensor_dim = m->sensor_dim[sensor_id];
100  if(sensor_dim == 1)
101  {
102  msg_type = MsgScalar;
103  }
104  else if(sensor_dim == 3)
105  {
106  if(m->sensor_type[sensor_id] == mjSENS_FRAMEPOS)
107  {
108  msg_type = MsgPoint;
109  }
110  else
111  {
112  msg_type = MsgVector3;
113  }
114  }
115  else if(sensor_dim == 4)
116  {
117  msg_type = MsgQuaternion;
118  }
119  else
120  {
121  mju_error("[SensorPublisher] Unsupported sensor data dimensions: %d.", sensor_dim);
122  return nullptr;
123  }
124 
125  // frame_id
126  const char * frame_id_char = mj_getPluginConfig(m, plugin_id, "frame_id");
127  std::string frame_id = "";
128  if(strlen(frame_id_char) > 0)
129  {
130  frame_id = std::string(frame_id_char);
131  }
132 
133  // topic_name
134  const char * topic_name_char = mj_getPluginConfig(m, plugin_id, "topic_name");
135  std::string topic_name = "";
136  if(strlen(topic_name_char) > 0)
137  {
138  topic_name = std::string(topic_name_char);
139  }
140 
141  // publish_rate
142  const char * publish_rate_char = mj_getPluginConfig(m, plugin_id, "publish_rate");
143  mjtNum publish_rate = 30.0;
144  if(strlen(publish_rate_char) > 0)
145  {
146  publish_rate = strtod(publish_rate_char, nullptr);
147  }
148  if(publish_rate <= 0)
149  {
150  mju_error("[SensorPublisher] `publish_rate` must be positive.");
151  return nullptr;
152  }
153 
154  std::cout << "[SensorPublisher] Create." << std::endl;
155 
156  return new SensorPublisher(m, d, sensor_id, msg_type, frame_id, topic_name, publish_rate);
157 }
158 
160  mjData *, // d
161  int sensor_id,
162  MessageType msg_type,
163  const std::string & frame_id,
164  const std::string & topic_name,
165  mjtNum publish_rate)
166 : sensor_id_(sensor_id), msg_type_(msg_type), frame_id_(frame_id), topic_name_(topic_name),
167  publish_skip_(std::max(static_cast<int>(1.0 / (publish_rate * m->opt.timestep)), 1))
168 {
169  if(frame_id_.empty())
170  {
171  frame_id_ = "map";
172  }
173  if(topic_name_.empty())
174  {
175  std::string sensor_name = std::string(mj_id2name(m, mjOBJ_SENSOR, sensor_id_));
176  topic_name_ = "mujoco/" + sensor_name;
177  }
178 
179  int argc = 0;
180  char ** argv = nullptr;
181  if(!ros::isInitialized())
182  {
183  ros::init(argc, argv, "mujoco_ros", ros::init_options::NoSigintHandler);
184  }
185 
186  nh_ = std::make_shared<ros::NodeHandle>();
187  if(msg_type_ == MsgScalar)
188  {
189  pub_ = nh_->advertise<mujoco_ros_utils::ScalarStamped>(topic_name_, 1);
190  }
191  else if(msg_type_ == MsgPoint)
192  {
193  pub_ = nh_->advertise<geometry_msgs::PointStamped>(topic_name_, 1);
194  }
195  else if(msg_type_ == MsgVector3)
196  {
197  pub_ = nh_->advertise<geometry_msgs::Vector3Stamped>(topic_name_, 1);
198  }
199  else // if(msg_type_ == MsgQuaternion)
200  {
201  pub_ = nh_->advertise<geometry_msgs::QuaternionStamped>(topic_name_, 1);
202  }
203 }
204 
205 void SensorPublisher::reset(const mjModel *, // m
206  int // plugin_id
207 )
208 {
209 }
210 
211 void SensorPublisher::compute(const mjModel * m, mjData * d, int // plugin_id
212 )
213 {
214  sim_cnt_++;
215  if(sim_cnt_ % publish_skip_ != 0)
216  {
217  return;
218  }
219 
220  std_msgs::Header header;
221  header.stamp = ros::Time::now();
222  header.frame_id = frame_id_;
223 
224  int sensor_adr = m->sensor_adr[sensor_id_];
225  if(msg_type_ == MsgScalar)
226  {
227  mujoco_ros_utils::ScalarStamped msg;
228  msg.header = header;
229  msg.value = d->sensordata[sensor_adr];
230  pub_.publish(msg);
231  }
232  else if(msg_type_ == MsgPoint)
233  {
234  geometry_msgs::PointStamped msg;
235  msg.header = header;
236  msg.point.x = d->sensordata[sensor_adr + 0];
237  msg.point.y = d->sensordata[sensor_adr + 1];
238  msg.point.z = d->sensordata[sensor_adr + 2];
239  pub_.publish(msg);
240  }
241  else if(msg_type_ == MsgVector3)
242  {
243  geometry_msgs::Vector3Stamped msg;
244  msg.header = header;
245  msg.vector.x = d->sensordata[sensor_adr + 0];
246  msg.vector.y = d->sensordata[sensor_adr + 1];
247  msg.vector.z = d->sensordata[sensor_adr + 2];
248  pub_.publish(msg);
249  }
250  else // if(msg_type_ == MsgQuaternion)
251  {
252  geometry_msgs::QuaternionStamped msg;
253  msg.header = header;
254  msg.quaternion.w = d->sensordata[sensor_adr + 0];
255  msg.quaternion.x = d->sensordata[sensor_adr + 1];
256  msg.quaternion.y = d->sensordata[sensor_adr + 2];
257  msg.quaternion.z = d->sensordata[sensor_adr + 3];
258  pub_.publish(msg);
259  }
260 }
261 
262 } // namespace MujocoRosUtils
MujocoRosUtils::SensorPublisher::nh_
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
Definition: SensorPublisher.h:95
MujocoRosUtils::SensorPublisher::SensorPublisher
SensorPublisher(SensorPublisher &&)=default
Copy constructor.
MujocoRosUtils::SensorPublisher::msg_type_
MessageType msg_type_
Type of ROS message.
Definition: SensorPublisher.h:86
MujocoRosUtils::SensorPublisher::frame_id_
std::string frame_id_
Frame ID of message header.
Definition: SensorPublisher.h:89
MujocoRosUtils::SensorPublisher::MsgScalar
@ MsgScalar
Scalar.
Definition: SensorPublisher.h:23
MujocoRosUtils::SensorPublisher::topic_name_
std::string topic_name_
Topic name.
Definition: SensorPublisher.h:92
MujocoRosUtils::SensorPublisher::MessageType
enum MujocoRosUtils::SensorPublisher::MessageType_ MessageType
Type of ROS message.
MujocoRosUtils::SensorPublisher::pub_
ros::Publisher pub_
ROS publisher.
Definition: SensorPublisher.h:98
MujocoRosUtils::SensorPublisher::compute
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
Definition: SensorPublisher.cpp:211
MujocoRosUtils::SensorPublisher::sim_cnt_
int sim_cnt_
Iteration count of simulation.
Definition: SensorPublisher.h:104
MujocoRosUtils::SensorPublisher::publish_skip_
int publish_skip_
Iteration interval to skip ROS publish.
Definition: SensorPublisher.h:101
MujocoRosUtils::SensorPublisher::reset
void reset(const mjModel *m, int plugin_id)
Reset.
Definition: SensorPublisher.cpp:205
MujocoRosUtils::SensorPublisher::MsgPoint
@ MsgPoint
Point.
Definition: SensorPublisher.h:26
MujocoRosUtils::SensorPublisher::MsgVector3
@ MsgVector3
3D vector
Definition: SensorPublisher.h:29
MujocoRosUtils::SensorPublisher::sensor_id_
int sensor_id_
Sensor ID.
Definition: SensorPublisher.h:83
SensorPublisher.h
MujocoRosUtils::SensorPublisher::RegisterPlugin
static void RegisterPlugin()
Register plugin.
Definition: SensorPublisher.cpp:15
MujocoRosUtils::SensorPublisher
Plugin to publish sensor data.
Definition: SensorPublisher.h:16
MujocoRosUtils::SensorPublisher::MsgQuaternion
@ MsgQuaternion
Quaternion.
Definition: SensorPublisher.h:32
MujocoRosUtils
Definition: ActuatorCommand.cpp:7
MujocoRosUtils::SensorPublisher::Create
static SensorPublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
Definition: SensorPublisher.cpp:74