3 #include <rosgraph_msgs/Clock.h>
5 #include <mujoco/mujoco.h>
15 mjp_defaultPlugin(&plugin);
17 plugin.name =
"MujocoRosUtils::ClockPublisher";
18 plugin.capabilityflags |= mjPLUGIN_PASSIVE;
20 const char * attributes[] = {
"topic_name",
"publish_rate",
"use_sim_time"};
22 plugin.nattribute =
sizeof(attributes) /
sizeof(attributes[0]);
23 plugin.attributes = attributes;
25 plugin.nstate = +[](
const mjModel *,
29 plugin.nsensordata = +[](
const mjModel *,
34 plugin.needstage = mjSTAGE_POS;
36 plugin.init = +[](
const mjModel * m, mjData * d,
int plugin_id)
43 d->plugin_data[plugin_id] =
reinterpret_cast<uintptr_t
>(plugin_instance);
47 plugin.destroy = +[](mjData * d,
int plugin_id)
49 delete reinterpret_cast<ClockPublisher *
>(d->plugin_data[plugin_id]);
50 d->plugin_data[plugin_id] = 0;
53 plugin.
reset = +[](
const mjModel * m,
double *,
54 void * plugin_data,
int plugin_id)
56 auto * plugin_instance =
reinterpret_cast<class
ClockPublisher *
>(plugin_data);
57 plugin_instance->
reset(m, plugin_id);
60 plugin.compute = +[](
const mjModel * m, mjData * d,
int plugin_id,
int
63 auto * plugin_instance =
reinterpret_cast<class
ClockPublisher *
>(d->plugin_data[plugin_id]);
64 plugin_instance->
compute(m, d, plugin_id);
67 mjp_registerPlugin(&plugin);
73 const char * topic_name_char = mj_getPluginConfig(m, plugin_id,
"topic_name");
74 std::string topic_name =
"";
75 if(strlen(topic_name_char) > 0)
77 topic_name = std::string(topic_name_char);
81 const char * publish_rate_char = mj_getPluginConfig(m, plugin_id,
"publish_rate");
82 mjtNum publish_rate = 100.0;
83 if(strlen(publish_rate_char) > 0)
85 publish_rate = strtod(publish_rate_char,
nullptr);
89 mju_error(
"[ClockPublisher] `publish_rate` must be positive.");
94 const char * use_sim_time_char = mj_getPluginConfig(m, plugin_id,
"use_sim_time");
95 bool use_sim_time =
true;
96 if(strlen(use_sim_time_char) > 0)
98 if(!(strcmp(use_sim_time_char,
"true") == 0 || strcmp(use_sim_time_char,
"false") == 0))
100 mju_error(
"[ClockPublisher] `use_sim_time` must be `true` or `false`.");
103 use_sim_time = (strcmp(use_sim_time_char,
"true") == 0);
106 if(m->body_plugin[0] != plugin_id)
108 mju_error(
"[ClockPublisher] This plugin must be registered in worldbody.");
112 std::cout <<
"[ClockPublisher] Create." << std::endl;
114 return new ClockPublisher(m, d, topic_name, publish_rate, use_sim_time);
119 const std::string & topic_name,
122 : topic_name_(topic_name), publish_skip_(std::max(static_cast<int>(1.0 / (publish_rate * m->opt.timestep)), 1)),
123 use_sim_time_(use_sim_time)
131 char ** argv =
nullptr;
132 if(!ros::isInitialized())
134 ros::init(argc, argv,
"mujoco_ros", ros::init_options::NoSigintHandler);
137 nh_ = std::make_shared<ros::NodeHandle>();
159 rosgraph_msgs::Clock msg;
160 msg.clock.fromSec(d->time);