mujoco_ros_utils
ClockPublisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <rclcpp/rclcpp.hpp>
4 #include <rosgraph_msgs/msg/clock.hpp>
5 
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
10 
11 #include <string>
12 
13 namespace MujocoRosUtils
14 {
15 
18 {
19 public:
21  static void RegisterPlugin();
22 
28  static ClockPublisher * Create(const mjModel * m, mjData * d, int plugin_id);
29 
30 public:
33 
38  void reset(const mjModel * m, int plugin_id);
39 
45  void compute(const mjModel * m, mjData * d, int plugin_id);
46 
47 protected:
55  ClockPublisher(const mjModel * m, mjData * d, const std::string & topic_name, mjtNum publish_rate, bool use_sim_time);
56 
57 protected:
59  rclcpp::Node::SharedPtr nh_;
60 
62  rclcpp::Publisher<rosgraph_msgs::msg::Clock>::SharedPtr pub_;
63 
65  std::string topic_name_;
66 
68  int publish_skip_ = 0;
69 
71  bool use_sim_time_ = false;
72 
74  int sim_cnt_ = 0;
75 };
76 
77 } // namespace MujocoRosUtils
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.