127 void updateSceneMarkers(std::chrono::nanoseconds wall_dt, std::chrono::nanoseconds ros_dt);
129#if RCLCPP_VERSION_GTE(30, 0, 0)
130 [[deprecated(
"Use updateSceneMarkers(std::chrono::nanoseconds, std::chrono::nanoseconds) instead")]]
void
141 Ui::MotionPlanningUI*
ui_;
153 std::shared_ptr<rviz_default_plugins::displays::InteractiveMarker>
scene_marker_;
168 void databaseConnectButtonClicked();
169 void planningPipelineIndexChanged(
int index);
170 void planningAlgorithmIndexChanged(
int index);
171 void resetDbButtonClicked();
172 void approximateIKChanged(
int state);
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();
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();
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);
222 void loadStateButtonClicked();
223 void saveStartStateButtonClicked();
224 void saveGoalStateButtonClicked();
225 void removeStateButtonClicked();
226 void clearStatesButtonClicked();
227 void setAsStartStateButtonClicked();
228 void setAsGoalStateButtonClicked();
231 void detectObjectsButtonClicked();
232 void pickObjectButtonClicked();
233 void placeObjectButtonClicked();
234 void selectedDetectedObjectChanged();
235 void detectedObjectChanged(QListWidgetItem* item);
236 void selectedSupportSurfaceChanged();
239 void tabChanged(
int index);
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);
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();
261 void fillStateSelectionOptions();
262 void fillPlanningGroupOptions();
263 void startStateTextChangedExec(
const std::string& start_state);
264 void goalStateTextChangedExec(
const std::string& goal_state);
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
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();
290 void populateRobotStatesList();
293 void processDetectedObjects();
294 void updateDetectedObjectsList(
const std::vector<std::string>& object_ids);
295 void publishTables();
296 void updateSupportSurfacesList();
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_;
303 void triggerObjectDetection();
305 std::string support_surface_name_;
307 std::string selected_object_name_;
308 std::string selected_support_surface_name_;
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_;
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_;
323 void changePlanningGroupHelper();
324 shapes::ShapePtr loadMeshResource(
const std::string& url);
325 void loadStoredStates(
const std::string& pattern);
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);
336 void setItemSelectionInList(
const std::string& item_name,
bool selection, QListWidget* list);
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_;
345 EigenSTL::vector_Isometry3d scaled_object_shape_poses_;
347 std::vector<std::pair<std::string, bool> > known_collision_objects_;
348 long unsigned int known_collision_objects_version_;
350 rclcpp::Client<std_srvs::srv::Empty>::SharedPtr clear_octomap_service_client_;