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>
54 void reset(
const mjModel * m,
int plugin_id);
61 void compute(
const mjModel * m, mjData * d,
int plugin_id);
77 const std::string & frame_id,
78 const std::string & topic_name,
95 std::shared_ptr<ros::NodeHandle>
nh_;
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
SensorPublisher(SensorPublisher &&)=default
Copy constructor.
MessageType msg_type_
Type of ROS message.
std::string frame_id_
Frame ID of message header.
std::string topic_name_
Topic name.
enum MujocoRosUtils::SensorPublisher::MessageType_ MessageType
Type of ROS message.
ros::Publisher pub_
ROS publisher.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
int sim_cnt_
Iteration count of simulation.
int publish_skip_
Iteration interval to skip ROS publish.
void reset(const mjModel *m, int plugin_id)
Reset.
static void RegisterPlugin()
Register plugin.
Plugin to publish sensor data.
@ MsgQuaternion
Quaternion.
MessageType_
Type of ROS message.
static SensorPublisher * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.