3 #include <rclcpp/rclcpp.hpp>
4 #include <rosgraph_msgs/msg/clock.hpp>
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
38 void reset(
const mjModel * m,
int plugin_id);
45 void compute(
const mjModel * m, mjData * d,
int plugin_id);
55 ClockPublisher(
const mjModel * m, mjData * d,
const std::string & topic_name, mjtNum publish_rate,
bool use_sim_time);
59 rclcpp::Node::SharedPtr
nh_;
62 rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr
pub_;
Plugin to publish clock topic.
void reset(const mjModel *m, int plugin_id)
Reset.
std::string topic_name_
Topic name of clock.
rclcpp::Node::SharedPtr nh_
ROS node handle.
int publish_skip_
Iteration interval to skip ROS publish.
static void RegisterPlugin()
Register plugin.
ClockPublisher(ClockPublisher &&)=default
Copy constructor.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
rclcpp::Publisher< rosgraph_msgs::msg::Clock >::SharedPtr pub_
ROS publisher for clock.
static ClockPublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
int sim_cnt_
Iteration count of simulation.
bool use_sim_time_
Value of use_sim_time rosparam.