43 #include <rviz_default_plugins/robot/robot.hpp>
44 #include <rviz_default_plugins/robot/robot_link.hpp>
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>
61 #include <OgreSceneManager.h>
62 #include <OgreSceneNode.h>
63 #include <rviz_rendering/objects/shape.hpp>
70 #include "ui_motion_planning_rviz_plugin_frame.h"
82 , text_to_display_(nullptr)
84 , frame_dock_(nullptr)
87 , int_marker_display_(nullptr)
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);
96 new rviz_common::properties::BoolProperty(
"Show Weight Limit",
false,
97 "Shows the weight limit at a particular pose for an end-effector",
101 new rviz_common::properties::BoolProperty(
"Show Manipulability Index",
false,
103 SLOT(changedShowManipulabilityIndex()),
this);
106 new rviz_common::properties::BoolProperty(
"Show Manipulability",
false,
108 SLOT(changedShowManipulability()),
this);
111 new rviz_common::properties::BoolProperty(
"Show Joint Torques",
false,
112 "Shows the joint torques for a given configuration and payload",
116 new rviz_common::properties::FloatProperty(
"Payload", 1.0f,
"Specify the payload at the end effector (kg)",
121 "TextHeight", 0.08f,
"Text height",
metrics_category_, SLOT(changedMetricsTextHeight()),
this);
127 "Planning Group",
"",
"The name of the group of links to plan for (from the ones defined in the SRDF)",
130 "Shows the axis-aligned bounding box for "
131 "the workspace allowed for planning",
134 new rviz_common::properties::BoolProperty(
"Query Start State",
false,
135 "Set a custom start state for the motion planning query",
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);
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);
148 new rviz_common::properties::ColorProperty(
"Start State Color", QColor(0, 255, 0),
150 SLOT(changedQueryStartColor()),
this);
152 new rviz_common::properties::FloatProperty(
"Start State Alpha", 1.0f,
"Specifies the alpha for the robot links",
158 new rviz_common::properties::ColorProperty(
"Goal State Color", QColor(250, 128, 0),
160 SLOT(changedQueryGoalColor()),
this);
163 new rviz_common::properties::FloatProperty(
"Goal State Alpha", 1.0f,
"Specifies the alpha for the robot links",
169 new rviz_common::properties::ColorProperty(
"Colliding Link Color", QColor(255, 0, 0),
171 SLOT(changedQueryCollidingLinkColor()),
this);
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);
212 std::make_shared<RobotStateVisualization>(
planning_scene_node_, context_,
"Planning Request Start",
nullptr);
216 std_msgs::msg::ColorRGBA color;
218 color.r = qcolor.redF();
219 color.g = qcolor.greenF();
220 color.b = qcolor.blueF();
225 std::make_shared<RobotStateVisualization>(
planning_scene_node_, context_,
"Planning Request Goal",
nullptr);
230 color.r = qcolor.redF();
231 color.g = qcolor.greenF();
232 color.b = qcolor.blueF();
235 rviz_common::WindowManagerInterface* window_context = context_->getWindowManager();
238 connect(
frame_, SIGNAL(configChanged()), getModel(), SIGNAL(configChanged()));
248 connect(
frame_dock_, SIGNAL(visibilityChanged(
bool)),
this, SLOT(motionPanelVisibilityChange(
bool)));
257 text_to_display_->setTextAlignment(rviz_rendering::MovableText::H_CENTER, rviz_rendering::MovableText::V_CENTER);
264 if (context_ && context_->getWindowManager() && context_->getWindowManager()->getParentWindow())
266 QShortcut* im_reset_shortcut =
267 new QShortcut(QKeySequence(
"Ctrl+I"), context_->getWindowManager()->getParentWindow());
268 connect(im_reset_shortcut, SIGNAL(activated()),
this, SLOT(resetInteractiveMarkers()));
272 void MotionPlanningDisplay::motionPanelVisibilityChange(
bool enable)
283 "/rviz/moveit/select_planning_group", rclcpp::SystemDefaultsQoS(),
295 addMainLoopJob([
this, group = msg->data] { changePlanningGroup(group); });
310 bool enabled = isEnabled();
330 QProgressBar* p =
frame_->
ui_->background_job_progress;
341 if (p->maximum() < n)
348 p->setValue(p->maximum() - n);
353 void MotionPlanningDisplay::changedShowWeightLimit()
367 void MotionPlanningDisplay::changedShowManipulabilityIndex()
381 void MotionPlanningDisplay::changedShowManipulability()
395 void MotionPlanningDisplay::changedShowJointTorques()
409 void MotionPlanningDisplay::changedMetricsSetPayload()
423 void MotionPlanningDisplay::changedMetricsTextHeight()
429 const Ogre::Vector3& pos,
const Ogre::Quaternion& orient)
438 std::stringstream ss;
439 ss.setf(std::ios_base::fixed);
442 for (
const auto& [label, value] : values)
443 ss << label <<
':' << value <<
'\n';
465 workspace_box_ = std::make_unique<rviz_rendering::Shape>(rviz_rendering::Shape::Cube, context_->getSceneManager(),
470 Ogre::Vector3 center(
frame_->
ui_->wcenter_x->value(),
frame_->
ui_->wcenter_y->value(),
481 const std::vector<robot_interaction::EndEffectorInteraction>& eef =
robot_interaction_->getActiveEndEffectors();
489 if (ee.parent_group == group)
499 dynamics_solver::DynamicsSolverPtr ds;
508 unsigned int saturated_joint;
509 std::vector<double> joint_values;
511 if (ds->getMaxPayload(joint_values, max_payload, saturated_joint))
513 metrics[
"max_payload"] = max_payload;
514 metrics[
"saturated_joint"] = saturated_joint;
516 std::vector<double> joint_torques;
517 joint_torques.resize(joint_values.size());
518 if (ds->getPayloadTorques(joint_values, payload, joint_torques))
520 for (std::size_t i = 0; i < joint_torques.size(); ++i)
522 std::stringstream stream;
523 stream <<
"torque[" << i <<
']';
524 metrics[stream.str()] = joint_torques[i];
534 double manipulability_index, manipulability;
537 metrics[
"manipulability_index"] = manipulability_index;
539 metrics[
"manipulability"] = manipulability;
545 inline void copyItemIfExists(
const std::map<std::string, double>& source, std::map<std::string, double>&
dest,
546 const std::string& key)
548 std::map<std::string, double>::const_iterator it = source.find(key);
549 if (it != source.end())
550 dest[key] = it->second;
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();
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)];
573 copyItemIfExists(metrics_table, text_table,
"max_payload");
574 copyItemIfExists(metrics_table, text_table,
"saturated_joint");
577 copyItemIfExists(metrics_table, text_table,
"manipulability_index");
579 copyItemIfExists(metrics_table, text_table,
"manipulability");
582 std::size_t nj =
getRobotModel()->getJointModelGroup(ee.parent_group)->getJointModelNames().size();
583 for (
size_t j = 0; j < nj; ++j)
585 std::stringstream stream;
586 stream <<
"torque[" << j <<
']';
587 copyItemIfExists(metrics_table, text_table, stream.str());
600 const Eigen::Vector3d& t = state->getGlobalLinkTransform(lm).translation();
603 position[2] = t.z() + 0.2;
633 std::vector<std::string> collision_links;
636 for (
const std::string& collision_link : collision_links)
638 if (!collision_links.empty())
644 for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
654 std::vector<std::string> outside_bounds;
658 if (!state->satisfiesBounds(jmodel, jmodel->getMaximumExtent() * 1e-2))
660 outside_bounds.push_back(jmodel->getChildLinkModel()->getName());
664 if (!outside_bounds.empty())
667 addStatusText(
"Links descending from joints that are outside bounds in start state:");
679 context_->queueRender();
690 frame_->
ui_->status_text->setTextColor(color);
696 frame_->
ui_->status_text->append(QString::fromStdString(
text));
701 for (
const std::string& it :
text)
719 void MotionPlanningDisplay::changedQueryStartState()
729 void MotionPlanningDisplay::changedQueryGoalState()
754 std::vector<std::string> collision_links;
757 for (
const std::string& collision_link : collision_links)
759 if (!collision_links.empty())
765 for (collision_detection::CollisionResult::ContactMap::const_iterator it = pairs.begin(); it != pairs.end();
777 std::vector<std::string> outside_bounds;
780 if (!state->satisfiesBounds(jmodel, jmodel->getMaximumExtent() * 1e-2))
782 outside_bounds.push_back(jmodel->getChildLinkModel()->getName());
787 if (!outside_bounds.empty())
790 addStatusText(
"Links descending from joints that are outside bounds in goal state:");
803 context_->queueRender();
806 void MotionPlanningDisplay::resetInteractiveMarkers()
842 void MotionPlanningDisplay::changedQueryStartColor()
844 std_msgs::msg::ColorRGBA color;
846 color.r = qcolor.redF();
847 color.g = qcolor.greenF();
848 color.b = qcolor.blueF();
851 changedQueryStartState();
854 void MotionPlanningDisplay::changedQueryStartAlpha()
857 changedQueryStartState();
860 void MotionPlanningDisplay::changedQueryMarkerScale()
872 void MotionPlanningDisplay::changedQueryGoalColor()
874 std_msgs::msg::ColorRGBA color;
876 color.r = qcolor.redF();
877 color.g = qcolor.greenF();
878 color.b = qcolor.blueF();
881 changedQueryGoalState();
884 void MotionPlanningDisplay::changedQueryGoalAlpha()
887 changedQueryGoalState();
890 void MotionPlanningDisplay::changedQueryCollidingLinkColor()
892 changedQueryStartState();
893 changedQueryGoalState();
896 void MotionPlanningDisplay::changedQueryJointViolationColor()
898 changedQueryStartState();
899 changedQueryGoalState();
902 void MotionPlanningDisplay::changedAttachedBodyColor()
911 bool error_state_changed)
916 "publishInteractiveMarkers");
921 bool error_state_changed)
926 "publishInteractiveMarkers");
935 context_->queueRender();
943 context_->queueRender();
977 const double* ik_solution)
const
1000 for (std::map<std::string, LinkDisplayStatus>::const_iterator it =
status_links_start_.begin();
1014 for (std::map<std::string, LinkDisplayStatus>::const_iterator it =
status_links_goal_.begin();
1041 RCLCPP_ERROR(
moveit::getLogger(
"moveit.ros.motion_planning_display"),
"Group [%s] not found in the robot model.",
1046 void MotionPlanningDisplay::changedPlanningGroup()
1070 void MotionPlanningDisplay::changedWorkspace()
1084 std::string v =
"<" + state_name +
">";
1086 if (v ==
"<random>")
1091 else if (v ==
"<current>")
1095 state = ps->getCurrentState();
1097 else if (v ==
"<same as goal>")
1101 else if (v ==
"<same as start>")
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");
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)
1133 if ((state_name ==
"same as start" && is_start) || (state_name ==
"same as goal" && !is_start))
1135 mh->insert(menu_states, state_name,
1174 const double* joint_group_variable_values) {
1211 const std::vector<std::string>& groups =
getRobotModel()->getJointModelGroupNames();
1213 for (
const std::string& group : groups)
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;
1228 for (
const std::string& group : groups)
1233 std::make_shared<dynamics_solver::DynamicsSolver>(
getRobotModel(), group, gravity_vector);
1238 frame_->fillPlanningGroupOptions();
1239 changedPlanningGroup();
1243 frame_->onNewPlanningSceneState();
1255 std::vector<double> values_to_keep;
1256 dest.copyJointGroupPositions(jmg, values_to_keep);
1364 if (config.mapGetFloat(
"MoveIt_Planning_Time", &d))
1365 frame_->
ui_->planning_time->setValue(d);
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);
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);
1388 rviz_common::Config workspace = config.mapGetChild(
"MoveIt_Workspace");
1389 rviz_common::Config ws_center = workspace.mapGetChild(
"Center");
1391 if (ws_center.mapGetFloat(
"X", &val))
1393 if (ws_center.mapGetFloat(
"Y", &val))
1395 if (ws_center.mapGetFloat(
"Z", &val))
1398 rviz_common::Config ws_size = workspace.mapGetChild(
"Size");
1399 if (ws_size.isValid())
1401 if (ws_size.mapGetFloat(
"X", &val))
1403 if (ws_size.mapGetFloat(
"Y", &val))
1405 if (ws_size.mapGetFloat(
"Z", &val))
1411 if (
node_->get_parameter(
"default_workspace_bounds", val))
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());
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());
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());
1462 changedPlanningGroup();
1469 place_location_shape.reset();
1477 for (std::size_t i = 0; i < place_poses.size(); ++i)
1480 std::make_shared<rviz_rendering::Shape>(rviz_rendering::Shape::Sphere, context_->getSceneManager());
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);
const std::vector< std::string > & getLinkModelNames() const
Get the names of the links that are part of this 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::string & getName() const
Get the name of the 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.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 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_
void changePlanningGroup(const std::string &group)
rviz_common::properties::FloatProperty * metrics_text_height_property_
std::string getCurrentPlanningGroup() const
void onNewPlanningSceneState() override
This is called upon successful retrieval of the (initial) planning scene state.
void queryGoalStateChanged()
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_
rviz_common::PanelDockWidget * frame_dock_
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)
void recomputeQueryStartStateMetrics()
bool text_display_for_start_
indicates whether the text display is for the start state or not
robot_interaction::RobotInteractionPtr robot_interaction_
void updateQueryGoalState()
rviz_common::properties::BoolProperty * show_manipulability_property_
void setQueryGoalState(const moveit::core::RobotState &goal)
robot_interaction::InteractionHandlerPtr query_start_state_
void drawQueryStartState()
void setStatusTextColor(const QColor &color)
std::map< std::string, LinkDisplayStatus > status_links_goal_
void clearRobotModel() override
void setQueryStartState(const moveit::core::RobotState &start)
void drawQueryGoalState()
rviz_common::properties::ColorProperty * query_outside_joint_limits_link_color_property_
void updateQueryStartState()
rviz_common::properties::FloatProperty * query_goal_alpha_property_
rviz_common::properties::ColorProperty * query_start_color_property_
void updateBackgroundJobProgressBar()
void computeMetricsInternal(std::map< std::string, double > &metrics, const robot_interaction::EndEffectorInteraction &eef, const moveit::core::RobotState &state, double payload)
void onInitialize() override
void computeMetrics(bool start, const std::string &group, double payload)
TrajectoryVisualizationPtr trajectory_visual_
rviz_rendering::MovableText * text_to_display_
rviz_common::properties::Property * path_category_
void queryStartStateChanged()
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_
void fixedFrameChanged() override
void renderWorkspaceBox()
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
rviz_common::Display * int_marker_display_
void useApproximateIK(bool flag)
void updateQueryStates(const moveit::core::RobotState ¤t_state)
rviz_common::properties::EditableEnumProperty * planning_group_property_
rviz_common::properties::BoolProperty * show_manipulability_index_property_
void resetStatusTextColor()
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::set< std::string > modified_groups_
std::map< std::string, dynamics_solver::DynamicsSolverPtr > dynamics_solver_
std::mutex update_metrics_lock_
moveit::core::RobotStateConstPtr getQueryStartState() const
void toggleSelectPlanningGroupSubscription(bool enable)
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_
void onDisable() override
std::vector< std::shared_ptr< rviz_rendering::Shape > > place_locations_display_
RobotStateVisualizationPtr query_robot_goal_
Handles drawing the robot at the goal configuration.
void rememberPreviousStartState()
void addStatusText(const std::string &text)
MotionPlanningFrame * frame_
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 recomputeQueryGoalStateMetrics()
void selectPlanningGroupCallback(const std_msgs::msg::String::ConstSharedPtr &msg)
void publishInteractiveMarkers(bool pose_update)
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)
void clearPlaceLocationsDisplay()
~MotionPlanningDisplay() override
moveit::core::RobotStateConstPtr getQueryGoalState() const
void displayMetrics(bool start)
robot_interaction::InteractionHandlerPtr query_goal_state_
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
Ui::MotionPlanningUI * ui_
void updateExternalCommunication()
void changePlanningGroup()
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
rclcpp::Node::SharedPtr node_
void fixedFrameChanged() override
rviz_common::properties::ColorProperty * attached_body_color_property_
void setLinkColor(const std::string &link_name, const QColor &color)
const std::string getMoveGroupNS() const
void onInitialize() override
void save(rviz_common::Config config) const override
virtual void clearRobotModel()
virtual void updateInternal(double wall_dt, double ros_dt)
void onDisable() override
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 clearJobs()
remove all queued jobs
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_
virtual void changedAttachedBodyColor()
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)
Displays Interactive Markers.
Vec3fX< details::Vec3Data< double > > Vector3d
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.
bool return_approximate_solution
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
kinematics::KinematicsQueryOptions options_
other options
@ RETURN_APPROXIMATE_SOLUTION
@ STATE_VALIDITY_CALLBACK
moveit::core::GroupStateValidityCallbackFn state_validity_callback_
This is called to determine if the state is valid.