mujoco_ros_utils
ClockPublisher.cpp
Go to the documentation of this file.
1 #include "ClockPublisher.h"
2 
3 #include <rosgraph_msgs/Clock.h>
4 
5 #include <mujoco/mujoco.h>
6 
7 #include <iostream>
8 
9 namespace MujocoRosUtils
10 {
11 
13 {
14  mjpPlugin plugin;
15  mjp_defaultPlugin(&plugin);
16 
17  plugin.name = "MujocoRosUtils::ClockPublisher";
18  plugin.capabilityflags |= mjPLUGIN_PASSIVE;
19 
20  const char * attributes[] = {"topic_name", "publish_rate", "use_sim_time"};
21 
22  plugin.nattribute = sizeof(attributes) / sizeof(attributes[0]);
23  plugin.attributes = attributes;
24 
25  plugin.nstate = +[](const mjModel *, // m
26  int // plugin_id
27  ) { return 0; };
28 
29  plugin.nsensordata = +[](const mjModel *, // m
30  int, // plugin_id
31  int // sensor_id
32  ) { return 0; };
33 
34  plugin.needstage = mjSTAGE_POS;
35 
36  plugin.init = +[](const mjModel * m, mjData * d, int plugin_id)
37  {
38  auto * plugin_instance = ClockPublisher::Create(m, d, plugin_id);
39  if(!plugin_instance)
40  {
41  return -1;
42  }
43  d->plugin_data[plugin_id] = reinterpret_cast<uintptr_t>(plugin_instance);
44  return 0;
45  };
46 
47  plugin.destroy = +[](mjData * d, int plugin_id)
48  {
49  delete reinterpret_cast<ClockPublisher *>(d->plugin_data[plugin_id]);
50  d->plugin_data[plugin_id] = 0;
51  };
52 
53  plugin.reset = +[](const mjModel * m, double *, // plugin_state
54  void * plugin_data, int plugin_id)
55  {
56  auto * plugin_instance = reinterpret_cast<class ClockPublisher *>(plugin_data);
57  plugin_instance->reset(m, plugin_id);
58  };
59 
60  plugin.compute = +[](const mjModel * m, mjData * d, int plugin_id, int // capability_bit
61  )
62  {
63  auto * plugin_instance = reinterpret_cast<class ClockPublisher *>(d->plugin_data[plugin_id]);
64  plugin_instance->compute(m, d, plugin_id);
65  };
66 
67  mjp_registerPlugin(&plugin);
68 }
69 
70 ClockPublisher * ClockPublisher::Create(const mjModel * m, mjData * d, int plugin_id)
71 {
72  // topic_name
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)
76  {
77  topic_name = std::string(topic_name_char);
78  }
79 
80  // publish_rate
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)
84  {
85  publish_rate = strtod(publish_rate_char, nullptr);
86  }
87  if(publish_rate <= 0)
88  {
89  mju_error("[ClockPublisher] `publish_rate` must be positive.");
90  return nullptr;
91  }
92 
93  // use_sim_time
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)
97  {
98  if(!(strcmp(use_sim_time_char, "true") == 0 || strcmp(use_sim_time_char, "false") == 0))
99  {
100  mju_error("[ClockPublisher] `use_sim_time` must be `true` or `false`.");
101  return nullptr;
102  }
103  use_sim_time = (strcmp(use_sim_time_char, "true") == 0);
104  }
105 
106  if(m->body_plugin[0] != plugin_id)
107  {
108  mju_error("[ClockPublisher] This plugin must be registered in worldbody.");
109  return nullptr;
110  }
111 
112  std::cout << "[ClockPublisher] Create." << std::endl;
113 
114  return new ClockPublisher(m, d, topic_name, publish_rate, use_sim_time);
115 }
116 
118  mjData *, // d
119  const std::string & topic_name,
120  mjtNum publish_rate,
121  bool use_sim_time)
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)
124 {
125  if(topic_name_.empty())
126  {
127  topic_name_ = "/clock";
128  }
129 
130  int argc = 0;
131  char ** argv = nullptr;
132  if(!ros::isInitialized())
133  {
134  ros::init(argc, argv, "mujoco_ros", ros::init_options::NoSigintHandler);
135  }
136 
137  nh_ = std::make_shared<ros::NodeHandle>();
138  pub_ = nh_->advertise<rosgraph_msgs::Clock>(topic_name_, 1);
139  nh_->setParam("/use_sim_time", use_sim_time_);
140 }
141 
142 void ClockPublisher::reset(const mjModel *, // m
143  int // plugin_id
144 )
145 {
146 }
147 
148 void ClockPublisher::compute(const mjModel *, // m
149  mjData * d,
150  int // plugin_id
151 )
152 {
153  sim_cnt_++;
154  if(sim_cnt_ % publish_skip_ != 0)
155  {
156  return;
157  }
158 
159  rosgraph_msgs::Clock msg;
160  msg.clock.fromSec(d->time);
161  pub_.publish(msg);
162 }
163 
164 } // namespace MujocoRosUtils
MujocoRosUtils::ClockPublisher::pub_
ros::Publisher pub_
ROS publisher for clock.
Definition: ClockPublisher.h:61
MujocoRosUtils::ClockPublisher
Plugin to publish clock topic.
Definition: ClockPublisher.h:16
MujocoRosUtils::ClockPublisher::RegisterPlugin
static void RegisterPlugin()
Register plugin.
Definition: ClockPublisher.cpp:12
MujocoRosUtils::ClockPublisher::use_sim_time_
bool use_sim_time_
Value of use_sim_time rosparam.
Definition: ClockPublisher.h:70
MujocoRosUtils::ClockPublisher::compute
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
Definition: ClockPublisher.cpp:148
ClockPublisher.h
MujocoRosUtils::ClockPublisher::reset
void reset(const mjModel *m, int plugin_id)
Reset.
Definition: ClockPublisher.cpp:142
MujocoRosUtils::ClockPublisher::nh_
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
Definition: ClockPublisher.h:58
MujocoRosUtils::ClockPublisher::Create
static ClockPublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
Definition: ClockPublisher.cpp:70
MujocoRosUtils::ClockPublisher::sim_cnt_
int sim_cnt_
Iteration count of simulation.
Definition: ClockPublisher.h:73
MujocoRosUtils::ClockPublisher::topic_name_
std::string topic_name_
Topic name of clock.
Definition: ClockPublisher.h:64
MujocoRosUtils::ClockPublisher::ClockPublisher
ClockPublisher(ClockPublisher &&)=default
Copy constructor.
MujocoRosUtils
Definition: ActuatorCommand.cpp:7
MujocoRosUtils::ClockPublisher::publish_skip_
int publish_skip_
Iteration interval to skip ROS publish.
Definition: ClockPublisher.h:67