mujoco_ros_utils
ExternalForce.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/callback_queue.h>
4 #include <ros/ros.h>
5 
6 #include <mujoco/mjdata.h>
7 #include <mujoco/mjmodel.h>
8 #include <mujoco/mjtnum.h>
9 #include <mujoco/mjvisualize.h>
10 
11 #include <mujoco_ros_utils/ExternalForce.h>
12 #include <string>
13 
14 namespace MujocoRosUtils
15 {
16 
19 {
20 public:
22  static void RegisterPlugin();
23 
29  static ExternalForce * Create(const mjModel * m, mjData * d, int plugin_id);
30 
31 public:
33  ExternalForce(ExternalForce &&) = default;
34 
39  void reset(const mjModel * m, int plugin_id);
40 
46  void compute(const mjModel * m, mjData * d, int plugin_id);
47 
55  void visualize(const mjModel * m, mjData * d, const mjvOption * opt, mjvScene * scn, int plugin_id);
56 
57 protected:
65  ExternalForce(const mjModel * m, mjData * d, int body_id, const std::string & topic_name, mjtNum vis_scale);
66 
70  void callback(const mujoco_ros_utils::ExternalForce::ConstPtr & msg);
71 
72 protected:
74  std::shared_ptr<ros::NodeHandle> nh_;
75 
77  ros::CallbackQueue callbackQueue_;
78 
80  ros::Subscriber sub_;
81 
83  int body_id_ = -1;
84 
86  std::string topic_name_;
87 
89  std::shared_ptr<mujoco_ros_utils::ExternalForce> msg_;
90 
92  mjtNum end_time_ = -1;
93 
95  mjtNum vis_scale_;
96 };
97 
98 } // namespace MujocoRosUtils
MujocoRosUtils::ExternalForce::callback
void callback(const mujoco_ros_utils::ExternalForce::ConstPtr &msg)
Constructor.
Definition: ExternalForce.cpp:237
MujocoRosUtils::ExternalForce::compute
void compute(const mjModel *m, mjData *d, int plugin_id)
Compute.
Definition: ExternalForce.cpp:144
MujocoRosUtils::ExternalForce::Create
static ExternalForce * Create(const mjModel *m, mjData *d, int plugin_id)
Create an instance.
Definition: ExternalForce.cpp:74
MujocoRosUtils::ExternalForce
Plugin to apply external force.
Definition: ExternalForce.h:18
MujocoRosUtils::ExternalForce::RegisterPlugin
static void RegisterPlugin()
Register plugin.
Definition: ExternalForce.cpp:10
MujocoRosUtils::ExternalForce::nh_
std::shared_ptr< ros::NodeHandle > nh_
ROS node handle.
Definition: ExternalForce.h:74
MujocoRosUtils::ExternalForce::callbackQueue_
ros::CallbackQueue callbackQueue_
ROS callback queue.
Definition: ExternalForce.h:77
MujocoRosUtils::ExternalForce::visualize
void visualize(const mjModel *m, mjData *d, const mjvOption *opt, mjvScene *scn, int plugin_id)
Visualize.
Definition: ExternalForce.cpp:190
MujocoRosUtils::ExternalForce::body_id_
int body_id_
Body ID.
Definition: ExternalForce.h:83
MujocoRosUtils::ExternalForce::topic_name_
std::string topic_name_
Topic name of external force.
Definition: ExternalForce.h:86
MujocoRosUtils::ExternalForce::end_time_
mjtNum end_time_
End time to apply external force (-1 if no external force is applied)
Definition: ExternalForce.h:92
MujocoRosUtils::ExternalForce::reset
void reset(const mjModel *m, int plugin_id)
Reset.
Definition: ExternalForce.cpp:137
MujocoRosUtils::ExternalForce::vis_scale_
mjtNum vis_scale_
Arrow length scale (negative value for no visualization)
Definition: ExternalForce.h:95
MujocoRosUtils::ExternalForce::sub_
ros::Subscriber sub_
ROS publisher for external force.
Definition: ExternalForce.h:80
MujocoRosUtils::ExternalForce::ExternalForce
ExternalForce(ExternalForce &&)=default
Copy constructor.
MujocoRosUtils::ExternalForce::msg_
std::shared_ptr< mujoco_ros_utils::ExternalForce > msg_
External force message.
Definition: ExternalForce.h:89
MujocoRosUtils
Definition: ActuatorCommand.cpp:7