mujoco_ros_utils
ExternalForce.cpp
Go to the documentation of this file.
1 #include "ExternalForce.h"
2 
3 #include <mujoco/mujoco.h>
4 
5 #include <iostream>
6 
7 namespace MujocoRosUtils
8 {
9 
11 {
12  mjpPlugin plugin;
13  mjp_defaultPlugin(&plugin);
14 
15  plugin.name = "MujocoRosUtils::ExternalForce";
16  plugin.capabilityflags |= mjPLUGIN_PASSIVE;
17 
18  const char * attributes[] = {"topic_name", "vis_scale"};
19 
20  plugin.nattribute = sizeof(attributes) / sizeof(attributes[0]);
21  plugin.attributes = attributes;
22 
23  plugin.nstate = +[](const mjModel *, // m
24  int // plugin_id
25  ) { return 0; };
26 
27  plugin.nsensordata = +[](const mjModel *, // m
28  int, // plugin_id
29  int // sensor_id
30  ) { return 0; };
31 
32  plugin.needstage = mjSTAGE_ACC;
33 
34  plugin.init = +[](const mjModel * m, mjData * d, int plugin_id)
35  {
36  auto * plugin_instance = ExternalForce::Create(m, d, plugin_id);
37  if(!plugin_instance)
38  {
39  return -1;
40  }
41  d->plugin_data[plugin_id] = reinterpret_cast<uintptr_t>(plugin_instance);
42  return 0;
43  };
44 
45  plugin.destroy = +[](mjData * d, int plugin_id)
46  {
47  delete reinterpret_cast<ExternalForce *>(d->plugin_data[plugin_id]);
48  d->plugin_data[plugin_id] = 0;
49  };
50 
51  plugin.reset = +[](const mjModel * m, double *, // plugin_state
52  void * plugin_data, int plugin_id)
53  {
54  auto * plugin_instance = reinterpret_cast<class ExternalForce *>(plugin_data);
55  plugin_instance->reset(m, plugin_id);
56  };
57 
58  plugin.compute = +[](const mjModel * m, mjData * d, int plugin_id, int // capability_bit
59  )
60  {
61  auto * plugin_instance = reinterpret_cast<class ExternalForce *>(d->plugin_data[plugin_id]);
62  plugin_instance->compute(m, d, plugin_id);
63  };
64 
65  plugin.visualize = +[](const mjModel * m, mjData * d, const mjvOption * opt, mjvScene * scn, int plugin_id)
66  {
67  auto * plugin_instance = reinterpret_cast<class ExternalForce *>(d->plugin_data[plugin_id]);
68  plugin_instance->visualize(m, d, opt, scn, plugin_id);
69  };
70 
71  mjp_registerPlugin(&plugin);
72 }
73 
74 ExternalForce * ExternalForce::Create(const mjModel * m, mjData * d, int plugin_id)
75 {
76  // topic_name
77  const char * topic_name_char = mj_getPluginConfig(m, plugin_id, "topic_name");
78  std::string topic_name = "";
79  if(strlen(topic_name_char) > 0)
80  {
81  topic_name = std::string(topic_name_char);
82  }
83 
84  // vis_scale
85  const char * vis_scale_char = mj_getPluginConfig(m, plugin_id, "vis_scale");
86  mjtNum vis_scale = 0.1;
87  if(strlen(vis_scale_char) > 0)
88  {
89  vis_scale = strtod(vis_scale_char, nullptr);
90  }
91 
92  // Set body_id
93  int body_id = 0;
94  for(; body_id < m->nbody; body_id++)
95  {
96  if(m->body_plugin[body_id] == plugin_id)
97  {
98  break;
99  }
100  }
101  if(body_id == m->nbody)
102  {
103  mju_error("[ExternalForce] Plugin not found in bodies.");
104  return nullptr;
105  }
106 
107  std::cout << "[ExternalForce] Create." << std::endl;
108 
109  return new ExternalForce(m, d, body_id, topic_name, vis_scale);
110 }
111 
112 ExternalForce::ExternalForce(const mjModel *, // m
113  mjData *, // d
114  int body_id,
115  const std::string & topic_name,
116  mjtNum vis_scale)
117 : body_id_(body_id), topic_name_(topic_name), vis_scale_(vis_scale)
118 {
119  if(topic_name_.empty())
120  {
121  topic_name_ = "/external_force";
122  }
123 
124  int argc = 0;
125  char ** argv = nullptr;
126  if(!ros::isInitialized())
127  {
128  ros::init(argc, argv, "mujoco_ros", ros::init_options::NoSigintHandler);
129  }
130 
131  nh_ = std::make_shared<ros::NodeHandle>();
132  // Use a dedicated queue so as not to call callbacks of other modules
133  nh_->setCallbackQueue(&callbackQueue_);
134  sub_ = nh_->subscribe<mujoco_ros_utils::ExternalForce>(topic_name_, 1, &ExternalForce::callback, this);
135 }
136 
137 void ExternalForce::reset(const mjModel *, // m
138  int // plugin_id
139 )
140 {
141  msg_ = nullptr;
142 }
143 
144 void ExternalForce::compute(const mjModel *, // m
145  mjData * d,
146  int // plugin_id
147 )
148 {
149  // Call ROS callback
150  callbackQueue_.callAvailable(ros::WallDuration());
151 
152  if(end_time_ >= 0 && end_time_ <= d->time)
153  {
154  end_time_ = -1;
155  msg_ = nullptr;
156  }
157 
158  if(!msg_)
159  {
160  return;
161  }
162 
163  mjtNum pos_local[3];
164  pos_local[0] = msg_->pos.x;
165  pos_local[1] = msg_->pos.y;
166  pos_local[2] = msg_->pos.z;
167  mjtNum force[3];
168  force[0] = msg_->force.x;
169  force[1] = msg_->force.y;
170  force[2] = msg_->force.z;
171  mjtNum pos_world[3];
172  mju_rotVecMat(pos_world, pos_local, d->xmat + 9 * body_id_);
173  mju_addTo3(pos_world, d->xpos + 3 * body_id_);
174  mjtNum moment_arm[3];
175  mju_sub3(moment_arm, pos_world, d->xipos + 3 * body_id_);
176  mjtNum moment[3];
177  mju_cross(moment, moment_arm, force);
178 
179  mjtNum * data_force = d->xfrc_applied + 6 * body_id_;
180  mjtNum * data_moment = d->xfrc_applied + 6 * body_id_ + 3;
181  mju_copy3(data_force, force);
182  mju_copy3(data_moment, moment);
183 
184  if(end_time_ < 0)
185  {
186  end_time_ = d->time + msg_->duration.toSec();
187  }
188 }
189 
190 void ExternalForce::visualize(const mjModel *, // m
191  mjData * d,
192  const mjvOption *, // opt
193  mjvScene * scn,
194  int // plugin_id
195 )
196 {
197  if(!msg_)
198  {
199  return;
200  }
201 
202  if(vis_scale_ <= 0)
203  {
204  return;
205  }
206 
207  mjMARKSTACK;
208 
209  mjtNum pos_local[3];
210  pos_local[0] = msg_->pos.x;
211  pos_local[1] = msg_->pos.y;
212  pos_local[2] = msg_->pos.z;
213  mjtNum force[3];
214  force[0] = msg_->force.x;
215  force[1] = msg_->force.y;
216  force[2] = msg_->force.z;
217  mjtNum pos_world[3];
218  mju_rotVecMat(pos_world, pos_local, d->xmat + 9 * body_id_);
219  mju_addTo3(pos_world, d->xpos + 3 * body_id_);
220  mjtNum arrow_end[3];
221  mju_addScl3(arrow_end, pos_world, force, vis_scale_);
222  float rgba[4] = {1.0, 0.0, 0.0, 1.0};
223  constexpr mjtNum width = 0.01;
224  mjvGeom * force_geom = scn->geoms + scn->ngeom;
225  mjv_initGeom(force_geom, mjGEOM_NONE, NULL, NULL, NULL, rgba);
226  mjv_makeConnector(force_geom, mjGEOM_ARROW, width, pos_world[0], pos_world[1], pos_world[2], arrow_end[0],
227  arrow_end[1], arrow_end[2]);
228  force_geom->objtype = mjOBJ_UNKNOWN;
229  force_geom->objid = -1;
230  force_geom->category = mjCAT_DECOR;
231  force_geom->segid = scn->ngeom;
232  scn->ngeom++;
233 
234  mjFREESTACK;
235 }
236 
237 void ExternalForce::callback(const mujoco_ros_utils::ExternalForce::ConstPtr & msg)
238 {
239  if(end_time_ > 0)
240  {
241  mju_warning("[ExternalForce] New message received while processing a previous message. Ignore the new message.");
242  return;
243  }
244  msg_ = std::make_shared<mujoco_ros_utils::ExternalForce>(*msg);
245 }
246 
247 } // 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
ExternalForce.h
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