moveit2
The MoveIt Motion Planning Framework for ROS 2.
motion_planning_frame.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 */
36 
37 #pragma once
38 
39 #include <QWidget>
40 #include <QTreeWidgetItem>
41 #include <QListWidgetItem>
42 
43 #ifndef Q_MOC_RUN
49 // TODO (ddengster): Enable when moveit_ros_perception is ported
50 // #include <moveit/semantic_world/semantic_world.h>
51 
52 #include <interactive_markers/interactive_marker_server.hpp>
53 #include <rviz_default_plugins/displays/interactive_markers/interactive_marker.hpp>
54 #include <moveit_msgs/msg/motion_plan_request.hpp>
55 #include <rclcpp_action/rclcpp_action.hpp>
56 #include <object_recognition_msgs/action/object_recognition.hpp>
57 
58 #include <std_msgs/msg/bool.hpp>
59 #include <std_msgs/msg/empty.hpp>
60 #include <std_srvs/srv/empty.hpp>
61 #endif
62 
63 #include <map>
64 #include <string>
65 #include <memory>
66 
67 namespace rviz_common
68 {
69 class DisplayContext;
70 }
71 
72 namespace Ui
73 {
74 class MotionPlanningUI;
75 }
76 
78 {
79 MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc
80 MOVEIT_CLASS_FORWARD(ConstraintsStorage); // Defines ConstraintsStoragePtr, ConstPtr, WeakPtr... etc
81 MOVEIT_CLASS_FORWARD(RobotStateStorage); // Defines RobotStateStoragePtr, ConstPtr, WeakPtr... etc
82 } // namespace moveit_warehouse
83 
84 namespace moveit_rviz_plugin
85 {
86 class MotionPlanningDisplay;
87 class MotionPlanningFrameJointsWidget;
88 
89 const std::string OBJECT_RECOGNITION_ACTION = "/recognize_objects";
90 
91 static const std::string TAB_CONTEXT = "Context";
92 static const std::string TAB_PLANNING = "Planning";
93 static const std::string TAB_MANIPULATION = "Manipulation";
94 static const std::string TAB_OBJECTS = "Scene Objects";
95 static const std::string TAB_SCENES = "Stored Scenes";
96 static const std::string TAB_STATES = "Stored States";
97 static const std::string TAB_STATUS = "Status";
98 
99 static const double LARGE_MESH_THRESHOLD = 10.0;
100 
101 class MotionPlanningFrame : public QWidget
102 {
103  friend class MotionPlanningDisplay;
104  Q_OBJECT
105 
106 public:
108  MotionPlanningFrame(MotionPlanningDisplay* pdisplay, rviz_common::DisplayContext* context, QWidget* parent = nullptr);
109  ~MotionPlanningFrame() override;
110 
111  void clearRobotModel();
112  void changePlanningGroup();
113  void enable();
114  void disable();
116 
117 protected:
118  static const int ITEM_TYPE_SCENE = 1;
119  static const int ITEM_TYPE_QUERY = 2;
120 
121  void initFromMoveGroupNS();
123 
124  void updateSceneMarkers(float wall_dt, float ros_dt);
125 
127 
129  rviz_common::DisplayContext* context_;
130  Ui::MotionPlanningUI* ui_;
132 
133  moveit::planning_interface::MoveGroupInterfacePtr move_group_;
134  // TODO (ddengster): Enable when moveit_ros_perception is ported
135  // moveit::semantic_world::SemanticWorldPtr semantic_world_;
136 
137  moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_;
138  moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_;
139  moveit_warehouse::ConstraintsStoragePtr constraints_storage_;
140  moveit_warehouse::RobotStateStoragePtr robot_state_storage_;
141 
142  std::shared_ptr<rviz_default_plugins::displays::InteractiveMarker> scene_marker_;
143 
144  typedef std::map<std::string, moveit_msgs::msg::RobotState> RobotStateMap;
145  typedef std::pair<std::string, moveit_msgs::msg::RobotState> RobotStatePair;
148  std::vector<moveit_msgs::msg::PlannerInterfaceDescription> planner_descriptions_;
149 
150 Q_SIGNALS:
153 
154 private Q_SLOTS:
155 
156  // Context tab
157  void databaseConnectButtonClicked();
158  void planningPipelineIndexChanged(int index);
159  void planningAlgorithmIndexChanged(int index);
160  void resetDbButtonClicked();
161  void approximateIKChanged(int state);
162 
163  // Planning tab
164  bool computeCartesianPlan();
165  bool computeJointSpacePlan();
166  void planButtonClicked();
167  void executeButtonClicked();
168  void planAndExecuteButtonClicked();
169  void stopButtonClicked();
170  void allowReplanningToggled(bool checked);
171  void allowLookingToggled(bool checked);
172  void allowExternalProgramCommunication(bool enable);
173  void pathConstraintsIndexChanged(int index);
174  void onNewPlanningSceneState();
175  void startStateTextChanged(const QString& start_state);
176  void goalStateTextChanged(const QString& goal_state);
177  void planningGroupTextChanged(const QString& planning_group);
178  void onClearOctomapClicked();
179 
180  // Scene Objects tab
181  void clearScene();
182  void publishScene();
183  void publishSceneIfNeeded();
184  void setLocalSceneEdited(bool dirty = true);
185  bool isLocalSceneDirty() const;
186  void sceneScaleChanged(int value);
187  void sceneScaleStartChange();
188  void sceneScaleEndChange();
189  void shapesComboBoxChanged(const QString& text);
190  void addSceneObject();
191  void removeSceneObject();
192  void selectedCollisionObjectChanged();
193  void objectPoseValueChanged(double value);
194  void collisionObjectChanged(QListWidgetItem* item);
195  void imProcessFeedback(visualization_msgs::msg::InteractiveMarkerFeedback& feedback);
196  void copySelectedCollisionObject();
197  void exportGeometryAsTextButtonClicked();
198  void importGeometryFromTextButtonClicked();
199 
200  // Stored scenes tab
201  void saveSceneButtonClicked();
202  void planningSceneItemClicked();
203  void saveQueryButtonClicked();
204  void deleteSceneButtonClicked();
205  void deleteQueryButtonClicked();
206  void loadSceneButtonClicked();
207  void loadQueryButtonClicked();
208  void warehouseItemNameChanged(QTreeWidgetItem* item, int column);
209 
210  // States tab
211  void loadStateButtonClicked();
212  void saveStartStateButtonClicked();
213  void saveGoalStateButtonClicked();
214  void removeStateButtonClicked();
215  void clearStatesButtonClicked();
216  void setAsStartStateButtonClicked();
217  void setAsGoalStateButtonClicked();
218 
219  // Pick and place
220  void detectObjectsButtonClicked();
221  void pickObjectButtonClicked();
222  void placeObjectButtonClicked();
223  void selectedDetectedObjectChanged();
224  void detectedObjectChanged(QListWidgetItem* item);
225  void selectedSupportSurfaceChanged();
226 
227  // General
228  void tabChanged(int index);
229 
230 private:
231  // Context tab
232  void computeDatabaseConnectButtonClicked();
233  void computeDatabaseConnectButtonClickedHelper(int mode);
234  void computeResetDbButtonClicked(const std::string& db);
235  void populatePlannersList(const std::vector<moveit_msgs::msg::PlannerInterfaceDescription>& desc);
236  void populatePlannerDescription(const moveit_msgs::msg::PlannerInterfaceDescription& desc);
237 
238  // Planning tab
239  void computePlanButtonClicked();
240  void computeExecuteButtonClicked();
241  void computePlanAndExecuteButtonClicked();
242  void computePlanAndExecuteButtonClickedDisplayHelper();
243  void computeStopButtonClicked();
244  void onFinishedExecution(bool success);
245  void populateConstraintsList();
246  void populateConstraintsList(const std::vector<std::string>& constr);
247  void configureForPlanning();
248  void configureWorkspace();
249  void updateQueryStateHelper(moveit::core::RobotState& state, const std::string& v);
250  void fillStateSelectionOptions();
251  void fillPlanningGroupOptions();
252  void startStateTextChangedExec(const std::string& start_state);
253  void goalStateTextChangedExec(const std::string& goal_state);
254 
255  // Scene objects tab
256  void updateCollisionObjectPose(bool update_marker_position);
257  void createSceneInteractiveMarker();
258  void renameCollisionObject(QListWidgetItem* item);
259  void attachDetachCollisionObject(QListWidgetItem* item);
260  void populateCollisionObjectsList();
261  void computeImportGeometryFromText(const std::string& path);
262  void computeExportGeometryAsText(const std::string& path);
263  visualization_msgs::msg::InteractiveMarker
264  createObjectMarkerMsg(const collision_detection::CollisionEnv::ObjectConstPtr& obj);
265 
266  // Stored scenes tab
267  void computeSaveSceneButtonClicked();
268  void computeSaveQueryButtonClicked(const std::string& scene, const std::string& query_name);
269  void computeLoadSceneButtonClicked();
270  void computeLoadQueryButtonClicked();
271  void populatePlanningSceneTreeView();
272  void computeDeleteSceneButtonClicked();
273  void computeDeleteQueryButtonClicked();
274  void computeDeleteQueryButtonClickedHelper(QTreeWidgetItem* s);
275  void checkPlanningSceneTreeEnabledButtons();
276 
277  // States tab
278  void saveRobotStateButtonClicked(const moveit::core::RobotState& state);
279  void populateRobotStatesList();
280 
281  // Pick and place
282  void processDetectedObjects();
283  void updateDetectedObjectsList(const std::vector<std::string>& object_ids);
284  void publishTables();
285  void updateSupportSurfacesList();
286 
287  std::map<std::string, std::string> pick_object_name_;
288  std::string place_object_name_;
289  std::vector<geometry_msgs::msg::PoseStamped> place_poses_;
290  // void pickObject();
291  // void placeObject();
292  void triggerObjectDetection();
293  void updateTables();
294  std::string support_surface_name_;
295  // For coloring
296  std::string selected_object_name_;
297  std::string selected_support_surface_name_;
298 
299  rclcpp_action::Client<object_recognition_msgs::action::ObjectRecognition>::SharedPtr object_recognition_client_;
300  void listenDetectedObjects(const object_recognition_msgs::msg::RecognizedObjectArray::ConstSharedPtr& msg);
301  rclcpp::Subscription<object_recognition_msgs::msg::RecognizedObjectArray>::SharedPtr object_recognition_subscriber_;
302 
303  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr plan_subscriber_;
304  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr execute_subscriber_;
305  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr stop_subscriber_;
306  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr update_start_state_subscriber_;
307  rclcpp::Subscription<std_msgs::msg::Empty>::SharedPtr update_goal_state_subscriber_;
308  rclcpp::Subscription<moveit_msgs::msg::RobotState>::SharedPtr update_custom_start_state_subscriber_;
309  rclcpp::Subscription<moveit_msgs::msg::RobotState>::SharedPtr update_custom_goal_state_subscriber_;
310 
311  // General
312  void changePlanningGroupHelper();
313  shapes::ShapePtr loadMeshResource(const std::string& url);
314  void loadStoredStates(const std::string& pattern);
315 
316  void remotePlanCallback(const std_msgs::msg::Empty::ConstSharedPtr& msg);
317  void remoteExecuteCallback(const std_msgs::msg::Empty::ConstSharedPtr& msg);
318  void remoteStopCallback(const std_msgs::msg::Empty::ConstSharedPtr& msg);
319  void remoteUpdateStartStateCallback(const std_msgs::msg::Empty::ConstSharedPtr& msg);
320  void remoteUpdateGoalStateCallback(const std_msgs::msg::Empty::ConstSharedPtr& msg);
321  void remoteUpdateCustomStartStateCallback(const moveit_msgs::msg::RobotState::ConstSharedPtr& msg);
322  void remoteUpdateCustomGoalStateCallback(const moveit_msgs::msg::RobotState::ConstSharedPtr& msg);
323 
324  /* Selects or unselects a item in a list by the item name */
325  void setItemSelectionInList(const std::string& item_name, bool selection, QListWidget* list);
326 
327  rclcpp::Node::SharedPtr node_;
328  rclcpp::Publisher<moveit_msgs::msg::PlanningScene>::SharedPtr planning_scene_publisher_;
329  rclcpp::Publisher<moveit_msgs::msg::PlanningSceneWorld>::SharedPtr planning_scene_world_publisher_;
330 
332  moveit::core::FixedTransformsMap scaled_object_subframes_;
333  EigenSTL::vector_Isometry3d scaled_object_shape_poses_;
334 
335  std::vector<std::pair<std::string, bool> > known_collision_objects_;
336  long unsigned int known_collision_objects_version_;
337  bool first_time_;
338  rclcpp::Client<std_srvs::srv::Empty>::SharedPtr clear_octomap_service_client_;
339 };
340 } // namespace moveit_rviz_plugin
World::ObjectConstPtr ObjectConstPtr
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
std::pair< std::string, moveit_msgs::msg::RobotState > RobotStatePair
void updateSceneMarkers(float wall_dt, float ros_dt)
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
MotionPlanningFrameJointsWidget * joints_tab_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
moveit::planning_interface::MoveGroupInterfacePtr move_group_
std::map< std::string, moveit_msgs::msg::RobotState > RobotStateMap
void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest &mreq)
void sceneUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
MotionPlanningFrame(const MotionPlanningFrame &)=delete
moveit_warehouse::RobotStateStoragePtr robot_state_storage_
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:53
const std::string OBJECT_RECOGNITION_ACTION
MOVEIT_CLASS_FORWARD(PlanningSceneStorage)
scene
Definition: pick.py:52
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest