3 #include <geometry_msgs/PointStamped.h>
4 #include <geometry_msgs/QuaternionStamped.h>
5 #include <geometry_msgs/Vector3Stamped.h>
7 #include <mujoco/mujoco.h>
10 #include <mujoco_ros_utils/ScalarStamped.h>
18 mjp_defaultPlugin(&plugin);
20 plugin.name =
"MujocoRosUtils::SensorPublisher";
21 plugin.capabilityflags |= mjPLUGIN_SENSOR;
23 const char * attributes[] = {
"sensor_name",
"frame_id",
"topic_name",
"publish_rate"};
25 plugin.nattribute =
sizeof(attributes) /
sizeof(attributes[0]);
26 plugin.attributes = attributes;
28 plugin.nstate = +[](
const mjModel *,
32 plugin.nsensordata = +[](
const mjModel *,
38 plugin.needstage = mjSTAGE_ACC;
40 plugin.init = +[](
const mjModel * m, mjData * d,
int plugin_id)
47 d->plugin_data[plugin_id] =
reinterpret_cast<uintptr_t
>(plugin_instance);
51 plugin.destroy = +[](mjData * d,
int plugin_id)
54 d->plugin_data[plugin_id] = 0;
57 plugin.
reset = +[](
const mjModel * m,
double *,
58 void * plugin_data,
int plugin_id)
60 auto * plugin_instance =
reinterpret_cast<class
SensorPublisher *
>(plugin_data);
61 plugin_instance->
reset(m, plugin_id);
64 plugin.compute = +[](
const mjModel * m, mjData * d,
int plugin_id,
int
67 auto * plugin_instance =
reinterpret_cast<class
SensorPublisher *
>(d->plugin_data[plugin_id]);
68 plugin_instance->
compute(m, d, plugin_id);
71 mjp_registerPlugin(&plugin);
77 const char * sensor_name_char = mj_getPluginConfig(m, plugin_id,
"sensor_name");
78 if(strlen(sensor_name_char) == 0)
80 mju_error(
"[SensorPublisher] `sensor_name` is missing.");
84 for(; sensor_id < m->nsensor; sensor_id++)
86 if(strcmp(sensor_name_char, mj_id2name(m, mjOBJ_SENSOR, sensor_id)) == 0)
91 if(sensor_id == m->nsensor)
93 mju_error(
"[SensorCommand] The sensor with the specified name not found.");
99 int sensor_dim = m->sensor_dim[sensor_id];
104 else if(sensor_dim == 3)
106 if(m->sensor_type[sensor_id] == mjSENS_FRAMEPOS)
115 else if(sensor_dim == 4)
121 mju_error(
"[SensorPublisher] Unsupported sensor data dimensions: %d.", sensor_dim);
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)
130 frame_id = std::string(frame_id_char);
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)
138 topic_name = std::string(topic_name_char);
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)
146 publish_rate = strtod(publish_rate_char,
nullptr);
148 if(publish_rate <= 0)
150 mju_error(
"[SensorPublisher] `publish_rate` must be positive.");
154 std::cout <<
"[SensorPublisher] Create." << std::endl;
156 return new SensorPublisher(m, d, sensor_id, msg_type, frame_id, topic_name, publish_rate);
163 const std::string & frame_id,
164 const std::string & topic_name,
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))
175 std::string sensor_name = std::string(mj_id2name(m, mjOBJ_SENSOR,
sensor_id_));
180 char ** argv =
nullptr;
181 if(!ros::isInitialized())
183 ros::init(argc, argv,
"mujoco_ros", ros::init_options::NoSigintHandler);
186 nh_ = std::make_shared<ros::NodeHandle>();
220 std_msgs::Header header;
221 header.stamp = ros::Time::now();
227 mujoco_ros_utils::ScalarStamped msg;
229 msg.value = d->sensordata[sensor_adr];
234 geometry_msgs::PointStamped msg;
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];
243 geometry_msgs::Vector3Stamped msg;
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];
252 geometry_msgs::QuaternionStamped msg;
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];