moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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, Acorn Pooley */
36 
37 #pragma once
38 
49 #include <moveit_msgs/msg/planning_scene.hpp>
50 #include <moveit_msgs/msg/robot_trajectory.hpp>
51 #include <moveit_msgs/msg/constraints.hpp>
52 #include <moveit_msgs/msg/planning_scene_components.hpp>
53 #include <octomap_msgs/msg/octomap_with_pose.hpp>
54 #include <memory>
55 #include <functional>
56 #include <thread>
57 #include <variant>
58 #include <rclcpp/rclcpp.hpp>
59 
60 #include <moveit_planning_scene_export.h>
61 
63 namespace planning_scene
64 {
65 MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc
66 
71 typedef std::function<bool(const moveit::core::RobotState&, bool)> StateFeasibilityFn;
72 
78 using MotionFeasibilityFn = std::function<bool(const moveit::core::RobotState&, const moveit::core::RobotState&, bool)>;
79 
81 using ObjectColorMap = std::map<std::string, std_msgs::msg::ColorRGBA>;
82 
84 using ObjectTypeMap = std::map<std::string, object_recognition_msgs::msg::ObjectType>;
85 
89 class MOVEIT_PLANNING_SCENE_EXPORT PlanningScene : public std::enable_shared_from_this<PlanningScene>
90 {
91 public:
95  PlanningScene(const PlanningScene&) = delete;
96 
101 
103  PlanningScene(const moveit::core::RobotModelConstPtr& robot_model,
104  const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
105 
108  PlanningScene(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model,
109  const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
110 
111  static const std::string OCTOMAP_NS;
112  static const std::string DEFAULT_SCENE_NAME;
113 
114  ~PlanningScene();
115 
117  const std::string& getName() const
118  {
119  return name_;
120  }
121 
123  void setName(const std::string& name)
124  {
125  name_ = name;
126  }
127 
138  PlanningScenePtr diff() const;
139 
142  PlanningScenePtr diff(const moveit_msgs::msg::PlanningScene& msg) const;
143 
145  const PlanningSceneConstPtr& getParent() const
146  {
147  return parent_;
148  }
149 
151  const moveit::core::RobotModelConstPtr& getRobotModel() const
152  {
153  // the kinematic model does not change
154  return robot_model_;
155  }
156 
159  {
160  // if we have an updated state, return it; otherwise, return the parent one
161  return robot_state_ ? *robot_state_ : parent_->getCurrentState();
162  }
164  moveit::core::RobotState& getCurrentStateNonConst();
165 
167  moveit::core::RobotStatePtr getCurrentStateUpdated(const moveit_msgs::msg::RobotState& update) const;
168 
175  const std::string& getPlanningFrame() const
176  {
177  // if we have an updated set of transforms, return it; otherwise, return the parent one
178  return scene_transforms_ ? scene_transforms_->getTargetFrame() : parent_->getPlanningFrame();
179  }
180 
183  {
184  if (scene_transforms_ || !parent_)
185  {
186  return *scene_transforms_;
187  }
188 
189  // if this planning scene is a child of another, and doesn't have its own custom transforms
190  return parent_->getTransforms();
191  }
192 
195  const moveit::core::Transforms& getTransforms();
196 
198  moveit::core::Transforms& getTransformsNonConst();
199 
204  const Eigen::Isometry3d& getFrameTransform(const std::string& id) const;
205 
211  const Eigen::Isometry3d& getFrameTransform(const std::string& id);
212 
218  const Eigen::Isometry3d& getFrameTransform(moveit::core::RobotState& state, const std::string& id) const
219  {
220  state.updateLinkTransforms();
221  return getFrameTransform(static_cast<const moveit::core::RobotState&>(state), id);
222  }
223 
228  const Eigen::Isometry3d& getFrameTransform(const moveit::core::RobotState& state, const std::string& id) const;
229 
232  bool knowsFrameTransform(const std::string& id) const;
233 
236  bool knowsFrameTransform(const moveit::core::RobotState& state, const std::string& id) const;
237 
245  const std::string getCollisionDetectorName() const
246  {
247  // If no collision detector is allocated, return an empty string
248  return collision_detector_ ? (collision_detector_->alloc_->getName()) : "";
249  }
250 
252  const collision_detection::WorldConstPtr& getWorld() const
253  {
254  // we always have a world representation
255  return world_const_;
256  }
257 
259  const collision_detection::WorldPtr& getWorldNonConst()
260  {
261  // we always have a world representation
262  return world_;
263  }
264 
266  const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const
267  {
268  return collision_detector_->getCollisionEnv();
269  }
270 
272  const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const
273  {
274  return collision_detector_->getCollisionEnvUnpadded();
275  }
276 
278  const collision_detection::CollisionEnvConstPtr& getCollisionEnv(const std::string& collision_detector_name) const;
279 
282  const collision_detection::CollisionEnvConstPtr&
283  getCollisionEnvUnpadded(const std::string& collision_detector_name) const;
284 
287  const collision_detection::CollisionEnvPtr& getCollisionEnvNonConst();
288 
291  {
292  return acm_ ? *acm_ : parent_->getAllowedCollisionMatrix();
293  }
295  collision_detection::AllowedCollisionMatrix& getAllowedCollisionMatrixNonConst();
296 
307  bool isStateColliding(const std::string& group = "", bool verbose = false);
308 
312  bool isStateColliding(const std::string& group = "", bool verbose = false) const
313  {
314  return isStateColliding(getCurrentState(), group, verbose);
315  }
316 
321  bool isStateColliding(moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const
322  {
324  return isStateColliding(static_cast<const moveit::core::RobotState&>(state), group, verbose);
325  }
326 
330  bool isStateColliding(const moveit::core::RobotState& state, const std::string& group = "",
331  bool verbose = false) const;
332 
335  bool isStateColliding(const moveit_msgs::msg::RobotState& state, const std::string& group = "",
336  bool verbose = false) const;
337 
341 
344  {
345  checkCollision(req, res, getCurrentState());
346  }
347 
351  moveit::core::RobotState& robot_state) const
352  {
353  robot_state.updateCollisionBodyTransforms();
354  checkCollision(req, res, static_cast<const moveit::core::RobotState&>(robot_state));
355  }
356 
361  const moveit::core::RobotState& robot_state) const;
362 
367  moveit::core::RobotState& robot_state,
369  {
370  robot_state.updateCollisionBodyTransforms();
371  checkCollision(req, res, static_cast<const moveit::core::RobotState&>(robot_state), acm);
372  }
373 
377  const moveit::core::RobotState& robot_state,
379 
383  void checkCollisionUnpadded(const collision_detection::CollisionRequest& req,
385 
390  {
391  checkCollisionUnpadded(req, res, getCurrentState(), getAllowedCollisionMatrix());
392  }
393 
398  const moveit::core::RobotState& robot_state) const
399  {
400  checkCollisionUnpadded(req, res, robot_state, getAllowedCollisionMatrix());
401  }
402 
408  {
409  robot_state.updateCollisionBodyTransforms();
410  checkCollisionUnpadded(req, res, static_cast<const moveit::core::RobotState&>(robot_state),
411  getAllowedCollisionMatrix());
412  }
413 
420  {
421  robot_state.updateCollisionBodyTransforms();
422  checkCollisionUnpadded(req, res, static_cast<const moveit::core::RobotState&>(robot_state), acm);
423  }
424 
427  void checkCollisionUnpadded(const collision_detection::CollisionRequest& req,
430 
432  void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res);
433 
437  {
438  checkSelfCollision(req, res, getCurrentState());
439  }
440 
443  moveit::core::RobotState& robot_state) const
444  {
445  robot_state.updateCollisionBodyTransforms();
446  checkSelfCollision(req, res, static_cast<const moveit::core::RobotState&>(robot_state), getAllowedCollisionMatrix());
447  }
448 
451  const moveit::core::RobotState& robot_state) const
452  {
453  // do self-collision checking with the unpadded version of the robot
454  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix());
455  }
456 
460  moveit::core::RobotState& robot_state,
462  {
463  robot_state.updateCollisionBodyTransforms();
464  checkSelfCollision(req, res, static_cast<const moveit::core::RobotState&>(robot_state), acm);
465  }
466 
470  const moveit::core::RobotState& robot_state,
472  {
473  // do self-collision checking with the unpadded version of the robot
474  getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
475  }
476 
478  void getCollidingLinks(std::vector<std::string>& links);
479 
481  void getCollidingLinks(std::vector<std::string>& links) const
482  {
483  getCollidingLinks(links, getCurrentState(), getAllowedCollisionMatrix());
484  }
485 
488  void getCollidingLinks(std::vector<std::string>& links, moveit::core::RobotState& robot_state) const
489  {
490  robot_state.updateCollisionBodyTransforms();
491  getCollidingLinks(links, static_cast<const moveit::core::RobotState&>(robot_state), getAllowedCollisionMatrix());
492  }
493 
495  void getCollidingLinks(std::vector<std::string>& links, const moveit::core::RobotState& robot_state) const
496  {
497  getCollidingLinks(links, robot_state, getAllowedCollisionMatrix());
498  }
499 
502  void getCollidingLinks(std::vector<std::string>& links, moveit::core::RobotState& robot_state,
504  {
505  robot_state.updateCollisionBodyTransforms();
506  getCollidingLinks(links, static_cast<const moveit::core::RobotState&>(robot_state), acm);
507  }
508 
511  void getCollidingLinks(std::vector<std::string>& links, const moveit::core::RobotState& robot_state,
513 
516  void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts);
517 
520  {
521  getCollidingPairs(contacts, getCurrentState(), getAllowedCollisionMatrix());
522  }
523 
527  const moveit::core::RobotState& robot_state, const std::string& group_name = "") const
528  {
529  getCollidingPairs(contacts, robot_state, getAllowedCollisionMatrix(), group_name);
530  }
531 
536  moveit::core::RobotState& robot_state, const std::string& group_name = "") const
537  {
538  robot_state.updateCollisionBodyTransforms();
539  getCollidingPairs(contacts, static_cast<const moveit::core::RobotState&>(robot_state), getAllowedCollisionMatrix(),
540  group_name);
541  }
542 
548  const std::string& group_name = "") const
549  {
550  robot_state.updateCollisionBodyTransforms();
551  getCollidingPairs(contacts, static_cast<const moveit::core::RobotState&>(robot_state), acm, group_name);
552  }
553 
556  void getCollidingPairs(collision_detection::CollisionResult::ContactMap& contacts,
557  const moveit::core::RobotState& robot_state,
559  const std::string& group_name = "") const;
560 
572  {
573  robot_state.updateCollisionBodyTransforms();
574  return distanceToCollision(static_cast<const moveit::core::RobotState&>(robot_state));
575  }
576 
580  double distanceToCollision(const moveit::core::RobotState& robot_state) const
581  {
582  return getCollisionEnv()->distanceRobot(robot_state, getAllowedCollisionMatrix());
583  }
584 
588  {
589  robot_state.updateCollisionBodyTransforms();
590  return distanceToCollisionUnpadded(static_cast<const moveit::core::RobotState&>(robot_state));
591  }
592 
595  double distanceToCollisionUnpadded(const moveit::core::RobotState& robot_state) const
596  {
597  return getCollisionEnvUnpadded()->distanceRobot(robot_state, getAllowedCollisionMatrix());
598  }
599 
605  {
606  robot_state.updateCollisionBodyTransforms();
607  return distanceToCollision(static_cast<const moveit::core::RobotState&>(robot_state), acm);
608  }
609 
615  {
616  return getCollisionEnv()->distanceRobot(robot_state, acm);
617  }
618 
624  {
625  robot_state.updateCollisionBodyTransforms();
626  return distanceToCollisionUnpadded(static_cast<const moveit::core::RobotState&>(robot_state), acm);
627  }
628 
634  {
635  return getCollisionEnvUnpadded()->distanceRobot(robot_state, acm);
636  }
637 
641  void saveGeometryToStream(std::ostream& out) const;
642 
644  bool loadGeometryFromStream(std::istream& in);
645 
647  bool loadGeometryFromStream(std::istream& in, const Eigen::Isometry3d& offset);
648 
653  void getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene& scene) const;
654 
658  void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene) const;
659 
662  void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene& scene,
663  const moveit_msgs::msg::PlanningSceneComponents& comp) const;
664 
667  bool getCollisionObjectMsg(moveit_msgs::msg::CollisionObject& collision_obj, const std::string& ns) const;
668 
671  void getCollisionObjectMsgs(std::vector<moveit_msgs::msg::CollisionObject>& collision_objs) const;
672 
675  bool getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject& attached_collision_obj,
676  const std::string& ns) const;
677 
680  void
681  getAttachedCollisionObjectMsgs(std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objs) const;
682 
684  bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose& octomap) const;
685 
687  void getObjectColorMsgs(std::vector<moveit_msgs::msg::ObjectColor>& object_colors) const;
688 
694  bool setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene& scene);
695 
698  bool setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene);
699 
702  bool usePlanningSceneMsg(const moveit_msgs::msg::PlanningScene& scene);
703 
708  bool shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::msg::CollisionObject& object,
709  Eigen::Isometry3d& object_pose_in_header_frame,
710  std::vector<shapes::ShapeConstPtr>& shapes,
711  EigenSTL::vector_Isometry3d& shape_poses);
712 
713  bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject& object);
714  bool processAttachedCollisionObjectMsg(const moveit_msgs::msg::AttachedCollisionObject& object);
715 
716  bool processPlanningSceneWorldMsg(const moveit_msgs::msg::PlanningSceneWorld& world);
717 
718  void processOctomapMsg(const octomap_msgs::msg::OctomapWithPose& map);
719  void processOctomapMsg(const octomap_msgs::msg::Octomap& map);
720  void processOctomapPtr(const std::shared_ptr<const octomap::OcTree>& octree, const Eigen::Isometry3d& t);
721 
725  void removeAllCollisionObjects();
726 
730  void setCurrentState(const moveit_msgs::msg::RobotState& state);
731 
733  void setCurrentState(const moveit::core::RobotState& state);
734 
736  void setAttachedBodyUpdateCallback(const moveit::core::AttachedBodyCallback& callback);
737 
739  void setCollisionObjectUpdateCallback(const collision_detection::World::ObserverCallbackFn& callback);
740 
741  bool hasObjectColor(const std::string& id) const;
742 
743  const std_msgs::msg::ColorRGBA& getObjectColor(const std::string& id) const;
744  void setObjectColor(const std::string& id, const std_msgs::msg::ColorRGBA& color);
745  void removeObjectColor(const std::string& id);
746  void getKnownObjectColors(ObjectColorMap& kc) const;
747 
748  bool hasObjectType(const std::string& id) const;
749 
750  const object_recognition_msgs::msg::ObjectType& getObjectType(const std::string& id) const;
751  void setObjectType(const std::string& id, const object_recognition_msgs::msg::ObjectType& type);
752  void removeObjectType(const std::string& id);
753  void getKnownObjectTypes(ObjectTypeMap& kc) const;
754 
759  void clearDiffs();
760 
764  void pushDiffs(const PlanningScenePtr& scene);
765 
769  void decoupleParent();
770 
775  {
776  state_feasibility_ = fn;
777  }
778 
782  {
783  return state_feasibility_;
784  }
785 
789  {
790  motion_feasibility_ = fn;
791  }
792 
796  {
797  return motion_feasibility_;
798  }
799 
802  bool isStateFeasible(const moveit_msgs::msg::RobotState& state, bool verbose = false) const;
803 
806  bool isStateFeasible(const moveit::core::RobotState& state, bool verbose = false) const;
807 
809  bool isStateConstrained(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr,
810  bool verbose = false) const;
811 
813  bool isStateConstrained(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr,
814  bool verbose = false) const;
815 
817  bool isStateConstrained(const moveit_msgs::msg::RobotState& state,
818  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const;
819 
821  bool isStateConstrained(const moveit::core::RobotState& state,
822  const kinematic_constraints::KinematicConstraintSet& constr, bool verbose = false) const;
823 
825  bool isStateValid(const moveit_msgs::msg::RobotState& state, const std::string& group = "",
826  bool verbose = false) const;
827 
829  bool isStateValid(const moveit::core::RobotState& state, const std::string& group = "", bool verbose = false) const;
830 
833  bool isStateValid(const moveit_msgs::msg::RobotState& state, const moveit_msgs::msg::Constraints& constr,
834  const std::string& group = "", bool verbose = false) const;
835 
838  bool isStateValid(const moveit::core::RobotState& state, const moveit_msgs::msg::Constraints& constr,
839  const std::string& group = "", bool verbose = false) const;
840 
843  bool isStateValid(const moveit::core::RobotState& state, const kinematic_constraints::KinematicConstraintSet& constr,
844  const std::string& group = "", bool verbose = false) const;
845 
847  bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory,
848  const std::string& group = "", bool verbose = false,
849  std::vector<std::size_t>* invalid_index = nullptr) const;
850 
854  bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory,
855  const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "",
856  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
857 
861  bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory,
862  const moveit_msgs::msg::Constraints& path_constraints,
863  const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "",
864  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
865 
869  bool isPathValid(const moveit_msgs::msg::RobotState& start_state, const moveit_msgs::msg::RobotTrajectory& trajectory,
870  const moveit_msgs::msg::Constraints& path_constraints,
871  const std::vector<moveit_msgs::msg::Constraints>& goal_constraints, const std::string& group = "",
872  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
873 
877  bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory,
878  const moveit_msgs::msg::Constraints& path_constraints,
879  const std::vector<moveit_msgs::msg::Constraints>& goal_constraints, const std::string& group = "",
880  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
881 
885  bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory,
886  const moveit_msgs::msg::Constraints& path_constraints,
887  const moveit_msgs::msg::Constraints& goal_constraints, const std::string& group = "",
888  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
889 
892  bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory,
893  const moveit_msgs::msg::Constraints& path_constraints, const std::string& group = "",
894  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
895 
897  bool isPathValid(const robot_trajectory::RobotTrajectory& trajectory, const std::string& group = "",
898  bool verbose = false, std::vector<std::size_t>* invalid_index = nullptr) const;
899 
902  void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
903  std::set<collision_detection::CostSource>& costs, double overlap_fraction = 0.9) const;
904 
907  void getCostSources(const robot_trajectory::RobotTrajectory& trajectory, std::size_t max_costs,
908  const std::string& group_name, std::set<collision_detection::CostSource>& costs,
909  double overlap_fraction = 0.9) const;
910 
912  void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs,
913  std::set<collision_detection::CostSource>& costs) const;
914 
917  void getCostSources(const moveit::core::RobotState& state, std::size_t max_costs, const std::string& group_name,
918  std::set<collision_detection::CostSource>& costs) const;
919 
921  void printKnownObjects(std::ostream& out = std::cout) const;
922 
925  [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
926  isEmpty(const moveit_msgs::msg::PlanningScene& msg);
927 
930  [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
931  isEmpty(const moveit_msgs::msg::PlanningSceneWorld& msg);
932 
934  [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool
935  isEmpty(const moveit_msgs::msg::RobotState& msg);
936 
938  static PlanningScenePtr clone(const PlanningSceneConstPtr& scene);
939 
953  void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator)
954  {
955  allocateCollisionDetector(allocator, nullptr /* no parent_detector */);
956  }
957 
958 private:
959  /* Private constructor used by the diff() methods. */
960  PlanningScene(const PlanningSceneConstPtr& parent);
961 
962  /* Initialize the scene. This should only be called by the constructors.
963  * Requires a valid robot_model_ */
964  void initialize();
965 
966  /* helper function to create a RobotModel from a urdf/srdf. */
967  static moveit::core::RobotModelPtr createRobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model,
968  const srdf::ModelConstSharedPtr& srdf_model);
969 
970  /* Helper functions for processing collision objects */
971  bool processCollisionObjectAdd(const moveit_msgs::msg::CollisionObject& object);
972  bool processCollisionObjectRemove(const moveit_msgs::msg::CollisionObject& object);
973  bool processCollisionObjectMove(const moveit_msgs::msg::CollisionObject& object);
974 
975  /* For exporting and importing the planning scene */
976  bool readPoseFromText(std::istream& in, Eigen::Isometry3d& pose) const;
977  void writePoseToText(std::ostream& out, const Eigen::Isometry3d& pose) const;
978 
980  static void poseMsgToEigen(const geometry_msgs::msg::Pose& msg, Eigen::Isometry3d& out);
981 
983 
984  /* Construct a new CollisionDector from allocator, copy-construct environments from parent_detector if not nullptr */
985  void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr& allocator,
986  const CollisionDetectorPtr& parent_detector);
987 
988  /* \brief A set of compatible collision detectors */
989  struct CollisionDetector
990  {
991  collision_detection::CollisionDetectorAllocatorPtr alloc_;
992  collision_detection::CollisionEnvPtr cenv_; // never nullptr
993  collision_detection::CollisionEnvConstPtr cenv_const_;
994 
995  collision_detection::CollisionEnvPtr cenv_unpadded_;
996  collision_detection::CollisionEnvConstPtr cenv_unpadded_const_;
997 
998  const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const
999  {
1000  return cenv_const_;
1001  }
1002  const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const
1003  {
1004  return cenv_unpadded_const_;
1005  }
1006  void copyPadding(const CollisionDetector& src);
1007  };
1008  friend struct CollisionDetector;
1009 
1010  std::string name_; // may be empty
1011 
1012  PlanningSceneConstPtr parent_; // Null unless this is a diff scene
1013 
1014  moveit::core::RobotModelConstPtr robot_model_; // Never null (may point to same model as parent)
1015 
1016  moveit::core::RobotStatePtr robot_state_; // if nullptr use parent's
1017 
1018  // Called when changes are made to attached bodies
1019  moveit::core::AttachedBodyCallback current_state_attached_body_callback_;
1020 
1021  // This variable is not necessarily used by child planning scenes
1022  // This Transforms class is actually a SceneTransforms class
1023  moveit::core::TransformsPtr scene_transforms_; // if nullptr use parent's
1024 
1025  collision_detection::WorldPtr world_; // never nullptr, never shared with parent/child
1026  collision_detection::WorldConstPtr world_const_; // copy of world_
1027  collision_detection::WorldDiffPtr world_diff_; // nullptr unless this is a diff scene
1028  collision_detection::World::ObserverCallbackFn current_world_object_update_callback_;
1029  collision_detection::World::ObserverHandle current_world_object_update_observer_handle_;
1030 
1031  CollisionDetectorPtr collision_detector_; // Never nullptr.
1032 
1033  collision_detection::AllowedCollisionMatrixPtr acm_; // if nullptr use parent's
1034 
1035  StateFeasibilityFn state_feasibility_;
1036  MotionFeasibilityFn motion_feasibility_;
1037 
1038  std::unique_ptr<ObjectColorMap> object_colors_;
1039 
1040  // a map of object types
1041  std::unique_ptr<ObjectTypeMap> object_types_;
1042 };
1043 } // namespace planning_scene
#define MOVEIT_STRUCT_FORWARD(C)
Definition: class_forward.h:55
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
Definition: world.h:301
A class that contains many different constraints, and can check RobotState *versus the full set....
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
Provides an implementation of a snapshot of a transform tree that can be easily queried for transform...
Definition: transforms.h:59
This class maintains the representation of the environment as seen by a planning instance....
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
Check whether the current state is in self collision.
void setName(const std::string &name)
Set the name of the planning scene.
double distanceToCollisionUnpadded(const moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed c...
double distanceToCollision(moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
The distance between the robot model at state robot_state to the nearest collision,...
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts) const
Get the names of the links that are involved in collisions for the current state.
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm, const std::string &group_name="") const
Get the names of the links that are involved in collisions for the state robot_state given the allowe...
double distanceToCollision(moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
bool isStateColliding(moveit::core::RobotState &state, const std::string &group="", bool verbose=false) const
Check if a given state is in collision (with the environment or self collision) If a group name is sp...
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
const std::string & getPlanningFrame() const
Get the frame in which planning is performed.
void getCollidingLinks(std::vector< std::string > &links, const moveit::core::RobotState &robot_state) const
Get the names of the links that are involved in collisions for the state robot_state.
const MotionFeasibilityFn & getMotionFeasibilityPredicate() const
Get the predicate that decides whether motion segments are considered valid or invalid for reasons be...
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts, const moveit::core::RobotState &robot_state, const std::string &group_name="") const
Get the names of the links that are involved in collisions for the state robot_state....
void setMotionFeasibilityPredicate(const MotionFeasibilityFn &fn)
Specify a predicate that decides whether motion segments are considered valid or invalid for reasons ...
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collis...
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded() const
Get the active collision detector for the robot.
void getCollidingLinks(std::vector< std::string > &links, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
Get the names of the links that are involved in collisions for the state robot_state given the allowe...
void checkCollisionUnpadded(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
Check whether the current state is in collision, but use a collision_detection::CollisionRobot instan...
const collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrix() const
Get the allowed collision matrix.
PlanningScene(const PlanningScene &)=delete
PlanningScene cannot be copy-constructed.
double distanceToCollisionUnpadded(moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
The distance between the robot model at state robot_state to the nearest collision,...
double distanceToCollision(const moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
const std::string getCollisionDetectorName() const
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts, moveit::core::RobotState &robot_state, const std::string &group_name="") const
Get the names of the links that are involved in collisions for the state robot_state....
PlanningScene & operator=(const PlanningScene &)=delete
PlanningScene cannot be copy-assigned.
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state) const
Check whether a specified state (robot_state) is in collision. This variant of the function takes a n...
void getCollidingLinks(std::vector< std::string > &links) const
Get the names of the links that are involved in collisions for the current state.
const StateFeasibilityFn & getStateFeasibilityPredicate() const
Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones...
void getCollidingLinks(std::vector< std::string > &links, moveit::core::RobotState &robot_state) const
Get the names of the links that are involved in collisions for the state robot_state....
void allocateCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr &allocator)
Allocate a new collision detector and replace the previous one if there was any.
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state) const
Check whether a specified state (robot_state) is in self collision.
double distanceToCollisionUnpadded(const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
The distance between the robot model at state robot_state to the nearest collision,...
const Eigen::Isometry3d & getFrameTransform(moveit::core::RobotState &state, const std::string &id) const
Get the transform corresponding to the frame id. This will be known if id is a link name,...
void checkCollisionUnpadded(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collis...
double distanceToCollision(const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
The distance between the robot model at state robot_state to the nearest collision,...
const moveit::core::RobotState & getCurrentState() const
Get the state at which the robot is assumed to be.
bool isStateColliding(const std::string &group="", bool verbose=false) const
Check if the current state is in collision (with the environment or self collision)....
void checkCollisionUnpadded(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state) const
Check whether a specified state (robot_state) is in collision, but use a collision_detection::Collisi...
const collision_detection::WorldConstPtr & getWorld() const
Get the representation of the world.
const moveit::core::Transforms & getTransforms() const
Get the set of fixed transforms from known frames to the planning frame.
const collision_detection::WorldPtr & getWorldNonConst()
Get the representation of the world.
void checkCollisionUnpadded(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state) const
Check whether a specified state (robot_state) is in collision, but use a collision_detection::Collisi...
const PlanningSceneConstPtr & getParent() const
Get the parent scene (with respect to which the diffs are maintained). This may be empty.
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed c...
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
Check whether the current state is in collision. The current state is expected to be updated.
void setStateFeasibilityPredicate(const StateFeasibilityFn &fn)
Specify a predicate that decides whether states are considered valid or invalid for reasons beyond on...
double distanceToCollisionUnpadded(moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
const collision_detection::CollisionEnvConstPtr & getCollisionEnv() const
Get the active collision environment.
static const std::string OCTOMAP_NS
static const std::string DEFAULT_SCENE_NAME
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state) const
Check whether a specified state (robot_state) is in self collision.
Maintain a sequence of waypoints and the time durations between these waypoints.
CollisionDetector
Enumerates the available collision detectors.
bool isEmpty(const moveit_msgs::msg::Constraints &constr)
Check if any constraints were specified.
Definition: utils.cpp:127
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
Definition: attached_body.h:51
scene
Definition: pick.py:52
bool isStateColliding(const bool test_for_self_collision, const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
Checks if current robot state is in self collision.
This namespace includes the central class for representing planning contexts.
std::function< bool(const moveit::core::RobotState &, bool)> StateFeasibilityFn
This is the function signature for additional feasibility checks to be imposed on states (in addition...
std::map< std::string, std_msgs::msg::ColorRGBA > ObjectColorMap
A map from object names (e.g., attached bodies, collision objects) to their colors.
std::function< bool(const moveit::core::RobotState &, const moveit::core::RobotState &, bool)> MotionFeasibilityFn
This is the function signature for additional feasibility checks to be imposed on motions segments be...
MOVEIT_CLASS_FORWARD(PlanningScene)
std::map< std::string, object_recognition_msgs::msg::ObjectType > ObjectTypeMap
A map from object names (e.g., attached bodies, collision objects) to their types.
name
Definition: setup.py:7
Definition: world.h:49
Representation of a collision checking request.
Representation of a collision checking result.
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap