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>
58 #include <rclcpp/rclcpp.hpp>
60 #include <moveit_planning_scene_export.h>
84 using ObjectTypeMap = std::map<std::string, object_recognition_msgs::msg::ObjectType>;
89 class MOVEIT_PLANNING_SCENE_EXPORT
PlanningScene :
public std::enable_shared_from_this<PlanningScene>
103 PlanningScene(
const moveit::core::RobotModelConstPtr& robot_model,
104 const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
108 PlanningScene(
const urdf::ModelInterfaceSharedPtr& urdf_model,
const srdf::ModelConstSharedPtr& srdf_model,
109 const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
138 PlanningScenePtr diff()
const;
142 PlanningScenePtr diff(
const moveit_msgs::msg::PlanningScene& msg)
const;
161 return robot_state_ ? *robot_state_ : parent_->getCurrentState();
167 moveit::core::RobotStatePtr getCurrentStateUpdated(
const moveit_msgs::msg::RobotState& update)
const;
178 return scene_transforms_ ? scene_transforms_->getTargetFrame() : parent_->getPlanningFrame();
184 if (scene_transforms_ || !parent_)
186 return *scene_transforms_;
190 return parent_->getTransforms();
204 const Eigen::Isometry3d& getFrameTransform(
const std::string&
id)
const;
211 const Eigen::Isometry3d& getFrameTransform(
const std::string&
id);
232 bool knowsFrameTransform(
const std::string&
id)
const;
248 return collision_detector_ ? (collision_detector_->alloc_->getName()) :
"";
252 const collision_detection::WorldConstPtr&
getWorld()
const
268 return collision_detector_->getCollisionEnv();
274 return collision_detector_->getCollisionEnvUnpadded();
278 const collision_detection::CollisionEnvConstPtr& getCollisionEnv(
const std::string& collision_detector_name)
const;
282 const collision_detection::CollisionEnvConstPtr&
283 getCollisionEnvUnpadded(
const std::string& collision_detector_name)
const;
287 const collision_detection::CollisionEnvPtr& getCollisionEnvNonConst();
292 return acm_ ? *acm_ : parent_->getAllowedCollisionMatrix();
331 bool verbose =
false)
const;
336 bool verbose =
false)
const;
345 checkCollision(req, res, getCurrentState());
391 checkCollisionUnpadded(req, res, getCurrentState(), getAllowedCollisionMatrix());
400 checkCollisionUnpadded(req, res, robot_state, getAllowedCollisionMatrix());
411 getAllowedCollisionMatrix());
438 checkSelfCollision(req, res, getCurrentState());
446 checkSelfCollision(req, res,
static_cast<const moveit::core::RobotState&
>(robot_state), getAllowedCollisionMatrix());
454 getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix());
474 getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm);
478 void getCollidingLinks(std::vector<std::string>& links);
483 getCollidingLinks(links, getCurrentState(), getAllowedCollisionMatrix());
497 getCollidingLinks(links, robot_state, getAllowedCollisionMatrix());
521 getCollidingPairs(contacts, getCurrentState(), getAllowedCollisionMatrix());
529 getCollidingPairs(contacts, robot_state, getAllowedCollisionMatrix(), group_name);
548 const std::string& group_name =
"")
const
559 const std::string& group_name =
"")
const;
582 return getCollisionEnv()->distanceRobot(robot_state, getAllowedCollisionMatrix());
597 return getCollisionEnvUnpadded()->distanceRobot(robot_state, getAllowedCollisionMatrix());
616 return getCollisionEnv()->distanceRobot(robot_state, acm);
635 return getCollisionEnvUnpadded()->distanceRobot(robot_state, acm);
641 void saveGeometryToStream(std::ostream& out)
const;
644 bool loadGeometryFromStream(std::istream& in);
647 bool loadGeometryFromStream(std::istream& in,
const Eigen::Isometry3d& offset);
653 void getPlanningSceneDiffMsg(moveit_msgs::msg::PlanningScene&
scene)
const;
658 void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene&
scene)
const;
662 void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene&
scene,
663 const moveit_msgs::msg::PlanningSceneComponents& comp)
const;
667 bool getCollisionObjectMsg(moveit_msgs::msg::CollisionObject& collision_obj,
const std::string& ns)
const;
671 void getCollisionObjectMsgs(std::vector<moveit_msgs::msg::CollisionObject>& collision_objs)
const;
675 bool getAttachedCollisionObjectMsg(moveit_msgs::msg::AttachedCollisionObject& attached_collision_obj,
676 const std::string& ns)
const;
681 getAttachedCollisionObjectMsgs(std::vector<moveit_msgs::msg::AttachedCollisionObject>& attached_collision_objs)
const;
684 bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose&
octomap)
const;
687 void getObjectColorMsgs(std::vector<moveit_msgs::msg::ObjectColor>& object_colors)
const;
694 bool setPlanningSceneDiffMsg(
const moveit_msgs::msg::PlanningScene&
scene);
698 bool setPlanningSceneMsg(
const moveit_msgs::msg::PlanningScene&
scene);
702 bool usePlanningSceneMsg(
const moveit_msgs::msg::PlanningScene&
scene);
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);
713 bool processCollisionObjectMsg(
const moveit_msgs::msg::CollisionObject&
object);
714 bool processAttachedCollisionObjectMsg(
const moveit_msgs::msg::AttachedCollisionObject&
object);
716 bool processPlanningSceneWorldMsg(
const moveit_msgs::msg::PlanningSceneWorld& world);
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);
725 void removeAllCollisionObjects();
730 void setCurrentState(
const moveit_msgs::msg::RobotState& state);
741 bool hasObjectColor(
const std::string&
id)
const;
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);
748 bool hasObjectType(
const std::string&
id)
const;
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);
764 void pushDiffs(
const PlanningScenePtr&
scene);
769 void decoupleParent();
776 state_feasibility_ = fn;
783 return state_feasibility_;
790 motion_feasibility_ = fn;
797 return motion_feasibility_;
802 bool isStateFeasible(
const moveit_msgs::msg::RobotState& state,
bool verbose =
false)
const;
809 bool isStateConstrained(
const moveit_msgs::msg::RobotState& state,
const moveit_msgs::msg::Constraints& constr,
810 bool verbose =
false)
const;
814 bool verbose =
false)
const;
817 bool isStateConstrained(
const moveit_msgs::msg::RobotState& state,
825 bool isStateValid(
const moveit_msgs::msg::RobotState& state,
const std::string&
group =
"",
826 bool verbose =
false)
const;
833 bool isStateValid(
const moveit_msgs::msg::RobotState& state,
const moveit_msgs::msg::Constraints& constr,
834 const std::string&
group =
"",
bool verbose =
false)
const;
839 const std::string&
group =
"",
bool verbose =
false)
const;
844 const std::string&
group =
"",
bool verbose =
false)
const;
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;
854 bool isPathValid(
const moveit_msgs::msg::RobotState& start_state,
const moveit_msgs::msg::RobotTrajectory& trajectory,
856 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
861 bool isPathValid(
const moveit_msgs::msg::RobotState& start_state,
const moveit_msgs::msg::RobotTrajectory& trajectory,
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;
869 bool isPathValid(
const moveit_msgs::msg::RobotState& start_state,
const moveit_msgs::msg::RobotTrajectory& trajectory,
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;
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;
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;
894 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
898 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
903 std::set<collision_detection::CostSource>& costs,
double overlap_fraction = 0.9)
const;
908 const std::string& group_name, std::set<collision_detection::CostSource>& costs,
909 double overlap_fraction = 0.9)
const;
913 std::set<collision_detection::CostSource>& costs)
const;
918 std::set<collision_detection::CostSource>& costs)
const;
921 void printKnownObjects(std::ostream& out = std::cout)
const;
925 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool
926 isEmpty(
const moveit_msgs::msg::PlanningScene& msg);
930 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool
931 isEmpty(
const moveit_msgs::msg::PlanningSceneWorld& msg);
934 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool
935 isEmpty(
const moveit_msgs::msg::RobotState& msg);
938 static PlanningScenePtr clone(
const PlanningSceneConstPtr&
scene);
955 allocateCollisionDetector(allocator,
nullptr );
967 static moveit::core::RobotModelPtr createRobotModel(
const urdf::ModelInterfaceSharedPtr& urdf_model,
968 const srdf::ModelConstSharedPtr& srdf_model);
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);
976 bool readPoseFromText(std::istream& in, Eigen::Isometry3d& pose)
const;
977 void writePoseToText(std::ostream& out,
const Eigen::Isometry3d& pose)
const;
980 static void poseMsgToEigen(
const geometry_msgs::msg::Pose& msg, Eigen::Isometry3d& out);
985 void allocateCollisionDetector(
const collision_detection::CollisionDetectorAllocatorPtr& allocator,
986 const CollisionDetectorPtr& parent_detector);
991 collision_detection::CollisionDetectorAllocatorPtr alloc_;
992 collision_detection::CollisionEnvPtr cenv_;
993 collision_detection::CollisionEnvConstPtr cenv_const_;
995 collision_detection::CollisionEnvPtr cenv_unpadded_;
996 collision_detection::CollisionEnvConstPtr cenv_unpadded_const_;
998 const collision_detection::CollisionEnvConstPtr& getCollisionEnv()
const
1002 const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded()
const
1004 return cenv_unpadded_const_;
1012 PlanningSceneConstPtr parent_;
1014 moveit::core::RobotModelConstPtr robot_model_;
1016 moveit::core::RobotStatePtr robot_state_;
1023 moveit::core::TransformsPtr scene_transforms_;
1025 collision_detection::WorldPtr world_;
1026 collision_detection::WorldConstPtr world_const_;
1027 collision_detection::WorldDiffPtr world_diff_;
1031 CollisionDetectorPtr collision_detector_;
1033 collision_detection::AllowedCollisionMatrixPtr acm_;
1038 std::unique_ptr<ObjectColorMap> object_colors_;
1041 std::unique_ptr<ObjectTypeMap> object_types_;
#define MOVEIT_STRUCT_FORWARD(C)
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
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.
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...
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.
std::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
bool isStateColliding(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.
Representation of a collision checking request.
Representation of a collision checking result.
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.