3 #include <mujoco/mujoco.h>
13 mjp_defaultPlugin(&plugin);
15 plugin.name =
"MujocoRosUtils::ExternalForce";
16 plugin.capabilityflags |= mjPLUGIN_PASSIVE;
18 const char * attributes[] = {
"topic_name",
"vis_scale"};
20 plugin.nattribute =
sizeof(attributes) /
sizeof(attributes[0]);
21 plugin.attributes = attributes;
23 plugin.nstate = +[](
const mjModel *,
27 plugin.nsensordata = +[](
const mjModel *,
32 plugin.needstage = mjSTAGE_ACC;
34 plugin.init = +[](
const mjModel * m, mjData * d,
int plugin_id)
41 d->plugin_data[plugin_id] =
reinterpret_cast<uintptr_t
>(plugin_instance);
45 plugin.destroy = +[](mjData * d,
int plugin_id)
47 delete reinterpret_cast<ExternalForce *
>(d->plugin_data[plugin_id]);
48 d->plugin_data[plugin_id] = 0;
51 plugin.
reset = +[](
const mjModel * m,
double *,
52 void * plugin_data,
int plugin_id)
54 auto * plugin_instance =
reinterpret_cast<class
ExternalForce *
>(plugin_data);
55 plugin_instance->
reset(m, plugin_id);
58 plugin.compute = +[](
const mjModel * m, mjData * d,
int plugin_id,
int
61 auto * plugin_instance =
reinterpret_cast<class
ExternalForce *
>(d->plugin_data[plugin_id]);
62 plugin_instance->
compute(m, d, plugin_id);
65 plugin.visualize = +[](
const mjModel * m, mjData * d,
const mjvOption * opt, mjvScene * scn,
int plugin_id)
67 auto * plugin_instance =
reinterpret_cast<class
ExternalForce *
>(d->plugin_data[plugin_id]);
68 plugin_instance->
visualize(m, d, opt, scn, plugin_id);
71 mjp_registerPlugin(&plugin);
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)
81 topic_name = std::string(topic_name_char);
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)
89 vis_scale = strtod(vis_scale_char,
nullptr);
94 for(; body_id < m->nbody; body_id++)
96 if(m->body_plugin[body_id] == plugin_id)
101 if(body_id == m->nbody)
103 mju_error(
"[ExternalForce] Plugin not found in bodies.");
107 std::cout <<
"[ExternalForce] Create." << std::endl;
109 return new ExternalForce(m, d, body_id, topic_name, vis_scale);
115 const std::string & topic_name,
117 : body_id_(body_id), topic_name_(topic_name), vis_scale_(vis_scale)
125 char ** argv =
nullptr;
126 if(!ros::isInitialized())
128 ros::init(argc, argv,
"mujoco_ros", ros::init_options::NoSigintHandler);
131 nh_ = std::make_shared<ros::NodeHandle>();
152 if(
end_time_ >= 0 && end_time_ <= d->time)
164 pos_local[0] =
msg_->pos.x;
165 pos_local[1] =
msg_->pos.y;
166 pos_local[2] =
msg_->pos.z;
168 force[0] =
msg_->force.x;
169 force[1] =
msg_->force.y;
170 force[2] =
msg_->force.z;
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_);
177 mju_cross(moment, moment_arm, force);
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);
210 pos_local[0] =
msg_->pos.x;
211 pos_local[1] =
msg_->pos.y;
212 pos_local[2] =
msg_->pos.z;
214 force[0] =
msg_->force.x;
215 force[1] =
msg_->force.y;
216 force[2] =
msg_->force.z;
218 mju_rotVecMat(pos_world, pos_local, d->xmat + 9 *
body_id_);
219 mju_addTo3(pos_world, d->xpos + 3 *
body_id_);
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;
241 mju_warning(
"[ExternalForce] New message received while processing a previous message. Ignore the new message.");
244 msg_ = std::make_shared<mujoco_ros_utils::ExternalForce>(*msg);