moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
motion_planning_display.hpp
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
37#pragma once
38
39#include <rclcpp/rclcpp.hpp>
40#include <rclcpp/version.h>
41
42#include <rviz_common/display.hpp>
43#include <rviz_common/panel_dock_widget.hpp>
46
47#ifndef Q_MOC_RUN
51
55
56#include <std_msgs/msg/string.hpp>
57#include <moveit_msgs/msg/display_trajectory.hpp>
58#endif
59
60#include <chrono>
61#include <memory>
62
63namespace Ogre
64{
65class SceneNode;
66}
67
69{
70class Shape;
71class MovableText;
72} // namespace rviz_rendering
73
74namespace rviz_common
75{
76namespace properties
77{
78class Property;
79class StringProperty;
80class BoolProperty;
81class FloatProperty;
82class RosTopicProperty;
83class EditableEnumProperty;
84class ColorProperty;
85class MovableText;
86} // namespace properties
87} // namespace rviz_common
88
90{
91namespace robot
92{
93class Robot;
94}
95} // namespace rviz_default_plugins
96
98{
100{
101 Q_OBJECT
102
103public:
105
106 ~MotionPlanningDisplay() override;
107
108 void load(const rviz_common::Config& config) override;
109 void save(rviz_common::Config config) const override;
110
111// For Rolling, L-turtle, and newer
112#if RCLCPP_VERSION_GTE(30, 0, 0)
113 using rviz_common::Display::update;
114 // `using` handles update(float, float) deprecation warning and redirect
115 void update(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt) override;
116// For Kilted and older
117#else
118 void update(float wall_dt, float ros_dt) override;
119#endif
120
121 void reset() override;
122
123 moveit::core::RobotStateConstPtr getQueryStartState() const
124 {
125 return query_start_state_->getState();
126 }
127
128 moveit::core::RobotStateConstPtr getQueryGoalState() const
129 {
130 return query_goal_state_->getState();
131 }
132
134 {
135 return *previous_state_;
136 }
137
138 const robot_interaction::RobotInteractionPtr& getRobotInteraction() const
139 {
140 return robot_interaction_;
141 }
142
143 const robot_interaction::InteractionHandlerPtr& getQueryStartStateHandler() const
144 {
145 return query_start_state_;
146 }
147
148 const robot_interaction::InteractionHandlerPtr& getQueryGoalStateHandler() const
149 {
150 return query_goal_state_;
151 }
152
154 {
155 trajectory_visual_->dropTrajectory();
156 }
157
160
161 void updateQueryStates(const moveit::core::RobotState& current_state);
165
166 void useApproximateIK(bool flag);
167
168 // Pick Place
170 void visualizePlaceLocations(const std::vector<geometry_msgs::msg::PoseStamped>& place_poses);
171 std::vector<std::shared_ptr<rviz_rendering::Shape> > place_locations_display_;
172
173 std::string getCurrentPlanningGroup() const;
174
175 void changePlanningGroup(const std::string& group);
176
177 void addStatusText(const std::string& text);
178 void addStatusText(const std::vector<std::string>& text);
179 void setStatusTextColor(const QColor& color);
181
183
184Q_SIGNALS:
185 // signals issued when start/goal states of a query changed
188
189private Q_SLOTS:
190
191 // ******************************************************************************************
192 // Slot Event Functions
193 // ******************************************************************************************
194
195 void changedQueryStartState();
196 void changedQueryGoalState();
197 void changedQueryMarkerScale();
198 void changedQueryStartColor();
199 void changedQueryGoalColor();
200 void changedQueryStartAlpha();
201 void changedQueryGoalAlpha();
202 void changedQueryCollidingLinkColor();
203 void changedQueryJointViolationColor();
204 void changedAttachedBodyColor() override;
205 void changedPlanningGroup();
206 void changedShowWeightLimit();
207 void changedShowManipulabilityIndex();
208 void changedShowManipulability();
209 void changedShowJointTorques();
210 void changedMetricsSetPayload();
211 void changedMetricsTextHeight();
212 void changedWorkspace();
213 void resetInteractiveMarkers();
214 void motionPanelVisibilityChange(bool enable);
215
216protected:
222
223 void clearRobotModel() override;
224 void onRobotModelLoaded() override;
225 void onNewPlanningSceneState() override;
227 void updateInternal(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt) override;
228// For Rolling, L-turtle, and newer
229#if RCLCPP_VERSION_GTE(30, 0, 0)
230 [[deprecated("Use updateInternal(std::chrono::nanoseconds, std::chrono::nanoseconds) instead")]] void
231 updateInternal(double wall_dt, double ros_dt) override;
232// For Kilted and older
233#else
234 void updateInternal(double wall_dt, double ros_dt) override;
235#endif
236
237 void renderWorkspaceBox();
238 void updateLinkColors();
239
240 void displayTable(const std::map<std::string, double>& values, const Ogre::ColourValue& color,
241 const Ogre::Vector3& pos, const Ogre::Quaternion& orient);
242 void displayMetrics(bool start);
243
245 void publishInteractiveMarkers(bool pose_update);
246
249 void drawQueryStartState();
250 void drawQueryGoalState();
251 void scheduleDrawQueryStartState(robot_interaction::InteractionHandler* handler, bool error_state_changed);
252 void scheduleDrawQueryGoalState(robot_interaction::InteractionHandler* handler, bool error_state_changed);
253
255 const double* ik_solution) const;
256
257 void computeMetrics(bool start, const std::string& group, double payload);
258 void computeMetricsInternal(std::map<std::string, double>& metrics,
260 const moveit::core::RobotState& state, double payload);
263 void backgroundJobUpdate(moveit::tools::BackgroundProcessing::JobEvent event, const std::string& jobname);
264
265 void setQueryStateHelper(bool use_start_state, const std::string& v);
266 void populateMenuHandler(std::shared_ptr<interactive_markers::MenuHandler>& mh);
267
268 void selectPlanningGroupCallback(const std_msgs::msg::String::ConstSharedPtr& msg);
269
270 // overrides from Display
271 void onInitialize() override;
272 void onEnable() override;
273 void onDisable() override;
274 void fixedFrameChanged() override;
275
276 RobotStateVisualizationPtr query_robot_start_;
277 RobotStateVisualizationPtr query_robot_goal_;
278
279 Ogre::SceneNode* text_display_scene_node_;
281 rviz_rendering::MovableText* text_to_display_;
282
283 rclcpp::Subscription<std_msgs::msg::String>::SharedPtr planning_group_sub_;
284
285 // render the workspace box
286 std::unique_ptr<rviz_rendering::Shape> workspace_box_;
287
288 // the planning frame
290 rviz_common::PanelDockWidget* frame_dock_;
291
292 // robot interaction
293 robot_interaction::RobotInteractionPtr robot_interaction_;
294 robot_interaction::InteractionHandlerPtr query_start_state_;
295 robot_interaction::InteractionHandlerPtr query_goal_state_;
296 std::shared_ptr<interactive_markers::MenuHandler> menu_handler_start_;
297 std::shared_ptr<interactive_markers::MenuHandler> menu_handler_goal_;
298 std::map<std::string, LinkDisplayStatus> status_links_start_;
299 std::map<std::string, LinkDisplayStatus> status_links_goal_;
301 moveit::core::RobotStatePtr previous_state_;
302
305 std::set<std::string> modified_groups_;
306
309 std::map<std::pair<bool, std::string>, std::map<std::string, double> > computed_metrics_;
311 std::map<std::string, bool> position_only_ik_;
312
313 // Metric calculations
314 kinematics_metrics::KinematicsMetricsPtr kinematics_metrics_;
315 std::map<std::string, dynamics_solver::DynamicsSolverPtr> dynamics_solver_;
317
318 // The trajectory playback component
319 TrajectoryVisualizationPtr trajectory_visual_;
320
321 // properties to show on side panel
322 rviz_common::properties::Property* path_category_;
323 rviz_common::properties::Property* plan_category_;
324 rviz_common::properties::Property* metrics_category_;
325
326 rviz_common::properties::EditableEnumProperty* planning_group_property_;
327 rviz_common::properties::BoolProperty* query_start_state_property_;
328 rviz_common::properties::BoolProperty* query_goal_state_property_;
329 rviz_common::properties::FloatProperty* query_marker_scale_property_;
330 rviz_common::properties::ColorProperty* query_start_color_property_;
331 rviz_common::properties::ColorProperty* query_goal_color_property_;
332 rviz_common::properties::FloatProperty* query_start_alpha_property_;
333 rviz_common::properties::FloatProperty* query_goal_alpha_property_;
334 rviz_common::properties::ColorProperty* query_colliding_link_color_property_;
335 rviz_common::properties::ColorProperty* query_outside_joint_limits_link_color_property_;
336
337 rviz_common::properties::BoolProperty* compute_weight_limit_property_;
338 rviz_common::properties::BoolProperty* show_manipulability_index_property_;
339 rviz_common::properties::BoolProperty* show_manipulability_property_;
340 rviz_common::properties::BoolProperty* show_joint_torques_property_;
341 rviz_common::properties::FloatProperty* metrics_set_payload_property_;
342 rviz_common::properties::FloatProperty* metrics_text_height_property_;
343 rviz_common::properties::BoolProperty* show_workspace_property_;
344
345 rviz_common::Display* int_marker_display_;
346};
347
348} // namespace moveit_rviz_plugin
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 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)
const moveit::core::RobotState & getPreviousState() const
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)
void updateInternal(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt) override
robot_interaction::InteractionHandlerPtr query_start_state_
std::map< std::string, LinkDisplayStatus > status_links_goal_
void setQueryStartState(const moveit::core::RobotState &start)
const robot_interaction::InteractionHandlerPtr & getQueryGoalStateHandler() const
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
const robot_interaction::RobotInteractionPtr & getRobotInteraction() const
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_
const robot_interaction::InteractionHandlerPtr & getQueryStartStateHandler() const
void visualizePlaceLocations(const std::vector< geometry_msgs::msg::PoseStamped > &place_poses)
moveit::core::RobotStateConstPtr getQueryGoalState() const
robot_interaction::InteractionHandlerPtr query_goal_state_