mujoco_ros_utils
ClockPublisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 
5 #include <mujoco/mjdata.h>
6 #include <mujoco/mjmodel.h>
7 #include <mujoco/mjtnum.h>
8 #include <mujoco/mjvisualize.h>
9 
10 #include <string>
11 
12 namespace MujocoRosUtils
13 {
14 
17 {
18 public:
20  static void RegisterPlugin();
21 
27  static ClockPublisher * Create(const mjModel * m, mjData * d, int plugin_id);
28 
29 public:
31  ClockPublisher(ClockPublisher &&) = default;
32 
37  void reset(const mjModel * m, int plugin_id);
38 
44  void compute(const mjModel * m, mjData * d, int plugin_id);
45 
46 protected:
54  ClockPublisher(const mjModel * m, mjData * d, const std::string & topic_name, mjtNum publish_rate, bool use_sim_time);
55 
56 protected:
58  std::shared_ptr<ros::NodeHandle> nh_;
59 
61  ros::Publisher pub_;
62 
64  std::string topic_name_;
65 
67  int publish_skip_ = 0;
68 
70  bool use_sim_time_ = false;
71 
73  int sim_cnt_ = 0;
74 };
75 
76 } // 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
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