Go to the documentation of this file.
3 #include <ros/callback_queue.h>
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
11 #include <mujoco_ros_utils/ExternalForce.h>
39 void reset(
const mjModel * m,
int plugin_id);
46 void compute(
const mjModel * m, mjData * d,
int plugin_id);
55 void visualize(
const mjModel * m, mjData * d,
const mjvOption * opt, mjvScene * scn,
int plugin_id);
65 ExternalForce(
const mjModel * m, mjData * d,
int body_id,
const std::string & topic_name, mjtNum vis_scale);
70 void callback(
const mujoco_ros_utils::ExternalForce::ConstPtr & msg);
74 std::shared_ptr<ros::NodeHandle>
nh_;
89 std::shared_ptr<mujoco_ros_utils::ExternalForce>
msg_;
void callback(const mujoco_ros_utils::ExternalForce::ConstPtr &msg)
Constructor.
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
static ExternalForce * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
Plugin to apply external force.
static void RegisterPlugin()
Register plugin.
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
ros::CallbackQueue callbackQueue_
ROS callback queue.
void visualize(const mjModel *m, mjData *d, const mjvOption *opt, mjvScene *scn, int plugin_id)
Visualize.
std::string topic_name_
Topic name of external force.
mjtNum end_time_
End time to apply external force (-1 if no external force is applied)
void reset(const mjModel *m, int plugin_id)
Reset.
mjtNum vis_scale_
Arrow length scale (negative value for no visualization)
ros::Subscriber sub_
ROS publisher for external force.
ExternalForce(ExternalForce &&)=default
Copy constructor.
std::shared_ptr< mujoco_ros_utils::ExternalForce > msg_
External force message.