Go to the documentation of this file.
5 #include <mujoco/mjdata.h>
6 #include <mujoco/mjmodel.h>
7 #include <mujoco/mjtnum.h>
8 #include <mujoco/mjvisualize.h>
37 void reset(
const mjModel * m,
int plugin_id);
44 void compute(
const mjModel * m, mjData * d,
int plugin_id);
54 ClockPublisher(
const mjModel * m, mjData * d,
const std::string & topic_name, mjtNum publish_rate,
bool use_sim_time);
58 std::shared_ptr<ros::NodeHandle>
nh_;
ros::Publisher pub_
ROS publisher for clock.
Plugin to publish clock topic.
static void RegisterPlugin()
Register plugin.
bool use_sim_time_
Value of use_sim_time rosparam.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
void reset(const mjModel *m, int plugin_id)
Reset.
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
static ClockPublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
int sim_cnt_
Iteration count of simulation.
std::string topic_name_
Topic name of clock.
ClockPublisher(ClockPublisher &&)=default
Copy constructor.
int publish_skip_
Iteration interval to skip ROS publish.