Go to the documentation of this file.
3 #include <ros/callback_queue.h>
5 #include <std_msgs/Float64.h>
7 #include <mujoco/mjdata.h>
8 #include <mujoco/mjmodel.h>
9 #include <mujoco/mjtnum.h>
10 #include <mujoco/mjvisualize.h>
40 void reset(
const mjModel * m,
int plugin_id);
47 void compute(
const mjModel * m, mjData * d,
int plugin_id);
56 ActuatorCommand(
const mjModel * m, mjData * d,
int actuator_id, std::string topic_name);
61 void callback(
const std_msgs::Float64::ConstPtr & msg);
68 mjtNum
ctrl_ = std::numeric_limits<mjtNum>::quiet_NaN();
72 std::shared_ptr<ros::NodeHandle>
nh_;
mjtNum ctrl_
Actuator command (NaN for no command)
ActuatorCommand(ActuatorCommand &&)=default
Copy constructor.
static ActuatorCommand * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
void reset(const mjModel *m, int plugin_id)
Reset.
std::shared_ptr< ros::NodeHandle > nh_
void callback(const std_msgs::Float64::ConstPtr &msg)
Constructor.
ros::CallbackQueue callbackQueue_
Plugin to send a command to an actuator via ROS topic.
int actuator_id_
Actuator ID.
static void RegisterPlugin()
Register plugin.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.