58 invisible.color.a = 0.0;
59 vec.resize(max_size, invisible);
68 auto ee_pos = state.ee_motion_.Get(
kPos);
73 msg.markers.push_back(base);
77 msg.markers.insert(msg.markers.begin(), m_ee_pos.begin(), m_ee_pos.end());
81 msg.markers.insert(msg.markers.begin(), ee_forces.begin(), ee_forces.end());
85 msg.markers.insert(msg.markers.begin(), rom.begin(), rom.end());
89 msg.markers.insert(msg.markers.begin(), support.begin(), support.end());
93 msg.markers.insert(msg.markers.begin(), friction.begin(), friction.end());
96 msg.markers.push_back(cop);
99 msg.markers.push_back(ip);
104 for (
Marker& m : msg.markers) {
114 const ContactState& in_contact)
const
118 for (
auto ee : ee_pos.GetEEsOrdered()) {
120 m.ns =
"endeffector_pos";
136 m.ns =
"gravity_force";
154 m.color.a =
f.norm() > 0.1 ? 1.0 : 0.0;
164 const ContactState& contact_state)
const
170 invisible.color.a = 0.0;
171 vec.push_back(invisible);
175 if (ee_pos.GetEECount() ==
terrain_msg_.surface_normals.size() && mu > 1e-3) {
178 for (
auto ee : normals.GetEEsOrdered()) {
183 m.color.a = contact_state.at(ee)? 0.25 : 0.0;
197 m.type = Marker::ARROW;
198 m.ns =
"friction_cone";
200 double cone_height = 0.1;
203 m.scale.y = 2.0 * cone_height * mu;
204 m.scale.z = cone_height;
206 auto start = Convert::ToRos<geometry_msgs::Point>(pos + normal);
207 m.points.push_back(
start);
209 auto end = Convert::ToRos<geometry_msgs::Point>(pos);
210 m.points.push_back(end);
217 Eigen::Quaterniond ori,
218 const ContactState& contact_state)
const
220 Vector3d edge_length(0.1, 0.05, 0.02);
225 for (
auto ee : contact_state.GetEEsOrdered())
226 if (contact_state.at(ee))
236 const EEPos& ee_pos)
const
239 for (
Vector3d ee : ee_forces.ToImpl())
246 for (
auto ee : ee_forces.GetEEsOrdered()) {
247 double p = ee_forces.at(ee).z()/z_sum;
248 cop += p*ee_pos.at(ee);
264 const EEPos& ee_pos)
const
267 m.type = Marker::LINE_STRIP;
270 geometry_msgs::Point cop =
CreateCopPos(ee_forces, ee_pos).pose.position;
271 geometry_msgs::Point com =
CreateSphere(pos).pose.position;
273 m.points.push_back(cop);
274 m.points.push_back(com);
276 m.ns =
"inverted_pendulum";
294 auto w_R_b = base.
ang.
q.toRotationMatrix();
296 for (
const auto& pos_B :
params_msg_.nominal_ee_pos) {
303 m.ns =
"range_of_motion";
316 m.type = Marker::CUBE;
317 m.pose.position = Convert::ToRos<geometry_msgs::Point>(pos);
319 m.scale = Convert::ToRos<geometry_msgs::Vector3>(edge_length);
329 m.type = Marker::SPHERE;
330 m.pose.position = Convert::ToRos<geometry_msgs::Point>(pos);
331 m.scale.x = diameter;
332 m.scale.y = diameter;
333 m.scale.z = diameter;
343 m.type = Marker::ARROW;
349 double force_scale = 800;
350 Vector3d p_start = ee_pos - force/force_scale;
351 auto start = Convert::ToRos<geometry_msgs::Point>(p_start);
352 m.points.push_back(start);
354 auto end = Convert::ToRos<geometry_msgs::Point>(ee_pos);
355 m.points.push_back(end);
362 const EEPos& ee_pos)
const
367 m.ns =
"support_polygons";
368 m.scale.x = m.scale.y = m.scale.z = 1.0;
370 for (
auto ee : contact_state.GetEEsOrdered()) {
371 if (contact_state.at(ee)) {
372 auto p = Convert::ToRos<geometry_msgs::Point>(ee_pos.at(ee));
373 m.points.push_back(p);
379 switch (m.points.size()) {
381 m.type = Marker::TRIANGLE_LIST;
382 auto temp = m.points;
389 m.points.erase(m.points.begin());
394 m.type = Marker::TRIANGLE_LIST;
400 m.type = Marker::LINE_STRIP;
408 m.type = Marker::CUBE;
415 m.type = Marker::CUBE;