moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
motion_planning_display.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan, Dave Coleman, Adam Leeper, Sachin Chitta */
36
42
43#include <rviz_default_plugins/robot/robot.hpp>
44#include <rviz_default_plugins/robot/robot_link.hpp>
46
47#include <rviz_common/properties/property.hpp>
48#include <rviz_common/properties/string_property.hpp>
49#include <rviz_common/properties/bool_property.hpp>
50#include <rviz_common/properties/float_property.hpp>
51#include <rviz_common/properties/ros_topic_property.hpp>
52#include <rviz_common/properties/editable_enum_property.hpp>
53#include <rviz_common/properties/color_property.hpp>
54#include <rviz_common/display_context.hpp>
55#include <rviz_common/frame_manager_iface.hpp>
56#include <rviz_common/panel_dock_widget.hpp>
57#include <rviz_common/window_manager_interface.hpp>
58#include <rviz_common/display.hpp>
59#include <rviz_rendering/objects/movable_text.hpp>
60
61#include <OgreSceneManager.h>
62#include <OgreSceneNode.h>
63#include <rviz_rendering/objects/shape.hpp>
64
67
68#include <QShortcut>
69
70#include "ui_motion_planning_rviz_plugin_frame.h"
73
74namespace moveit_rviz_plugin
75{
76
77// ******************************************************************************************
78// Base class constructor
79// ******************************************************************************************
82 , text_to_display_(nullptr)
83 , frame_(nullptr)
84 , frame_dock_(nullptr)
85 , menu_handler_start_(std::make_shared<interactive_markers::MenuHandler>())
86 , menu_handler_goal_(std::make_shared<interactive_markers::MenuHandler>())
87 , int_marker_display_(nullptr)
88{
89 // Category Groups
90 plan_category_ = new rviz_common::properties::Property("Planning Request", QVariant(), "", this);
91 metrics_category_ = new rviz_common::properties::Property("Planning Metrics", QVariant(), "", this);
92 path_category_ = new rviz_common::properties::Property("Planned Path", QVariant(), "", this);
93
94 // Metrics category -----------------------------------------------------------------------------------------
96 new rviz_common::properties::BoolProperty("Show Weight Limit", false,
97 "Shows the weight limit at a particular pose for an end-effector",
98 metrics_category_, SLOT(changedShowWeightLimit()), this);
99
101 new rviz_common::properties::BoolProperty("Show Manipulability Index", false,
102 "Shows the manipulability index for an end-effector", metrics_category_,
103 SLOT(changedShowManipulabilityIndex()), this);
104
106 new rviz_common::properties::BoolProperty("Show Manipulability", false,
107 "Shows the manipulability for an end-effector", metrics_category_,
108 SLOT(changedShowManipulability()), this);
109
111 new rviz_common::properties::BoolProperty("Show Joint Torques", false,
112 "Shows the joint torques for a given configuration and payload",
113 metrics_category_, SLOT(changedShowJointTorques()), this);
114
116 new rviz_common::properties::FloatProperty("Payload", 1.0f, "Specify the payload at the end effector (kg)",
117 metrics_category_, SLOT(changedMetricsSetPayload()), this);
119
120 metrics_text_height_property_ = new rviz_common::properties::FloatProperty(
121 "TextHeight", 0.08f, "Text height", metrics_category_, SLOT(changedMetricsTextHeight()), this);
122 metrics_text_height_property_->setMin(0.001);
123
124 // Planning request category -----------------------------------------------------------------------------------------
125
126 planning_group_property_ = new rviz_common::properties::EditableEnumProperty(
127 "Planning Group", "", "The name of the group of links to plan for (from the ones defined in the SRDF)",
128 plan_category_, SLOT(changedPlanningGroup()), this);
129 show_workspace_property_ = new rviz_common::properties::BoolProperty("Show Workspace", false,
130 "Shows the axis-aligned bounding box for "
131 "the workspace allowed for planning",
132 plan_category_, SLOT(changedWorkspace()), this);
134 new rviz_common::properties::BoolProperty("Query Start State", false,
135 "Set a custom start state for the motion planning query",
136 plan_category_, SLOT(changedQueryStartState()), this);
138 new rviz_common::properties::BoolProperty("Query Goal State", true,
139 "Shows the goal state for the motion planning query", plan_category_,
140 SLOT(changedQueryGoalState()), this);
141 query_marker_scale_property_ = new rviz_common::properties::FloatProperty(
142 "Interactive Marker Size", 0.0f,
143 "Specifies scale of the interactive marker overlaid on the robot. 0 is auto scale.", plan_category_,
144 SLOT(changedQueryMarkerScale()), this);
145 query_marker_scale_property_->setMin(0.0f);
146
148 new rviz_common::properties::ColorProperty("Start State Color", QColor(0, 255, 0),
149 "The highlight color for the start state", plan_category_,
150 SLOT(changedQueryStartColor()), this);
152 new rviz_common::properties::FloatProperty("Start State Alpha", 1.0f, "Specifies the alpha for the robot links",
153 plan_category_, SLOT(changedQueryStartAlpha()), this);
154 query_start_alpha_property_->setMin(0.0);
155 query_start_alpha_property_->setMax(1.0);
156
158 new rviz_common::properties::ColorProperty("Goal State Color", QColor(250, 128, 0),
159 "The highlight color for the goal state", plan_category_,
160 SLOT(changedQueryGoalColor()), this);
161
163 new rviz_common::properties::FloatProperty("Goal State Alpha", 1.0f, "Specifies the alpha for the robot links",
164 plan_category_, SLOT(changedQueryGoalAlpha()), this);
165 query_goal_alpha_property_->setMin(0.0);
166 query_goal_alpha_property_->setMax(1.0);
167
169 new rviz_common::properties::ColorProperty("Colliding Link Color", QColor(255, 0, 0),
170 "The highlight color for colliding links", plan_category_,
171 SLOT(changedQueryCollidingLinkColor()), this);
172
173 query_outside_joint_limits_link_color_property_ = new rviz_common::properties::ColorProperty(
174 "Joint Violation Color", QColor(255, 0, 255),
175 "The highlight color for child links of joints that are outside bounds", plan_category_,
176 SLOT(changedQueryJointViolationColor()), this);
177
178 // Trajectory playback / planned path category ---------------------------------------------
179 trajectory_visual_ = std::make_shared<TrajectoryVisualization>(path_category_, this);
180
181 // Start background jobs
183 const std::string& name) { backgroundJobUpdate(event, name); });
184}
185
186// ******************************************************************************************
187// Deconstructor
188// ******************************************************************************************
201
203{
205
206 // Planned Path Display
207 trajectory_visual_->onInitialize(node_, planning_scene_node_, context_);
208 QColor qcolor = attached_body_color_property_->getColor();
209 trajectory_visual_->setDefaultAttachedObjectColor(qcolor);
210
212 std::make_shared<RobotStateVisualization>(planning_scene_node_, context_, "Planning Request Start", nullptr);
213 query_robot_start_->setCollisionVisible(false);
214 query_robot_start_->setVisualVisible(true);
215 query_robot_start_->setVisible(query_start_state_property_->getBool());
216 std_msgs::msg::ColorRGBA color;
217 qcolor = query_start_color_property_->getColor();
218 color.r = qcolor.redF();
219 color.g = qcolor.greenF();
220 color.b = qcolor.blueF();
221 color.a = 1.0f;
222 query_robot_start_->setDefaultAttachedObjectColor(color);
223
225 std::make_shared<RobotStateVisualization>(planning_scene_node_, context_, "Planning Request Goal", nullptr);
226 query_robot_goal_->setCollisionVisible(false);
227 query_robot_goal_->setVisualVisible(true);
228 query_robot_goal_->setVisible(query_goal_state_property_->getBool());
229 qcolor = query_goal_color_property_->getColor();
230 color.r = qcolor.redF();
231 color.g = qcolor.greenF();
232 color.b = qcolor.blueF();
233 query_robot_goal_->setDefaultAttachedObjectColor(color);
234
235 rviz_common::WindowManagerInterface* window_context = context_->getWindowManager();
236 frame_ = new MotionPlanningFrame(this, context_, window_context ? window_context->getParentWindow() : nullptr);
237
238 connect(frame_, SIGNAL(configChanged()), getModel(), SIGNAL(configChanged()));
240 addStatusText("Initialized.");
241
242 // immediately switch to next trajectory display after planning
243 connect(frame_, SIGNAL(planningFinished()), trajectory_visual_.get(), SLOT(interruptCurrentDisplay()));
244
245 if (window_context)
246 {
247 frame_dock_ = window_context->addPane(getName(), frame_);
248 connect(frame_dock_, SIGNAL(visibilityChanged(bool)), this, SLOT(motionPanelVisibilityChange(bool)));
249 frame_dock_->setIcon(getIcon());
250 }
251
253 int_marker_display_->initialize(context_);
254
255 text_display_scene_node_ = planning_scene_node_->createChildSceneNode();
256 text_to_display_ = new rviz_rendering::MovableText("EMPTY");
257 text_to_display_->setTextAlignment(rviz_rendering::MovableText::H_CENTER, rviz_rendering::MovableText::V_CENTER);
258 text_to_display_->setCharacterHeight(metrics_text_height_property_->getFloat());
259 text_to_display_->showOnTop();
260 text_to_display_->setVisible(false);
263
264 if (context_ && context_->getWindowManager() && context_->getWindowManager()->getParentWindow())
265 {
266 QShortcut* im_reset_shortcut =
267 new QShortcut(QKeySequence("Ctrl+I"), context_->getWindowManager()->getParentWindow());
268 connect(im_reset_shortcut, SIGNAL(activated()), this, SLOT(resetInteractiveMarkers()));
269 }
270}
271
272void MotionPlanningDisplay::motionPanelVisibilityChange(bool enable)
273{
274 if (enable)
275 setEnabled(true);
276}
277
279{
280 if (enable)
281 {
282 planning_group_sub_ = node_->create_subscription<std_msgs::msg::String>(
283 "/rviz/moveit/select_planning_group", rclcpp::SystemDefaultsQoS(),
284 [this](const std_msgs::msg::String::ConstSharedPtr& msg) { return selectPlanningGroupCallback(msg); });
285 }
286 else
287 {
288 planning_group_sub_.reset();
289 }
290}
291
292void MotionPlanningDisplay::selectPlanningGroupCallback(const std_msgs::msg::String::ConstSharedPtr& msg)
293{
294 // synchronize ROS callback with main loop
295 addMainLoopJob([this, group = msg->data] { changePlanningGroup(group); });
296}
297
299{
300 text_to_display_->setVisible(false);
301
302 query_robot_start_->clear();
303 query_robot_goal_->clear();
304
306
307 // Planned Path Display
308 trajectory_visual_->reset();
309
310 bool enabled = isEnabled();
311 frame_->disable();
312 if (enabled)
313 {
314 frame_->enable();
315 query_robot_start_->setVisible(query_start_state_property_->getBool());
316 query_robot_goal_->setVisible(query_goal_state_property_->getBool());
317 }
318}
319
325
327{
328 if (!frame_)
329 return;
330 QProgressBar* p = frame_->ui_->background_job_progress;
332
333 if (n == 0)
334 {
335 p->hide();
336 p->setMaximum(0);
337 p->setValue(0);
338 }
339 else
340 {
341 if (p->maximum() < n) // increase max
342 {
343 p->setMaximum(n);
344 if (n > 1) // only show bar if there will be a progress to show
345 p->show();
346 }
347 else // progress
348 p->setValue(p->maximum() - n);
349 p->update();
350 }
351}
352
353void MotionPlanningDisplay::changedShowWeightLimit()
354{
356 {
357 if (query_start_state_property_->getBool())
358 displayMetrics(true);
359 }
360 else
361 {
362 if (query_goal_state_property_->getBool())
363 displayMetrics(false);
364 }
365}
366
367void MotionPlanningDisplay::changedShowManipulabilityIndex()
368{
370 {
371 if (query_start_state_property_->getBool())
372 displayMetrics(true);
373 }
374 else
375 {
376 if (query_goal_state_property_->getBool())
377 displayMetrics(false);
378 }
379}
380
381void MotionPlanningDisplay::changedShowManipulability()
382{
384 {
385 if (query_start_state_property_->getBool())
386 displayMetrics(true);
387 }
388 else
389 {
390 if (query_goal_state_property_->getBool())
391 displayMetrics(false);
392 }
393}
394
395void MotionPlanningDisplay::changedShowJointTorques()
396{
398 {
399 if (query_start_state_property_->getBool())
400 displayMetrics(true);
401 }
402 else
403 {
404 if (query_goal_state_property_->getBool())
405 displayMetrics(false);
406 }
407}
408
409void MotionPlanningDisplay::changedMetricsSetPayload()
410{
412 {
413 if (query_start_state_property_->getBool())
414 displayMetrics(true);
415 }
416 else
417 {
418 if (query_goal_state_property_->getBool())
419 displayMetrics(false);
420 }
421}
422
423void MotionPlanningDisplay::changedMetricsTextHeight()
424{
425 text_to_display_->setCharacterHeight(metrics_text_height_property_->getFloat());
426}
427
428void MotionPlanningDisplay::displayTable(const std::map<std::string, double>& values, const Ogre::ColourValue& color,
429 const Ogre::Vector3& pos, const Ogre::Quaternion& orient)
430{
431 if (values.empty())
432 {
433 text_to_display_->setVisible(false);
434 return;
435 }
436
437 // the line we want to render
438 std::stringstream ss;
439 ss.setf(std::ios_base::fixed);
440 ss.precision(2);
441
442 for (const auto& [label, value] : values)
443 ss << label << ':' << value << '\n';
444
445 text_to_display_->setCaption(ss.str());
446 text_to_display_->setColor(color);
447 text_display_scene_node_->setPosition(pos);
448 text_display_scene_node_->setOrientation(orient);
449
450 // make sure the node is visible
451 text_to_display_->setVisible(true);
452}
453
455{
456 if (!frame_ || !show_workspace_property_->getBool())
457 {
458 if (workspace_box_)
459 workspace_box_.reset();
460 return;
461 }
462
463 if (!workspace_box_)
464 {
465 workspace_box_ = std::make_unique<rviz_rendering::Shape>(rviz_rendering::Shape::Cube, context_->getSceneManager(),
467 workspace_box_->setColor(0.0f, 0.0f, 0.6f, 0.3f);
468 }
469
470 Ogre::Vector3 center(frame_->ui_->wcenter_x->value(), frame_->ui_->wcenter_y->value(),
471 frame_->ui_->wcenter_z->value());
472 Ogre::Vector3 extents(frame_->ui_->wsize_x->value(), frame_->ui_->wsize_y->value(), frame_->ui_->wsize_z->value());
473 workspace_box_->setScale(extents);
474 workspace_box_->setPosition(center);
475}
476
477void MotionPlanningDisplay::computeMetrics(bool start, const std::string& group, double payload)
478{
480 return;
481 const std::vector<robot_interaction::EndEffectorInteraction>& eef = robot_interaction_->getActiveEndEffectors();
482 if (eef.empty())
483 return;
484 std::scoped_lock slock(update_metrics_lock_);
485
486 moveit::core::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState();
488 {
489 if (ee.parent_group == group)
490 computeMetricsInternal(computed_metrics_[std::make_pair(start, group)], ee, *state, payload);
491 }
492}
493
494void MotionPlanningDisplay::computeMetricsInternal(std::map<std::string, double>& metrics,
496 const moveit::core::RobotState& state, double payload)
497{
498 metrics.clear();
499 dynamics_solver::DynamicsSolverPtr ds;
500 std::map<std::string, dynamics_solver::DynamicsSolverPtr>::const_iterator it = dynamics_solver_.find(ee.parent_group);
501 if (it != dynamics_solver_.end())
502 ds = it->second;
503
504 // Max payload
505 if (ds)
506 {
507 double max_payload;
508 unsigned int saturated_joint;
509 std::vector<double> joint_values;
510 state.copyJointGroupPositions(ee.parent_group, joint_values);
511 if (ds->getMaxPayload(joint_values, max_payload, saturated_joint))
512 {
513 metrics["max_payload"] = max_payload;
514 metrics["saturated_joint"] = saturated_joint;
515 }
516 std::vector<double> joint_torques;
517 joint_torques.resize(joint_values.size());
518 if (ds->getPayloadTorques(joint_values, payload, joint_torques))
519 {
520 for (std::size_t i = 0; i < joint_torques.size(); ++i)
521 {
522 std::stringstream stream;
523 stream << "torque[" << i << ']';
524 metrics[stream.str()] = joint_torques[i];
525 }
526 }
527 }
528
530 {
532 node_->get_parameter_or(ee.parent_group + ".position_only_ik", position_only_ik_[ee.parent_group], false);
533
534 double manipulability_index, manipulability;
535 bool position_ik = position_only_ik_[ee.parent_group];
536 if (kinematics_metrics_->getManipulabilityIndex(state, ee.parent_group, manipulability_index, position_ik))
537 metrics["manipulability_index"] = manipulability_index;
538 if (kinematics_metrics_->getManipulability(state, ee.parent_group, manipulability))
539 metrics["manipulability"] = manipulability;
540 }
541}
542
543namespace
544{
545inline void copyItemIfExists(const std::map<std::string, double>& source, std::map<std::string, double>& dest,
546 const std::string& key)
547{
548 std::map<std::string, double>::const_iterator it = source.find(key);
549 if (it != source.end())
550 dest[key] = it->second;
551}
552} // namespace
553
555{
557 return;
558
559 static const Ogre::Quaternion ORIENTATION(1.0, 0.0, 0.0, 0.0);
560 const std::vector<robot_interaction::EndEffectorInteraction>& eef = robot_interaction_->getActiveEndEffectors();
561 if (eef.empty())
562 return;
563
564 moveit::core::RobotStateConstPtr state = start ? getQueryStartState() : getQueryGoalState();
565
567 {
568 Ogre::Vector3 position(0.0, 0.0, 0.0);
569 std::map<std::string, double> text_table;
570 const std::map<std::string, double>& metrics_table = computed_metrics_[std::make_pair(start, ee.parent_group)];
571 if (compute_weight_limit_property_->getBool())
572 {
573 copyItemIfExists(metrics_table, text_table, "max_payload");
574 copyItemIfExists(metrics_table, text_table, "saturated_joint");
575 }
577 copyItemIfExists(metrics_table, text_table, "manipulability_index");
578 if (show_manipulability_property_->getBool())
579 copyItemIfExists(metrics_table, text_table, "manipulability");
580 if (show_joint_torques_property_->getBool())
581 {
582 std::size_t nj = getRobotModel()->getJointModelGroup(ee.parent_group)->getJointModelNames().size();
583 for (size_t j = 0; j < nj; ++j)
584 {
585 std::stringstream stream;
586 stream << "torque[" << j << ']';
587 copyItemIfExists(metrics_table, text_table, stream.str());
588 }
589 }
590
591 const moveit::core::LinkModel* lm = nullptr;
592 const moveit::core::JointModelGroup* jmg = getRobotModel()->getJointModelGroup(ee.parent_group);
593 if (jmg)
594 {
595 if (!jmg->getLinkModelNames().empty())
596 lm = state->getLinkModel(jmg->getLinkModelNames().back());
597 }
598 if (lm)
599 {
600 const Eigen::Vector3d& t = state->getGlobalLinkTransform(lm).translation();
601 position[0] = t.x();
602 position[1] = t.y();
603 position[2] = t.z() + 0.2; // \todo this should be a param
604 }
605 if (start)
606 {
607 displayTable(text_table, query_start_color_property_->getOgreColor(), position, ORIENTATION);
608 }
609 else
610 {
611 displayTable(text_table, query_goal_color_property_->getOgreColor(), position, ORIENTATION);
612 }
614 }
615}
616
618{
620 return;
621
622 if (query_start_state_property_->getBool())
623 {
624 if (isEnabled())
625 {
626 moveit::core::RobotStateConstPtr state = getQueryStartState();
627
628 // update link poses
629 query_robot_start_->update(state);
630 query_robot_start_->setVisible(true);
631
632 // update link colors
633 std::vector<std::string> collision_links;
634 getPlanningSceneRO()->getCollidingLinks(collision_links, *state);
635 status_links_start_.clear();
636 for (const std::string& collision_link : collision_links)
637 status_links_start_[collision_link] = COLLISION_LINK;
638 if (!collision_links.empty())
639 {
641 getPlanningSceneRO()->getCollidingPairs(pairs, *state);
643 addStatusText("Start state colliding links:");
644 for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
645 ++it)
646 addStatusText(it->first.first + " - " + it->first.second);
647 addStatusText(".");
648 }
649 if (!getCurrentPlanningGroup().empty())
650 {
651 const moveit::core::JointModelGroup* jmg = state->getJointModelGroup(getCurrentPlanningGroup());
652 if (jmg)
653 {
654 std::vector<std::string> outside_bounds;
655 const std::vector<const moveit::core::JointModel*>& jmodels = jmg->getActiveJointModels();
656 for (const moveit::core::JointModel* jmodel : jmodels)
657 {
658 if (!state->satisfiesBounds(jmodel, jmodel->getMaximumExtent() * 1e-2))
659 {
660 outside_bounds.push_back(jmodel->getChildLinkModel()->getName());
661 status_links_start_[outside_bounds.back()] = OUTSIDE_BOUNDS_LINK;
662 }
663 }
664 if (!outside_bounds.empty())
665 {
667 addStatusText("Links descending from joints that are outside bounds in start state:");
668 addStatusText(outside_bounds);
669 }
670 }
671 }
673 // update metrics text
674 displayMetrics(true);
675 }
676 }
677 else
678 query_robot_start_->setVisible(false);
679 context_->queueRender();
680}
681
686
688{
689 if (frame_)
690 frame_->ui_->status_text->setTextColor(color);
691}
692
693void MotionPlanningDisplay::addStatusText(const std::string& text)
694{
695 if (frame_)
696 frame_->ui_->status_text->append(QString::fromStdString(text));
697}
698
699void MotionPlanningDisplay::addStatusText(const std::vector<std::string>& text)
700{
701 for (const std::string& it : text)
702 addStatusText(it);
703}
704
706{
707 std::string group = planning_group_property_->getStdString();
708 if (!group.empty())
709 computeMetrics(true, group, metrics_set_payload_property_->getFloat());
710}
711
713{
714 std::string group = planning_group_property_->getStdString();
715 if (!group.empty())
716 computeMetrics(false, group, metrics_set_payload_property_->getFloat());
717}
718
719void MotionPlanningDisplay::changedQueryStartState()
720{
722 return;
724 addStatusText("Changed start state");
726 addBackgroundJob([this] { publishInteractiveMarkers(true); }, "publishInteractiveMarkers");
727}
728
729void MotionPlanningDisplay::changedQueryGoalState()
730{
732 return;
734 addStatusText("Changed goal state");
736 addBackgroundJob([this] { publishInteractiveMarkers(true); }, "publishInteractiveMarkers");
737}
738
740{
742 return;
743 if (query_goal_state_property_->getBool())
744 {
745 if (isEnabled())
746 {
747 moveit::core::RobotStateConstPtr state = getQueryGoalState();
748
749 // update link poses
750 query_robot_goal_->update(state);
751 query_robot_goal_->setVisible(true);
752
753 // update link colors
754 std::vector<std::string> collision_links;
755 getPlanningSceneRO()->getCollidingLinks(collision_links, *state);
756 status_links_goal_.clear();
757 for (const std::string& collision_link : collision_links)
758 status_links_goal_[collision_link] = COLLISION_LINK;
759 if (!collision_links.empty())
760 {
762 getPlanningSceneRO()->getCollidingPairs(pairs, *state);
764 addStatusText("Goal state colliding links:");
765 for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
766 ++it)
767 addStatusText(it->first.first + " - " + it->first.second);
768 addStatusText(".");
769 }
770
771 if (!getCurrentPlanningGroup().empty())
772 {
773 const moveit::core::JointModelGroup* jmg = state->getJointModelGroup(getCurrentPlanningGroup());
774 if (jmg)
775 {
776 const std::vector<const moveit::core::JointModel*>& jmodels = jmg->getActiveJointModels();
777 std::vector<std::string> outside_bounds;
778 for (const moveit::core::JointModel* jmodel : jmodels)
779 {
780 if (!state->satisfiesBounds(jmodel, jmodel->getMaximumExtent() * 1e-2))
781 {
782 outside_bounds.push_back(jmodel->getChildLinkModel()->getName());
783 status_links_goal_[outside_bounds.back()] = OUTSIDE_BOUNDS_LINK;
784 }
785 }
786
787 if (!outside_bounds.empty())
788 {
790 addStatusText("Links descending from joints that are outside bounds in goal state:");
791 addStatusText(outside_bounds);
792 }
793 }
794 }
796
797 // update metrics text
798 displayMetrics(false);
799 }
800 }
801 else
802 query_robot_goal_->setVisible(false);
803 context_->queueRender();
804}
805
806void MotionPlanningDisplay::resetInteractiveMarkers()
807{
808 query_start_state_->clearError();
809 query_goal_state_->clearError();
810 addBackgroundJob([this] { publishInteractiveMarkers(false); }, "publishInteractiveMarkers");
811}
812
814{
816 {
817 if (pose_update &&
820 {
821 if (query_start_state_property_->getBool())
822 robot_interaction_->updateInteractiveMarkers(query_start_state_);
823 if (query_goal_state_property_->getBool())
824 robot_interaction_->updateInteractiveMarkers(query_goal_state_);
825 }
826 else
827 {
828 robot_interaction_->clearInteractiveMarkers();
829 if (query_start_state_property_->getBool())
830 robot_interaction_->addInteractiveMarkers(query_start_state_, query_marker_scale_property_->getFloat());
831 if (query_goal_state_property_->getBool())
832 robot_interaction_->addInteractiveMarkers(query_goal_state_, query_marker_scale_property_->getFloat());
833 robot_interaction_->publishInteractiveMarkers();
834 }
835 if (frame_)
836 {
838 }
839 }
840}
841
842void MotionPlanningDisplay::changedQueryStartColor()
843{
844 std_msgs::msg::ColorRGBA color;
845 QColor qcolor = query_start_color_property_->getColor();
846 color.r = qcolor.redF();
847 color.g = qcolor.greenF();
848 color.b = qcolor.blueF();
849 color.a = 1.0f;
850 query_robot_start_->setDefaultAttachedObjectColor(color);
851 changedQueryStartState();
852}
853
854void MotionPlanningDisplay::changedQueryStartAlpha()
855{
856 query_robot_start_->setAlpha(query_start_alpha_property_->getFloat());
857 changedQueryStartState();
858}
859
860void MotionPlanningDisplay::changedQueryMarkerScale()
861{
863 return;
864
865 if (isEnabled())
866 {
867 // Clear the interactive markers and re-add them:
869 }
870}
871
872void MotionPlanningDisplay::changedQueryGoalColor()
873{
874 std_msgs::msg::ColorRGBA color;
875 QColor qcolor = query_goal_color_property_->getColor();
876 color.r = qcolor.redF();
877 color.g = qcolor.greenF();
878 color.b = qcolor.blueF();
879 color.a = 1.0f;
880 query_robot_goal_->setDefaultAttachedObjectColor(color);
881 changedQueryGoalState();
882}
883
884void MotionPlanningDisplay::changedQueryGoalAlpha()
885{
886 query_robot_goal_->setAlpha(query_goal_alpha_property_->getFloat());
887 changedQueryGoalState();
888}
889
890void MotionPlanningDisplay::changedQueryCollidingLinkColor()
891{
892 changedQueryStartState();
893 changedQueryGoalState();
894}
895
896void MotionPlanningDisplay::changedQueryJointViolationColor()
897{
898 changedQueryStartState();
899 changedQueryGoalState();
900}
901
902void MotionPlanningDisplay::changedAttachedBodyColor()
903{
905 // forward color to TrajectoryVisualization
906 const QColor& color = attached_body_color_property_->getColor();
907 trajectory_visual_->setDefaultAttachedObjectColor(color);
908}
909
911 bool error_state_changed)
912{
914 return;
915 addBackgroundJob([this, pose_update = !error_state_changed] { publishInteractiveMarkers(pose_update); },
916 "publishInteractiveMarkers");
918}
919
921 bool error_state_changed)
922{
924 return;
925 addBackgroundJob([this, pose_update = !error_state_changed] { publishInteractiveMarkers(pose_update); },
926 "publishInteractiveMarkers");
928}
929
931{
934 addMainLoopJob([this] { changedQueryStartState(); });
935 context_->queueRender();
936}
937
939{
942 addMainLoopJob([this] { changedQueryGoalState(); });
943 context_->queueRender();
944}
945
950
956
962
974
977 const double* ik_solution) const
978{
979 if (frame_->ui_->collision_aware_ik->isChecked() && planning_scene_monitor_)
980 {
981 state->setJointGroupPositions(group, ik_solution);
982 state->update();
983 bool res = !getPlanningSceneRO()->isStateColliding(*state, group->getName());
984 return res;
985 }
986 else
987 return true;
988}
989
991{
993 unsetAllColors(&query_robot_goal_->getRobot());
994 std::string group = planning_group_property_->getStdString();
995 if (!group.empty())
996 {
997 setGroupColor(&query_robot_start_->getRobot(), group, query_start_color_property_->getColor());
998 setGroupColor(&query_robot_goal_->getRobot(), group, query_goal_color_property_->getColor());
999
1000 for (std::map<std::string, LinkDisplayStatus>::const_iterator it = status_links_start_.begin();
1001 it != status_links_start_.end(); ++it)
1002 {
1003 if (it->second == COLLISION_LINK)
1004 {
1005 setLinkColor(&query_robot_start_->getRobot(), it->first, query_colliding_link_color_property_->getColor());
1006 }
1007 else
1008 {
1009 setLinkColor(&query_robot_start_->getRobot(), it->first,
1011 }
1012 }
1013
1014 for (std::map<std::string, LinkDisplayStatus>::const_iterator it = status_links_goal_.begin();
1015 it != status_links_goal_.end(); ++it)
1016 {
1017 if (it->second == COLLISION_LINK)
1018 {
1019 setLinkColor(&query_robot_goal_->getRobot(), it->first, query_colliding_link_color_property_->getColor());
1020 }
1021 else
1022 {
1023 setLinkColor(&query_robot_goal_->getRobot(), it->first,
1025 }
1026 }
1027 }
1028}
1029
1031{
1033 return;
1034
1035 if (getRobotModel()->hasJointModelGroup(group))
1036 {
1037 planning_group_property_->setStdString(group);
1038 }
1039 else
1040 {
1041 RCLCPP_ERROR(moveit::getLogger("moveit.ros.motion_planning_display"), "Group [%s] not found in the robot model.",
1042 group.c_str());
1043 }
1044}
1045
1046void MotionPlanningDisplay::changedPlanningGroup()
1047{
1049 return;
1050
1051 if (!planning_group_property_->getStdString().empty() &&
1052 !getRobotModel()->hasJointModelGroup(planning_group_property_->getStdString()))
1053 {
1054 planning_group_property_->setStdString("");
1055 return;
1056 }
1057 modified_groups_.insert(planning_group_property_->getStdString());
1058
1059 robot_interaction_->decideActiveComponents(planning_group_property_->getStdString());
1060
1064
1065 if (frame_)
1067 addBackgroundJob([this] { publishInteractiveMarkers(false); }, "publishInteractiveMarkers");
1068}
1069
1070void MotionPlanningDisplay::changedWorkspace()
1071{
1073}
1074
1076{
1077 return planning_group_property_->getStdString();
1078}
1079
1080void MotionPlanningDisplay::setQueryStateHelper(bool use_start_state, const std::string& state_name)
1081{
1082 moveit::core::RobotState state = use_start_state ? *getQueryStartState() : *getQueryGoalState();
1083
1084 std::string v = "<" + state_name + ">";
1085
1086 if (v == "<random>")
1087 {
1089 state.setToRandomPositions(jmg);
1090 }
1091 else if (v == "<current>")
1092 {
1094 if (ps)
1095 state = ps->getCurrentState();
1096 }
1097 else if (v == "<same as goal>")
1098 {
1099 state = *getQueryGoalState();
1100 }
1101 else if (v == "<same as start>")
1102 {
1103 state = *getQueryStartState();
1104 }
1105 else
1106 {
1107 // maybe it is a named state
1109 state.setToDefaultValues(jmg, state_name);
1110 }
1111
1112 use_start_state ? setQueryStartState(state) : setQueryGoalState(state);
1113}
1114
1115void MotionPlanningDisplay::populateMenuHandler(std::shared_ptr<interactive_markers::MenuHandler>& mh)
1116{
1117 typedef interactive_markers::MenuHandler immh;
1118 std::vector<std::string> state_names;
1119 state_names.push_back("random");
1120 state_names.push_back("current");
1121 state_names.push_back("same as start");
1122 state_names.push_back("same as goal");
1123
1124 // hacky way to distinguish between the start and goal handlers...
1125 bool is_start = (mh.get() == menu_handler_start_.get());
1126
1127 // Commands for changing the state
1128 immh::EntryHandle menu_states =
1129 mh->insert(is_start ? "Set start state to" : "Set goal state to", immh::FeedbackCallback());
1130 for (const std::string& state_name : state_names)
1131 {
1132 // Don't add "same as start" to the start state handler, and vice versa.
1133 if ((state_name == "same as start" && is_start) || (state_name == "same as goal" && !is_start))
1134 continue;
1135 mh->insert(menu_states, state_name,
1136 [this, is_start, state_name](auto&&) { setQueryStateHelper(is_start, state_name); });
1137 }
1138
1139 // // Group commands, which end up being the same for both interaction handlers
1140 // const std::vector<std::string>& group_names = getRobotModel()->getJointModelGroupNames();
1141 // immh::EntryHandle menu_groups = mh->insert("Planning Group", immh::FeedbackCallback());
1142 // for (int i = 0; i < group_names.size(); ++i)
1143 // mh->insert(menu_groups, group_names[i],
1144 // [this, &name = group_names[i]] { changePlanningGroup(name); });
1145}
1146
1148{
1149 // Invalidate all references to the RobotModel ...
1150 if (frame_)
1153 trajectory_visual_->clearRobotModel();
1154 previous_state_.reset();
1155 query_start_state_.reset();
1156 query_goal_state_.reset();
1157 kinematics_metrics_.reset();
1158 robot_interaction_.reset();
1159 dynamics_solver_.clear();
1160 // ... before calling the parent's method, which finally destroys the creating RobotModelLoader.
1162}
1163
1165{
1167 trajectory_visual_->onRobotModelLoaded(getRobotModel());
1168
1169 robot_interaction_ = std::make_shared<robot_interaction::RobotInteraction>(
1170 getRobotModel(), node_, rclcpp::names::append(getMoveGroupNS(), "rviz_moveit_motion_planning_display"));
1172 o.state_validity_callback_ = [this](moveit::core::RobotState* robot_state,
1173 const moveit::core::JointModelGroup* joint_group,
1174 const double* joint_group_variable_values) {
1175 return isIKSolutionCollisionFree(robot_state, joint_group, joint_group_variable_values);
1176 };
1177 robot_interaction_->getKinematicOptionsMap()->setOptions(
1179
1180 int_marker_display_->subProp("Interactive Markers Namespace")
1181 ->setValue(QString::fromStdString(robot_interaction_->getServerTopic()));
1182 query_robot_start_->load(*getRobotModel()->getURDF());
1183 query_robot_goal_->load(*getRobotModel()->getURDF());
1184
1185 // initialize previous state, start state, and goal state to current state
1186 previous_state_ = std::make_shared<moveit::core::RobotState>(getPlanningSceneRO()->getCurrentState());
1187 query_start_state_ = std::make_shared<robot_interaction::InteractionHandler>(
1189 query_goal_state_ = std::make_shared<robot_interaction::InteractionHandler>(
1191 query_start_state_->setUpdateCallback(
1192 [this](robot_interaction::InteractionHandler* handler, bool error_state_changed) {
1193 scheduleDrawQueryStartState(handler, error_state_changed);
1194 });
1195 query_goal_state_->setUpdateCallback([this](robot_interaction::InteractionHandler* handler, bool error_state_changed) {
1196 scheduleDrawQueryGoalState(handler, error_state_changed);
1197 });
1198
1199 // Interactive marker menus
1202 query_start_state_->setMenuHandler(menu_handler_start_);
1203 query_goal_state_->setMenuHandler(menu_handler_goal_);
1204
1205 if (!planning_group_property_->getStdString().empty())
1206 {
1207 if (!getRobotModel()->hasJointModelGroup(planning_group_property_->getStdString()))
1208 planning_group_property_->setStdString("");
1209 }
1210
1211 const std::vector<std::string>& groups = getRobotModel()->getJointModelGroupNames();
1212 planning_group_property_->clearOptions();
1213 for (const std::string& group : groups)
1214 planning_group_property_->addOptionStd(group);
1215 planning_group_property_->sortOptions();
1216 if (!groups.empty() && planning_group_property_->getStdString().empty())
1217 planning_group_property_->setStdString(groups[0]);
1218
1219 modified_groups_.clear();
1220 kinematics_metrics_ = std::make_shared<kinematics_metrics::KinematicsMetrics>(getRobotModel());
1221
1222 geometry_msgs::msg::Vector3 gravity_vector;
1223 gravity_vector.x = 0.0;
1224 gravity_vector.y = 0.0;
1225 gravity_vector.z = 9.81;
1226
1227 dynamics_solver_.clear();
1228 for (const std::string& group : groups)
1229 {
1230 if (getRobotModel()->getJointModelGroup(group)->isChain())
1231 {
1232 dynamics_solver_[group] =
1233 std::make_shared<dynamics_solver::DynamicsSolver>(getRobotModel(), group, gravity_vector);
1234 }
1235 }
1236
1237 if (frame_)
1238 frame_->fillPlanningGroupOptions();
1239 changedPlanningGroup();
1240}
1242{
1243 frame_->onNewPlanningSceneState();
1244}
1245
1247 const moveit::core::RobotState& src)
1248{
1249 moveit::core::RobotState src_copy = src;
1250 for (const std::string& modified_group : modified_groups_)
1251 {
1252 const moveit::core::JointModelGroup* jmg = dest.getJointModelGroup(modified_group);
1253 if (jmg)
1254 {
1255 std::vector<double> values_to_keep;
1256 dest.copyJointGroupPositions(jmg, values_to_keep);
1257 src_copy.setJointGroupPositions(jmg, values_to_keep);
1258 }
1259 }
1260
1261 // overwrite the destination state
1262 dest = src_copy;
1263}
1264
1266{
1267 std::string group = planning_group_property_->getStdString();
1268
1269 if (query_start_state_ && query_start_state_property_->getBool() && !group.empty())
1270 {
1272 updateStateExceptModified(start, current_state);
1273 setQueryStartState(start);
1274 }
1275
1276 if (query_goal_state_ && query_goal_state_property_->getBool() && !group.empty())
1277 {
1279 updateStateExceptModified(goal, current_state);
1280 setQueryGoalState(goal);
1281 }
1282}
1283
1292
1293// ******************************************************************************************
1294// Enable
1295// ******************************************************************************************
1297{
1299
1300 // Planned Path Display
1301 trajectory_visual_->onEnable();
1302
1303 text_to_display_->setVisible(false);
1304
1305 query_robot_start_->setVisible(query_start_state_property_->getBool());
1306 query_robot_goal_->setVisible(query_goal_state_property_->getBool());
1307
1308 int_marker_display_->setEnabled(true);
1309 int_marker_display_->setFixedFrame(fixed_frame_);
1310
1311 frame_->enable();
1312}
1313
1314// ******************************************************************************************
1315// Disable
1316// ******************************************************************************************
1318{
1320 robot_interaction_->clear();
1321 int_marker_display_->setEnabled(false);
1322
1323 query_robot_start_->setVisible(false);
1324 query_robot_goal_->setVisible(false);
1325 text_to_display_->setVisible(false);
1326
1328
1329 // Planned Path Display
1330 trajectory_visual_->onDisable();
1331
1332 frame_->disable();
1333}
1334
1335// ******************************************************************************************
1336// Update
1337// ******************************************************************************************
1338void MotionPlanningDisplay::update(float wall_dt, float ros_dt)
1339{
1341 int_marker_display_->update(wall_dt, ros_dt);
1342 if (frame_)
1343 frame_->updateSceneMarkers(wall_dt, ros_dt);
1344
1345 PlanningSceneDisplay::update(wall_dt, ros_dt);
1346}
1347
1348void MotionPlanningDisplay::updateInternal(double wall_dt, double ros_dt)
1349{
1350 PlanningSceneDisplay::updateInternal(wall_dt, ros_dt);
1351
1352 // Planned Path Display
1353 trajectory_visual_->update(wall_dt, ros_dt);
1354
1356}
1357
1358void MotionPlanningDisplay::load(const rviz_common::Config& config)
1359{
1361 if (frame_)
1362 {
1363 float d;
1364 if (config.mapGetFloat("MoveIt_Planning_Time", &d))
1365 frame_->ui_->planning_time->setValue(d);
1366 int attempts;
1367 if (config.mapGetInt("MoveIt_Planning_Attempts", &attempts))
1368 frame_->ui_->planning_attempts->setValue(attempts);
1369 if (config.mapGetFloat("Velocity_Scaling_Factor", &d))
1370 frame_->ui_->velocity_scaling_factor->setValue(d);
1371 if (config.mapGetFloat("Acceleration_Scaling_Factor", &d))
1372 frame_->ui_->acceleration_scaling_factor->setValue(d);
1373
1374 bool b;
1375 if (config.mapGetBool("MoveIt_Allow_Replanning", &b))
1376 frame_->ui_->allow_replanning->setChecked(b);
1377 if (config.mapGetBool("MoveIt_Allow_Sensor_Positioning", &b))
1378 frame_->ui_->allow_looking->setChecked(b);
1379 if (config.mapGetBool("MoveIt_Allow_External_Program", &b))
1380 frame_->ui_->allow_external_program->setChecked(b);
1381 if (config.mapGetBool("MoveIt_Use_Cartesian_Path", &b))
1382 frame_->ui_->use_cartesian_path->setChecked(b);
1383 if (config.mapGetBool("MoveIt_Use_Constraint_Aware_IK", &b))
1384 frame_->ui_->collision_aware_ik->setChecked(b);
1385 if (config.mapGetBool("MoveIt_Allow_Approximate_IK", &b))
1386 frame_->ui_->approximate_ik->setChecked(b);
1387
1388 rviz_common::Config workspace = config.mapGetChild("MoveIt_Workspace");
1389 rviz_common::Config ws_center = workspace.mapGetChild("Center");
1390 float val;
1391 if (ws_center.mapGetFloat("X", &val))
1392 frame_->ui_->wcenter_x->setValue(val);
1393 if (ws_center.mapGetFloat("Y", &val))
1394 frame_->ui_->wcenter_y->setValue(val);
1395 if (ws_center.mapGetFloat("Z", &val))
1396 frame_->ui_->wcenter_z->setValue(val);
1397
1398 rviz_common::Config ws_size = workspace.mapGetChild("Size");
1399 if (ws_size.isValid())
1400 {
1401 if (ws_size.mapGetFloat("X", &val))
1402 frame_->ui_->wsize_x->setValue(val);
1403 if (ws_size.mapGetFloat("Y", &val))
1404 frame_->ui_->wsize_y->setValue(val);
1405 if (ws_size.mapGetFloat("Z", &val))
1406 frame_->ui_->wsize_z->setValue(val);
1407 }
1408 else
1409 {
1410 double val;
1411 if (node_->get_parameter("default_workspace_bounds", val))
1412 {
1413 frame_->ui_->wsize_x->setValue(val);
1414 frame_->ui_->wsize_y->setValue(val);
1415 frame_->ui_->wsize_z->setValue(val);
1416 }
1417 }
1418 }
1419}
1420
1421void MotionPlanningDisplay::save(rviz_common::Config config) const
1422{
1424 if (frame_)
1425 {
1426 // "Options" Section
1427 config.mapSetValue("MoveIt_Planning_Time", frame_->ui_->planning_time->value());
1428 config.mapSetValue("MoveIt_Planning_Attempts", frame_->ui_->planning_attempts->value());
1429 config.mapSetValue("Velocity_Scaling_Factor", frame_->ui_->velocity_scaling_factor->value());
1430 config.mapSetValue("Acceleration_Scaling_Factor", frame_->ui_->acceleration_scaling_factor->value());
1431
1432 config.mapSetValue("MoveIt_Allow_Replanning", frame_->ui_->allow_replanning->isChecked());
1433 config.mapSetValue("MoveIt_Allow_Sensor_Positioning", frame_->ui_->allow_looking->isChecked());
1434 config.mapSetValue("MoveIt_Allow_External_Program", frame_->ui_->allow_external_program->isChecked());
1435 config.mapSetValue("MoveIt_Use_Cartesian_Path", frame_->ui_->use_cartesian_path->isChecked());
1436 config.mapSetValue("MoveIt_Use_Constraint_Aware_IK", frame_->ui_->collision_aware_ik->isChecked());
1437 config.mapSetValue("MoveIt_Allow_Approximate_IK", frame_->ui_->approximate_ik->isChecked());
1438
1439 rviz_common::Config workspace = config.mapMakeChild("MoveIt_Workspace");
1440 rviz_common::Config ws_center = workspace.mapMakeChild("Center");
1441 ws_center.mapSetValue("X", frame_->ui_->wcenter_x->value());
1442 ws_center.mapSetValue("Y", frame_->ui_->wcenter_y->value());
1443 ws_center.mapSetValue("Z", frame_->ui_->wcenter_z->value());
1444 rviz_common::Config ws_size = workspace.mapMakeChild("Size");
1445 ws_size.mapSetValue("X", frame_->ui_->wsize_x->value());
1446 ws_size.mapSetValue("Y", frame_->ui_->wsize_y->value());
1447 ws_size.mapSetValue("Z", frame_->ui_->wsize_z->value());
1448 }
1449}
1450
1452{
1455 int_marker_display_->setFixedFrame(fixed_frame_);
1456 // When the fixed frame changes we need to tell RViz to update the rendered interactive marker display
1457 if (frame_ && frame_->scene_marker_)
1458 {
1459 frame_->scene_marker_->requestPoseUpdate(frame_->scene_marker_->getPosition(),
1460 frame_->scene_marker_->getOrientation());
1461 }
1462 changedPlanningGroup();
1463}
1464
1465// Pick and place
1467{
1468 for (std::shared_ptr<rviz_rendering::Shape>& place_location_shape : place_locations_display_)
1469 place_location_shape.reset();
1471}
1472
1473void MotionPlanningDisplay::visualizePlaceLocations(const std::vector<geometry_msgs::msg::PoseStamped>& place_poses)
1474{
1476 place_locations_display_.resize(place_poses.size());
1477 for (std::size_t i = 0; i < place_poses.size(); ++i)
1478 {
1480 std::make_shared<rviz_rendering::Shape>(rviz_rendering::Shape::Sphere, context_->getSceneManager());
1481 place_locations_display_[i]->setColor(1.0f, 0.0f, 0.0f, 0.3f);
1482 Ogre::Vector3 center(place_poses[i].pose.position.x, place_poses[i].pose.position.y, place_poses[i].pose.position.z);
1483 Ogre::Vector3 extents(0.02, 0.02, 0.02);
1484 place_locations_display_[i]->setScale(extents);
1485 place_locations_display_[i]->setPosition(center);
1486 }
1487}
1488
1489} // namespace moveit_rviz_plugin
const std::string & getName() const
Get the name of the joint group.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this joint group.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
void clearJobUpdateEvent()
Clear the callback to be triggered when events in JobEvent take place.
void setJobUpdateEvent(const JobUpdateCallback &event)
Set the callback to be triggered when events in JobEvent take place.
std::size_t getJobCount() const
Get the size of the queue of jobs (includes currently processed job).
void populateMenuHandler(std::shared_ptr< interactive_markers::MenuHandler > &mh)
RobotStateVisualizationPtr query_robot_start_
Handles drawing the robot at the start configuration.
void scheduleDrawQueryGoalState(robot_interaction::InteractionHandler *handler, bool error_state_changed)
kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_
rviz_common::properties::FloatProperty * metrics_text_height_property_
void onNewPlanningSceneState() override
This is called upon successful retrieval of the (initial) planning scene state.
void save(rviz_common::Config config) const override
moveit::core::RobotStatePtr previous_state_
remember previous start state (updated before starting execution)
void updateInternal(double wall_dt, double ros_dt) override
void backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent event, const std::string &jobname)
rviz_common::properties::BoolProperty * show_joint_torques_property_
void displayTable(const std::map< std::string, double > &values, const Ogre::ColourValue &color, const Ogre::Vector3 &pos, const Ogre::Quaternion &orient)
rviz_common::properties::FloatProperty * query_marker_scale_property_
void updateStateExceptModified(moveit::core::RobotState &dest, const moveit::core::RobotState &src)
bool text_display_for_start_
indicates whether the text display is for the start state or not
robot_interaction::RobotInteractionPtr robot_interaction_
rviz_common::properties::BoolProperty * show_manipulability_property_
void setQueryGoalState(const moveit::core::RobotState &goal)
robot_interaction::InteractionHandlerPtr query_start_state_
std::map< std::string, LinkDisplayStatus > status_links_goal_
void setQueryStartState(const moveit::core::RobotState &start)
rviz_common::properties::ColorProperty * query_outside_joint_limits_link_color_property_
rviz_common::properties::FloatProperty * query_goal_alpha_property_
rviz_common::properties::ColorProperty * query_start_color_property_
void computeMetricsInternal(std::map< std::string, double > &metrics, const robot_interaction::EndEffectorInteraction &eef, const moveit::core::RobotState &state, double payload)
void computeMetrics(bool start, const std::string &group, double payload)
rviz_common::properties::Property * path_category_
rviz_common::properties::FloatProperty * metrics_set_payload_property_
void setQueryStateHelper(bool use_start_state, const std::string &v)
std::map< std::string, bool > position_only_ik_
Some groups use position only ik, calls to the metrics have to be modified appropriately.
rviz_common::properties::ColorProperty * query_goal_color_property_
rviz_common::properties::BoolProperty * compute_weight_limit_property_
std::unique_ptr< rviz_rendering::Shape > workspace_box_
std::map< std::pair< bool, std::string >, std::map< std::string, double > > computed_metrics_
std::map< std::string, LinkDisplayStatus > status_links_start_
Ogre::SceneNode * text_display_scene_node_
displays texts
void updateQueryStates(const moveit::core::RobotState &current_state)
rviz_common::properties::EditableEnumProperty * planning_group_property_
rviz_common::properties::BoolProperty * show_manipulability_index_property_
rviz_common::properties::Property * metrics_category_
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_start_
void scheduleDrawQueryStartState(robot_interaction::InteractionHandler *handler, bool error_state_changed)
std::map< std::string, dynamics_solver::DynamicsSolverPtr > dynamics_solver_
moveit::core::RobotStateConstPtr getQueryStartState() const
rviz_common::properties::BoolProperty * show_workspace_property_
rviz_common::properties::BoolProperty * query_goal_state_property_
void load(const rviz_common::Config &config) override
bool isIKSolutionCollisionFree(moveit::core::RobotState *state, const moveit::core::JointModelGroup *group, const double *ik_solution) const
rviz_common::properties::FloatProperty * query_start_alpha_property_
std::vector< std::shared_ptr< rviz_rendering::Shape > > place_locations_display_
RobotStateVisualizationPtr query_robot_goal_
Handles drawing the robot at the goal configuration.
void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) override
void update(float wall_dt, float ros_dt) override
rviz_common::properties::BoolProperty * query_start_state_property_
rviz_common::properties::Property * plan_category_
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_goal_
rclcpp::Subscription< std_msgs::msg::String >::SharedPtr planning_group_sub_
void selectPlanningGroupCallback(const std_msgs::msg::String::ConstSharedPtr &msg)
void onRobotModelLoaded() override
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
rviz_common::properties::ColorProperty * query_colliding_link_color_property_
void visualizePlaceLocations(const std::vector< geometry_msgs::msg::PoseStamped > &place_poses)
moveit::core::RobotStateConstPtr getQueryGoalState() const
robot_interaction::InteractionHandlerPtr query_goal_state_
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
void updateSceneMarkers(double wall_dt, double ros_dt)
void sceneUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
planning_scene_monitor::LockedPlanningSceneRO getPlanningSceneRO() const
get read-only access to planning scene
rviz_common::properties::ColorProperty * attached_body_color_property_
void setLinkColor(const std::string &link_name, const QColor &color)
void save(rviz_common::Config config) const override
virtual void updateInternal(double wall_dt, double ros_dt)
virtual void onRobotModelLoaded()
This is an event called by loadRobotModel() in the MainLoop; do not call directly.
void setGroupColor(rviz_default_plugins::robot::Robot *robot, const std::string &group_name, const QColor &color)
virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
void addMainLoopJob(const std::function< void()> &job)
queue the execution of this function for the next time the main update() loop gets called
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
const moveit::core::RobotModelConstPtr & getRobotModel() const
void addBackgroundJob(const std::function< void()> &job, const std::string &name)
void update(float wall_dt, float ros_dt) override
void unsetAllColors(rviz_default_plugins::robot::Robot *robot)
Ogre::SceneNode * planning_scene_node_
displays planning scene with everything in it
moveit::tools::BackgroundProcessing background_process_
void load(const rviz_common::Config &config) override
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
static const std::string DEFAULT
When used as key this means the default value.
static const std::string ALL
When used as key this means set ALL keys (including default)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::string append(const std::string &left, const std::string &right)
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
kinematics::KinematicsQueryOptions options_
other options
moveit::core::GroupStateValidityCallbackFn state_validity_callback_
This is called to determine if the state is valid.