40 #include <QTreeWidgetItem>
41 #include <QListWidgetItem>
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>
58 #include <std_msgs/msg/bool.hpp>
59 #include <std_msgs/msg/empty.hpp>
60 #include <std_srvs/srv/empty.hpp>
74 class MotionPlanningUI;
86 class MotionPlanningDisplay;
87 class MotionPlanningFrameJointsWidget;
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";
99 static const double LARGE_MESH_THRESHOLD = 10.0;
130 Ui::MotionPlanningUI*
ui_;
142 std::shared_ptr<rviz_default_plugins::displays::InteractiveMarker>
scene_marker_;
157 void databaseConnectButtonClicked();
158 void planningPipelineIndexChanged(
int index);
159 void planningAlgorithmIndexChanged(
int index);
160 void resetDbButtonClicked();
161 void approximateIKChanged(
int state);
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();
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();
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);
211 void loadStateButtonClicked();
212 void saveStartStateButtonClicked();
213 void saveGoalStateButtonClicked();
214 void removeStateButtonClicked();
215 void clearStatesButtonClicked();
216 void setAsStartStateButtonClicked();
217 void setAsGoalStateButtonClicked();
220 void detectObjectsButtonClicked();
221 void pickObjectButtonClicked();
222 void placeObjectButtonClicked();
223 void selectedDetectedObjectChanged();
224 void detectedObjectChanged(QListWidgetItem* item);
225 void selectedSupportSurfaceChanged();
228 void tabChanged(
int index);
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);
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();
250 void fillStateSelectionOptions();
251 void fillPlanningGroupOptions();
252 void startStateTextChangedExec(
const std::string& start_state);
253 void goalStateTextChangedExec(
const std::string& goal_state);
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
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();
279 void populateRobotStatesList();
282 void processDetectedObjects();
283 void updateDetectedObjectsList(
const std::vector<std::string>& object_ids);
284 void publishTables();
285 void updateSupportSurfacesList();
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_;
292 void triggerObjectDetection();
294 std::string support_surface_name_;
296 std::string selected_object_name_;
297 std::string selected_support_surface_name_;
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_;
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_;
312 void changePlanningGroupHelper();
313 shapes::ShapePtr loadMeshResource(
const std::string& url);
314 void loadStoredStates(
const std::string& pattern);
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);
325 void setItemSelectionInList(
const std::string& item_name,
bool selection, QListWidget* list);
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_;
333 EigenSTL::vector_Isometry3d scaled_object_shape_poses_;
335 std::vector<std::pair<std::string, bool> > known_collision_objects_;
336 long unsigned int known_collision_objects_version_;
338 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr clear_octomap_service_client_;
World::ObjectConstPtr ObjectConstPtr
Representation of a robot's state. This includes position, velocity, acceleration and effort.
moveit_warehouse::PlanningSceneStoragePtr planning_scene_storage_
void initFromMoveGroupNS()
static const int ITEM_TYPE_SCENE
std::shared_ptr< rviz_default_plugins::displays::InteractiveMarker > scene_marker_
rviz_common::DisplayContext * context_
std::pair< std::string, moveit_msgs::msg::RobotState > RobotStatePair
Ui::MotionPlanningUI * ui_
RobotStateMap robot_states_
~MotionPlanningFrame() override
void updateSceneMarkers(float wall_dt, float ros_dt)
void updateExternalCommunication()
void changePlanningGroup()
static const int ITEM_TYPE_QUERY
moveit::planning_interface::MoveGroupInterface::PlanPtr current_plan_
MotionPlanningFrameJointsWidget * joints_tab_
std::vector< moveit_msgs::msg::PlannerInterfaceDescription > planner_descriptions_
moveit_warehouse::ConstraintsStoragePtr constraints_storage_
std::string default_planning_pipeline_
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)
MotionPlanningDisplay * planning_display_
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
MOVEIT_CLASS_FORWARD(PlanningSceneStorage)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest