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