moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | Friends | List of all members
planning_scene::PlanningScene Class Reference

This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained. More...

#include <planning_scene.h>

Inheritance diagram for planning_scene::PlanningScene:
Inheritance graph
[legend]
Collaboration diagram for planning_scene::PlanningScene:
Collaboration graph
[legend]

Public Member Functions

 PlanningScene (const PlanningScene &)=delete
 PlanningScene cannot be copy-constructed. More...
 
PlanningSceneoperator= (const PlanningScene &)=delete
 PlanningScene cannot be copy-assigned. More...
 
 PlanningScene (const moveit::core::RobotModelConstPtr &robot_model, const collision_detection::WorldPtr &world=std::make_shared< collision_detection::World >())
 construct using an existing RobotModel More...
 
 PlanningScene (const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model, const collision_detection::WorldPtr &world=std::make_shared< collision_detection::World >())
 construct using a urdf and srdf. A RobotModel for the PlanningScene will be created using the urdf and srdf. More...
 
 ~PlanningScene ()
 
const std::string & getName () const
 Get the name of the planning scene. This is empty by default. More...
 
void setName (const std::string &name)
 Set the name of the planning scene. More...
 
PlanningScenePtr diff () const
 Return a new child PlanningScene that uses this one as parent. More...
 
PlanningScenePtr diff (const moveit_msgs::msg::PlanningScene &msg) const
 Return a new child PlanningScene that uses this one as parent and has the diffs specified by msg applied. More...
 
const PlanningSceneConstPtr & getParent () const
 Get the parent scene (with respect to which the diffs are maintained). This may be empty. More...
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 Get the kinematic model for which the planning scene is maintained. More...
 
const moveit::core::RobotStategetCurrentState () const
 Get the state at which the robot is assumed to be. More...
 
moveit::core::RobotStategetCurrentStateNonConst ()
 Get the state at which the robot is assumed to be. More...
 
moveit::core::RobotStatePtr getCurrentStateUpdated (const moveit_msgs::msg::RobotState &update) const
 Get a copy of the current state with components overwritten by the state message update. More...
 
void saveGeometryToStream (std::ostream &out) const
 Save the geometry of the planning scene to a stream, as plain text. More...
 
bool loadGeometryFromStream (std::istream &in)
 Load the geometry of the planning scene from a stream. More...
 
bool loadGeometryFromStream (std::istream &in, const Eigen::Isometry3d &offset)
 Load the geometry of the planning scene from a stream at a certain location using offset. More...
 
void getPlanningSceneDiffMsg (moveit_msgs::msg::PlanningScene &scene) const
 Fill the message scene with the differences between this instance of PlanningScene with respect to the parent. If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg() More...
 
void getPlanningSceneMsg (moveit_msgs::msg::PlanningScene &scene) const
 Construct a message (scene) with all the necessary data so that the scene can be later reconstructed to be exactly the same using setPlanningSceneMsg() More...
 
void getPlanningSceneMsg (moveit_msgs::msg::PlanningScene &scene, const moveit_msgs::msg::PlanningSceneComponents &comp) const
 Construct a message (scene) with the data requested in comp. If all options in comp are filled, this will be a complete planning scene message. More...
 
bool getCollisionObjectMsg (moveit_msgs::msg::CollisionObject &collision_obj, const std::string &ns) const
 Construct a message (collision_object) with the collision object data from the planning_scene for the requested object. More...
 
void getCollisionObjectMsgs (std::vector< moveit_msgs::msg::CollisionObject > &collision_objs) const
 Construct a vector of messages (collision_objects) with the collision object data for all objects in planning_scene. More...
 
bool getAttachedCollisionObjectMsg (moveit_msgs::msg::AttachedCollisionObject &attached_collision_obj, const std::string &ns) const
 Construct a message (attached_collision_object) with the attached collision object data from the planning_scene for the requested object. More...
 
void getAttachedCollisionObjectMsgs (std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs) const
 Construct a vector of messages (attached_collision_objects) with the attached collision object data for all objects in planning_scene. More...
 
bool getOctomapMsg (octomap_msgs::msg::OctomapWithPose &octomap) const
 Construct a message (octomap) with the octomap data from the planning_scene. More...
 
void getObjectColorMsgs (std::vector< moveit_msgs::msg::ObjectColor > &object_colors) const
 Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene. More...
 
bool setPlanningSceneDiffMsg (const moveit_msgs::msg::PlanningScene &scene)
 Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff (is_diff member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. Data from the message is only appended (and in cases such as e.g., the robot state, is overwritten). More...
 
bool setPlanningSceneMsg (const moveit_msgs::msg::PlanningScene &scene)
 Set this instance of a planning scene to be the same as the one serialized in the scene message, even if the message itself is marked as being a diff (is_diff member) More...
 
bool usePlanningSceneMsg (const moveit_msgs::msg::PlanningScene &scene)
 Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set. More...
 
bool shapesAndPosesFromCollisionObjectMessage (const moveit_msgs::msg::CollisionObject &object, Eigen::Isometry3d &object_pose_in_header_frame, std::vector< shapes::ShapeConstPtr > &shapes, EigenSTL::vector_Isometry3d &shape_poses)
 Takes the object message and returns the object pose, shapes and shape poses. If the object pose is empty (identity) but the shape pose is set, this uses the shape pose as the object pose. The shape pose becomes the identity instead. More...
 
bool processCollisionObjectMsg (const moveit_msgs::msg::CollisionObject &object)
 
bool processAttachedCollisionObjectMsg (const moveit_msgs::msg::AttachedCollisionObject &object)
 
bool processPlanningSceneWorldMsg (const moveit_msgs::msg::PlanningSceneWorld &world)
 
void processOctomapMsg (const octomap_msgs::msg::OctomapWithPose &map)
 
void processOctomapMsg (const octomap_msgs::msg::Octomap &map)
 
void processOctomapPtr (const std::shared_ptr< const octomap::OcTree > &octree, const Eigen::Isometry3d &t)
 
void removeAllCollisionObjects ()
 Clear all collision objects in planning scene. More...
 
void setCurrentState (const moveit_msgs::msg::RobotState &state)
 Set the current robot state to be state. If not all joint values are specified, the previously maintained joint values are kept. More...
 
void setCurrentState (const moveit::core::RobotState &state)
 Set the current robot state. More...
 
void setAttachedBodyUpdateCallback (const moveit::core::AttachedBodyCallback &callback)
 Set the callback to be triggered when changes are made to the current scene state. More...
 
void setCollisionObjectUpdateCallback (const collision_detection::World::ObserverCallbackFn &callback)
 Set the callback to be triggered when changes are made to the current scene world. More...
 
bool hasObjectColor (const std::string &id) const
 
const std_msgs::msg::ColorRGBA & getObjectColor (const std::string &id) const
 
void setObjectColor (const std::string &id, const std_msgs::msg::ColorRGBA &color)
 
void removeObjectColor (const std::string &id)
 
void getKnownObjectColors (ObjectColorMap &kc) const
 
bool hasObjectType (const std::string &id) const
 
const object_recognition_msgs::msg::ObjectType & getObjectType (const std::string &id) const
 
void setObjectType (const std::string &id, const object_recognition_msgs::msg::ObjectType &type)
 
void removeObjectType (const std::string &id)
 
void getKnownObjectTypes (ObjectTypeMap &kc) const
 
void clearDiffs ()
 Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it exists) the parent CollisionDetector (if it exists) This function is a no-op if there is no parent planning scene. More...
 
void pushDiffs (const PlanningScenePtr &scene)
 If there is a parent specified for this scene, then the diffs with respect to that parent are applied to a specified planning scene, whatever that scene may be. If there is no parent specified, this function is a no-op. More...
 
void decoupleParent ()
 Make sure that all the data maintained in this scene is local. All unmodified data is copied from the parent and the pointer to the parent is discarded. More...
 
void setStateFeasibilityPredicate (const StateFeasibilityFn &fn)
 Specify a predicate that decides whether states are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation. This is useful for setting up problem specific constraints (e.g., stability) More...
 
const StateFeasibilityFngetStateFeasibilityPredicate () const
 Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation. More...
 
void setMotionFeasibilityPredicate (const MotionFeasibilityFn &fn)
 Specify a predicate that decides whether motion segments are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation.
More...
 
const MotionFeasibilityFngetMotionFeasibilityPredicate () const
 Get the predicate that decides whether motion segments are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation. More...
 
bool isStateFeasible (const moveit_msgs::msg::RobotState &state, bool verbose=false) const
 Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. More...
 
bool isStateFeasible (const moveit::core::RobotState &state, bool verbose=false) const
 Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. More...
 
bool isStateConstrained (const moveit_msgs::msg::RobotState &state, const moveit_msgs::msg::Constraints &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateConstrained (const moveit::core::RobotState &state, const moveit_msgs::msg::Constraints &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateConstrained (const moveit_msgs::msg::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateConstrained (const moveit::core::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateValid (const moveit_msgs::msg::RobotState &state, const std::string &group="", bool verbose=false) const
 Check if a given state is valid. This means checking for collisions and feasibility. More...
 
bool isStateValid (const moveit::core::RobotState &state, const std::string &group="", bool verbose=false) const
 Check if a given state is valid. This means checking for collisions and feasibility. More...
 
bool isStateValid (const moveit_msgs::msg::RobotState &state, const moveit_msgs::msg::Constraints &constr, const std::string &group="", bool verbose=false) const
 Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. More...
 
bool isStateValid (const moveit::core::RobotState &state, const moveit_msgs::msg::Constraints &constr, const std::string &group="", bool verbose=false) const
 Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. More...
 
bool isStateValid (const moveit::core::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, const std::string &group="", bool verbose=false) const
 Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. More...
 
bool isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility) More...
 
bool isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. More...
 
bool isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const moveit_msgs::msg::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. More...
 
bool isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. More...
 
bool isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. More...
 
bool isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const moveit_msgs::msg::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. More...
 
bool isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). More...
 
bool isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility) More...
 
void getCostSources (const robot_trajectory::RobotTrajectory &trajectory, std::size_t max_costs, std::set< collision_detection::CostSource > &costs, double overlap_fraction=0.9) const
 Get the top max_costs cost sources for a specified trajectory. The resulting costs are stored in costs. More...
 
void getCostSources (const robot_trajectory::RobotTrajectory &trajectory, std::size_t max_costs, const std::string &group_name, std::set< collision_detection::CostSource > &costs, double overlap_fraction=0.9) const
 Get the top max_costs cost sources for a specified trajectory, but only for group group_name. The resulting costs are stored in costs. More...
 
void getCostSources (const moveit::core::RobotState &state, std::size_t max_costs, std::set< collision_detection::CostSource > &costs) const
 Get the top max_costs cost sources for a specified state. The resulting costs are stored in costs. More...
 
void getCostSources (const moveit::core::RobotState &state, std::size_t max_costs, const std::string &group_name, std::set< collision_detection::CostSource > &costs) const
 Get the top max_costs cost sources for a specified state, but only for group group_name. The resulting costs are stored in costs. More...
 
void printKnownObjects (std::ostream &out=std::cout) const
 Outputs debug information about the planning scene contents. More...
 
void allocateCollisionDetector (const collision_detection::CollisionDetectorAllocatorPtr &allocator)
 Allocate a new collision detector and replace the previous one if there was any. More...
 
Reasoning about frames
const std::string & getPlanningFrame () const
 Get the frame in which planning is performed. More...
 
const moveit::core::TransformsgetTransforms () const
 Get the set of fixed transforms from known frames to the planning frame. More...
 
const moveit::core::TransformsgetTransforms ()
 Get the set of fixed transforms from known frames to the planning frame. This variant is non-const and also updates the current state. More...
 
moveit::core::TransformsgetTransformsNonConst ()
 Get the set of fixed transforms from known frames to the planning frame. More...
 
const Eigen::Isometry3d & getFrameTransform (const std::string &id) const
 Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. More...
 
const Eigen::Isometry3d & getFrameTransform (const std::string &id)
 Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. Because this function is non-const, the current state transforms are also updated, if needed. More...
 
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, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. This function also updates the link transforms of state. More...
 
const Eigen::Isometry3d & getFrameTransform (const 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, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. More...
 
bool knowsFrameTransform (const std::string &id) const
 Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object. More...
 
bool knowsFrameTransform (const moveit::core::RobotState &state, const std::string &id) const
 Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object. More...
 
Reasoning about the geometry of the planning scene
const std::string getCollisionDetectorName () const
 
const collision_detection::WorldConstPtr & getWorld () const
 Get the representation of the world. More...
 
const collision_detection::WorldPtr & getWorldNonConst ()
 Get the representation of the world. More...
 
const collision_detection::CollisionEnvConstPtr & getCollisionEnv () const
 Get the active collision environment. More...
 
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded () const
 Get the active collision detector for the robot. More...
 
const collision_detection::CollisionEnvConstPtr & getCollisionEnv (const std::string &collision_detector_name) const
 Get a specific collision detector for the world. If not found return active CollisionWorld. More...
 
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded (const std::string &collision_detector_name) const
 Get a specific collision detector for the unpadded robot. If no found return active unpadded CollisionRobot. More...
 
const collision_detection::CollisionEnvPtr & getCollisionEnvNonConst ()
 Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot. More...
 
const collision_detection::AllowedCollisionMatrixgetAllowedCollisionMatrix () const
 Get the allowed collision matrix. More...
 
collision_detection::AllowedCollisionMatrixgetAllowedCollisionMatrixNonConst ()
 Get the allowed collision matrix. More...
 
Collision checking with respect to this planning scene
bool isStateColliding (const std::string &group="", bool verbose=false)
 Check if the current state is in collision (with the environment or self collision). If a group name is specified, collision checking is done for that group only. Since the function is non-const, the current state transforms are updated before the collision check. More...
 
bool isStateColliding (const std::string &group="", bool verbose=false) const
 Check if the current state is in collision (with the environment or self collision). If a group name is specified, collision checking is done for that group only. It is expected the current state transforms are up to date. More...
 
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 specified, collision checking is done for that group only. The link transforms for state are updated before the collision check. More...
 
bool isStateColliding (const 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 specified, collision checking is done for that group only. It is expected that the link transforms of state are up to date. More...
 
bool isStateColliding (const moveit_msgs::msg::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 specified, collision checking is done for that group only. More...
 
void checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
 Check whether the current state is in collision, and if needed, updates the collision transforms of the current state before the computation. More...
 
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. More...
 
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 non-const robot_state and calls updateCollisionBodyTransforms() on it. More...
 
void checkCollision (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. The collision transforms of robot_state are expected to be up to date. More...
 
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 collision matrix (acm). This variant of the function takes a non-const robot_state and updates its link transforms if needed. More...
 
void checkCollision (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 collision, with respect to a given allowed collision matrix (acm). More...
 
void checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
 Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Since the function is non-const, the current state transforms are also updated if needed. More...
 
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 instance that has no padding.
More...
 
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::CollisionRobot instance that has no padding.
More...
 
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::CollisionRobot instance that has no padding. Update the link transforms of robot_state if needed. More...
 
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 collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const robot_state and calls updates the link transforms if needed. More...
 
void checkCollisionUnpadded (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 collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding.
More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
 Check whether the current state is in self collision. More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
 Check whether the current state is in self collision. More...
 
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. More...
 
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. More...
 
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 collision matrix (acm). The link transforms of robot_state are updated if needed. More...
 
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 collision matrix (acm) More...
 
void getCollidingLinks (std::vector< std::string > &links)
 Get the names of the links that are involved in collisions for the current state. More...
 
void getCollidingLinks (std::vector< std::string > &links) const
 Get the names of the links that are involved in collisions for the current state. More...
 
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. Update the link transforms for robot_state if needed. More...
 
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. More...
 
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 allowed collision matrix (acm) More...
 
void getCollidingLinks (std::vector< std::string > &links, const 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 allowed collision matrix (acm) More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts)
 Get the names of the links that are involved in collisions for the current state. Update the link transforms for the current state if needed. More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts) const
 Get the names of the links that are involved in collisions for the current state. More...
 
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. Can be restricted to links part of or updated by group_name. More...
 
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. Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name. More...
 
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 allowed collision matrix (acm). Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name. More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, const 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 allowed collision matrix (acm). Can be restricted to links part of or updated by group_name. More...
 
Distance computation
double distanceToCollision (moveit::core::RobotState &robot_state) const
 The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions) More...
 
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-collisions) More...
 
double distanceToCollisionUnpadded (moveit::core::RobotState &robot_state) const
 The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding. More...
 
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-collisions), if the robot has no padding. More...
 
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, ignoring self-collisions and elements that are allowed to collide. More...
 
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, ignoring self-collisions and elements that are allowed to collide. More...
 
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, ignoring self-collisions and elements that are allowed to collide, if the robot has no padding. More...
 
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, ignoring self-collisions and elements that always allowed to collide, if the robot has no padding. More...
 

Static Public Member Functions

static bool isEmpty (const moveit_msgs::msg::PlanningScene &msg)
 Check if a message includes any information about a planning scene, or it is just a default, empty message. More...
 
static bool isEmpty (const moveit_msgs::msg::PlanningSceneWorld &msg)
 Check if a message includes any information about a planning scene world, or it is just a default, empty message. More...
 
static bool isEmpty (const moveit_msgs::msg::RobotState &msg)
 Check if a message includes any information about a robot state, or it is just a default, empty message. More...
 
static PlanningScenePtr clone (const PlanningSceneConstPtr &scene)
 Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not. More...
 

Static Public Attributes

static const std::string OCTOMAP_NS = "<octomap>"
 
static const std::string DEFAULT_SCENE_NAME = "(noname)"
 

Friends

struct CollisionDetector
 Enumerates the available collision detectors. More...
 

Detailed Description

This class maintains the representation of the environment as seen by a planning instance. The environment geometry, the robot geometry and state are maintained.

Definition at line 89 of file planning_scene.h.

Constructor & Destructor Documentation

◆ PlanningScene() [1/3]

planning_scene::PlanningScene::PlanningScene ( const PlanningScene )
delete

PlanningScene cannot be copy-constructed.

Here is the caller graph for this function:

◆ PlanningScene() [2/3]

planning_scene::PlanningScene::PlanningScene ( const moveit::core::RobotModelConstPtr &  robot_model,
const collision_detection::WorldPtr &  world = std::make_shared<collision_detection::World>() 
)

construct using an existing RobotModel

Definition at line 116 of file planning_scene.cpp.

◆ PlanningScene() [3/3]

planning_scene::PlanningScene::PlanningScene ( const urdf::ModelInterfaceSharedPtr &  urdf_model,
const srdf::ModelConstSharedPtr &  srdf_model,
const collision_detection::WorldPtr &  world = std::make_shared<collision_detection::World>() 
)

construct using a urdf and srdf. A RobotModel for the PlanningScene will be created using the urdf and srdf.

Definition at line 124 of file planning_scene.cpp.

◆ ~PlanningScene()

planning_scene::PlanningScene::~PlanningScene ( )

Definition at line 141 of file planning_scene.cpp.

Member Function Documentation

◆ allocateCollisionDetector()

void planning_scene::PlanningScene::allocateCollisionDetector ( const collision_detection::CollisionDetectorAllocatorPtr &  allocator)
inline

Allocate a new collision detector and replace the previous one if there was any.

The collision detector type is specified with (a shared pointer to) an allocator which is a subclass of CollisionDetectorAllocator. This identifies a combination of CollisionWorld/CollisionRobot which can be used together.

A new PlanningScene uses an FCL collision detector by default.

example: to add FCL collision detection (normally not necessary) call planning_scene->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());

Definition at line 953 of file planning_scene.h.

Here is the caller graph for this function:

◆ checkCollision() [1/6]

void planning_scene::PlanningScene::checkCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
)

Check whether the current state is in collision, and if needed, updates the collision transforms of the current state before the computation.

Definition at line 360 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkCollision() [2/6]

void planning_scene::PlanningScene::checkCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
) const
inline

Check whether the current state is in collision. The current state is expected to be updated.

Definition at line 343 of file planning_scene.h.

◆ checkCollision() [3/6]

void planning_scene::PlanningScene::checkCollision ( 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. The collision transforms of robot_state are expected to be up to date.

Definition at line 369 of file planning_scene.cpp.

Here is the call graph for this function:

◆ checkCollision() [4/6]

void planning_scene::PlanningScene::checkCollision ( 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 collision, with respect to a given allowed collision matrix (acm).

Definition at line 385 of file planning_scene.cpp.

Here is the call graph for this function:

◆ checkCollision() [5/6]

void planning_scene::PlanningScene::checkCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state 
) const
inline

Check whether a specified state (robot_state) is in collision. This variant of the function takes a non-const robot_state and calls updateCollisionBodyTransforms() on it.

Definition at line 350 of file planning_scene.h.

Here is the call graph for this function:

◆ checkCollision() [6/6]

void planning_scene::PlanningScene::checkCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm). This variant of the function takes a non-const robot_state and updates its link transforms if needed.

Definition at line 366 of file planning_scene.h.

Here is the call graph for this function:

◆ checkCollisionUnpadded() [1/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
)

Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Since the function is non-const, the current state transforms are also updated if needed.

Definition at line 398 of file planning_scene.cpp.

Here is the call graph for this function:

◆ checkCollisionUnpadded() [2/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
) const
inline

Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding.

Definition at line 388 of file planning_scene.h.

◆ checkCollisionUnpadded() [3/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState robot_state 
) const
inline

Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding.

Definition at line 396 of file planning_scene.h.

◆ checkCollisionUnpadded() [4/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( 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 collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding.

Definition at line 407 of file planning_scene.cpp.

Here is the call graph for this function:

◆ checkCollisionUnpadded() [5/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state 
) const
inline

Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of robot_state if needed.

Definition at line 406 of file planning_scene.h.

Here is the call graph for this function:

◆ checkCollisionUnpadded() [6/6]

void planning_scene::PlanningScene::checkCollisionUnpadded ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const robot_state and calls updates the link transforms if needed.

Definition at line 417 of file planning_scene.h.

Here is the call graph for this function:

◆ checkSelfCollision() [1/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
)

Check whether the current state is in self collision.

Definition at line 376 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ checkSelfCollision() [2/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res 
) const
inline

Check whether the current state is in self collision.

Definition at line 435 of file planning_scene.h.

◆ checkSelfCollision() [3/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState robot_state 
) const
inline

Check whether a specified state (robot_state) is in self collision.

Definition at line 450 of file planning_scene.h.

◆ checkSelfCollision() [4/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm)

Definition at line 469 of file planning_scene.h.

◆ checkSelfCollision() [5/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state 
) const
inline

Check whether a specified state (robot_state) is in self collision.

Definition at line 442 of file planning_scene.h.

Here is the call graph for this function:

◆ checkSelfCollision() [6/6]

void planning_scene::PlanningScene::checkSelfCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm). The link transforms of robot_state are updated if needed.

Definition at line 459 of file planning_scene.h.

Here is the call graph for this function:

◆ clearDiffs()

void planning_scene::PlanningScene::clearDiffs ( )

Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it exists) the parent CollisionDetector (if it exists) This function is a no-op if there is no parent planning scene.

Definition at line 282 of file planning_scene.cpp.

Here is the call graph for this function:

◆ clone()

PlanningScenePtr planning_scene::PlanningScene::clone ( const PlanningSceneConstPtr &  scene)
static

Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not.

Definition at line 195 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ decoupleParent()

void planning_scene::PlanningScene::decoupleParent ( )

Make sure that all the data maintained in this scene is local. All unmodified data is copied from the parent and the pointer to the parent is discarded.

Definition at line 1097 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ diff() [1/2]

PlanningScenePtr planning_scene::PlanningScene::diff ( ) const

Return a new child PlanningScene that uses this one as parent.

The child scene has its own copy of the world. It maintains a list (in world_diff_) of changes made to the child world.

The robot_model_, robot_state_, scene_transforms_, and acm_ are not copied. They are shared with the parent. So if changes to these are made in the parent they will be visible in the child. But if any of these is modified (i.e. if the get*NonConst functions are called) in the child then a copy is made and subsequent changes to the corresponding member of the parent will no longer be visible in the child.

Definition at line 203 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ diff() [2/2]

PlanningScenePtr planning_scene::PlanningScene::diff ( const moveit_msgs::msg::PlanningScene &  msg) const

Return a new child PlanningScene that uses this one as parent and has the diffs specified by msg applied.

Definition at line 208 of file planning_scene.cpp.

Here is the call graph for this function:

◆ distanceToCollision() [1/4]

double planning_scene::PlanningScene::distanceToCollision ( const moveit::core::RobotState robot_state) const
inline

The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions)

Definition at line 580 of file planning_scene.h.

◆ distanceToCollision() [2/4]

double planning_scene::PlanningScene::distanceToCollision ( const moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide.

Definition at line 613 of file planning_scene.h.

◆ distanceToCollision() [3/4]

double planning_scene::PlanningScene::distanceToCollision ( moveit::core::RobotState robot_state) const
inline

The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions)

Definition at line 571 of file planning_scene.h.

Here is the call graph for this function:

◆ distanceToCollision() [4/4]

double planning_scene::PlanningScene::distanceToCollision ( moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide.

Definition at line 603 of file planning_scene.h.

Here is the call graph for this function:

◆ distanceToCollisionUnpadded() [1/4]

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( const moveit::core::RobotState robot_state) const
inline

The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding.

Definition at line 595 of file planning_scene.h.

◆ distanceToCollisionUnpadded() [2/4]

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( const moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that always allowed to collide, if the robot has no padding.

Definition at line 632 of file planning_scene.h.

◆ distanceToCollisionUnpadded() [3/4]

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( moveit::core::RobotState robot_state) const
inline

The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding.

Definition at line 587 of file planning_scene.h.

Here is the call graph for this function:

◆ distanceToCollisionUnpadded() [4/4]

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide, if the robot has no padding.

Definition at line 622 of file planning_scene.h.

Here is the call graph for this function:

◆ getAllowedCollisionMatrix()

const collision_detection::AllowedCollisionMatrix& planning_scene::PlanningScene::getAllowedCollisionMatrix ( ) const
inline

Get the allowed collision matrix.

Definition at line 290 of file planning_scene.h.

Here is the caller graph for this function:

◆ getAllowedCollisionMatrixNonConst()

collision_detection::AllowedCollisionMatrix & planning_scene::PlanningScene::getAllowedCollisionMatrixNonConst ( )

Get the allowed collision matrix.

Definition at line 509 of file planning_scene.cpp.

◆ getAttachedCollisionObjectMsg()

bool planning_scene::PlanningScene::getAttachedCollisionObjectMsg ( moveit_msgs::msg::AttachedCollisionObject &  attached_collision_obj,
const std::string &  ns 
) const

Construct a message (attached_collision_object) with the attached collision object data from the planning_scene for the requested object.

Definition at line 716 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getAttachedCollisionObjectMsgs()

void planning_scene::PlanningScene::getAttachedCollisionObjectMsgs ( std::vector< moveit_msgs::msg::AttachedCollisionObject > &  attached_collision_objs) const

Construct a vector of messages (attached_collision_objects) with the attached collision object data for all objects in planning_scene.

Definition at line 732 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCollidingLinks() [1/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links)

Get the names of the links that are involved in collisions for the current state.

Definition at line 445 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCollidingLinks() [2/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links) const
inline

Get the names of the links that are involved in collisions for the current state.

Definition at line 481 of file planning_scene.h.

◆ getCollidingLinks() [3/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links,
const moveit::core::RobotState robot_state 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state.

Definition at line 495 of file planning_scene.h.

◆ getCollidingLinks() [4/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links,
const 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 allowed collision matrix (acm)

Definition at line 453 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCollidingLinks() [5/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links,
moveit::core::RobotState robot_state 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed.

Definition at line 488 of file planning_scene.h.

Here is the call graph for this function:

◆ getCollidingLinks() [6/6]

void planning_scene::PlanningScene::getCollidingLinks ( std::vector< std::string > &  links,
moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm)

Definition at line 502 of file planning_scene.h.

Here is the call graph for this function:

◆ getCollidingPairs() [1/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts)

Get the names of the links that are involved in collisions for the current state. Update the link transforms for the current state if needed.

Definition at line 422 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCollidingPairs() [2/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts) const
inline

Get the names of the links that are involved in collisions for the current state.

Definition at line 519 of file planning_scene.h.

◆ getCollidingPairs() [3/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
const 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 allowed collision matrix (acm). Can be restricted to links part of or updated by group_name.

Definition at line 430 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCollidingPairs() [4/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
const moveit::core::RobotState robot_state,
const std::string &  group_name = "" 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state. Can be restricted to links part of or updated by group_name.

Definition at line 526 of file planning_scene.h.

◆ getCollidingPairs() [5/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
moveit::core::RobotState robot_state,
const collision_detection::AllowedCollisionMatrix acm,
const std::string &  group_name = "" 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm). Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name.

Definition at line 546 of file planning_scene.h.

Here is the call graph for this function:

◆ getCollidingPairs() [6/6]

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
moveit::core::RobotState robot_state,
const std::string &  group_name = "" 
) const
inline

Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name.

Definition at line 535 of file planning_scene.h.

Here is the call graph for this function:

◆ getCollisionDetectorName()

const std::string planning_scene::PlanningScene::getCollisionDetectorName ( ) const
inline

Definition at line 245 of file planning_scene.h.

Here is the caller graph for this function:

◆ getCollisionEnv() [1/2]

const collision_detection::CollisionEnvConstPtr& planning_scene::PlanningScene::getCollisionEnv ( ) const
inline

Get the active collision environment.

Definition at line 266 of file planning_scene.h.

Here is the caller graph for this function:

◆ getCollisionEnv() [2/2]

const collision_detection::CollisionEnvConstPtr & planning_scene::PlanningScene::getCollisionEnv ( const std::string &  collision_detector_name) const

Get a specific collision detector for the world. If not found return active CollisionWorld.

Definition at line 255 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCollisionEnvNonConst()

const collision_detection::CollisionEnvPtr & planning_scene::PlanningScene::getCollisionEnvNonConst ( )

Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot.

Definition at line 470 of file planning_scene.cpp.

◆ getCollisionEnvUnpadded() [1/2]

const collision_detection::CollisionEnvConstPtr& planning_scene::PlanningScene::getCollisionEnvUnpadded ( ) const
inline

Get the active collision detector for the robot.

Definition at line 272 of file planning_scene.h.

Here is the caller graph for this function:

◆ getCollisionEnvUnpadded() [2/2]

const collision_detection::CollisionEnvConstPtr & planning_scene::PlanningScene::getCollisionEnvUnpadded ( const std::string &  collision_detector_name) const

Get a specific collision detector for the unpadded robot. If no found return active unpadded CollisionRobot.

Definition at line 268 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCollisionObjectMsg()

bool planning_scene::PlanningScene::getCollisionObjectMsg ( moveit_msgs::msg::CollisionObject &  collision_obj,
const std::string &  ns 
) const

Construct a message (collision_object) with the collision object data from the planning_scene for the requested object.

Definition at line 666 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCollisionObjectMsgs()

void planning_scene::PlanningScene::getCollisionObjectMsgs ( std::vector< moveit_msgs::msg::CollisionObject > &  collision_objs) const

Construct a vector of messages (collision_objects) with the collision object data for all objects in planning_scene.

Definition at line 704 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCostSources() [1/4]

void planning_scene::PlanningScene::getCostSources ( const moveit::core::RobotState state,
std::size_t  max_costs,
const std::string &  group_name,
std::set< collision_detection::CostSource > &  costs 
) const

Get the top max_costs cost sources for a specified state, but only for group group_name. The resulting costs are stored in costs.

Definition at line 2223 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCostSources() [2/4]

void planning_scene::PlanningScene::getCostSources ( const moveit::core::RobotState state,
std::size_t  max_costs,
std::set< collision_detection::CostSource > &  costs 
) const

Get the top max_costs cost sources for a specified state. The resulting costs are stored in costs.

Definition at line 2217 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCostSources() [3/4]

void planning_scene::PlanningScene::getCostSources ( const robot_trajectory::RobotTrajectory trajectory,
std::size_t  max_costs,
const std::string &  group_name,
std::set< collision_detection::CostSource > &  costs,
double  overlap_fraction = 0.9 
) const

Get the top max_costs cost sources for a specified trajectory, but only for group group_name. The resulting costs are stored in costs.

Definition at line 2183 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getCostSources() [4/4]

void planning_scene::PlanningScene::getCostSources ( const robot_trajectory::RobotTrajectory trajectory,
std::size_t  max_costs,
std::set< collision_detection::CostSource > &  costs,
double  overlap_fraction = 0.9 
) const

Get the top max_costs cost sources for a specified trajectory. The resulting costs are stored in costs.

Definition at line 2177 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ getCurrentState()

const moveit::core::RobotState& planning_scene::PlanningScene::getCurrentState ( ) const
inline

Get the state at which the robot is assumed to be.

Definition at line 158 of file planning_scene.h.

Here is the caller graph for this function:

◆ getCurrentStateNonConst()

moveit::core::RobotState & planning_scene::PlanningScene::getCurrentStateNonConst ( )

Get the state at which the robot is assumed to be.

Definition at line 475 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ getCurrentStateUpdated()

moveit::core::RobotStatePtr planning_scene::PlanningScene::getCurrentStateUpdated ( const moveit_msgs::msg::RobotState &  update) const

Get a copy of the current state with components overwritten by the state message update.

Definition at line 486 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getFrameTransform() [1/4]

const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform ( const 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, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not.

Definition at line 1801 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getFrameTransform() [2/4]

const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform ( const std::string &  id)

Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. Because this function is non-const, the current state transforms are also updated, if needed.

Definition at line 1793 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getFrameTransform() [3/4]

const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform ( const std::string &  id) const

Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not.

Definition at line 1788 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getFrameTransform() [4/4]

const Eigen::Isometry3d& planning_scene::PlanningScene::getFrameTransform ( moveit::core::RobotState state,
const std::string &  id 
) const
inline

Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. This function also updates the link transforms of state.

Definition at line 218 of file planning_scene.h.

Here is the call graph for this function:

◆ getKnownObjectColors()

void planning_scene::PlanningScene::getKnownObjectColors ( ObjectColorMap kc) const

Definition at line 1907 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ getKnownObjectTypes()

void planning_scene::PlanningScene::getKnownObjectTypes ( ObjectTypeMap kc) const

Definition at line 1873 of file planning_scene.cpp.

◆ getMotionFeasibilityPredicate()

const MotionFeasibilityFn& planning_scene::PlanningScene::getMotionFeasibilityPredicate ( ) const
inline

Get the predicate that decides whether motion segments are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation.

Definition at line 795 of file planning_scene.h.

◆ getName()

const std::string& planning_scene::PlanningScene::getName ( ) const
inline

Get the name of the planning scene. This is empty by default.

Definition at line 117 of file planning_scene.h.

Here is the caller graph for this function:

◆ getObjectColor()

const std_msgs::msg::ColorRGBA & planning_scene::PlanningScene::getObjectColor ( const std::string &  id) const

Definition at line 1893 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ getObjectColorMsgs()

void planning_scene::PlanningScene::getObjectColorMsgs ( std::vector< moveit_msgs::msg::ObjectColor > &  object_colors) const

Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene.

Definition at line 761 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getObjectType()

const object_recognition_msgs::msg::ObjectType & planning_scene::PlanningScene::getObjectType ( const std::string &  id) const

Definition at line 1846 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ getOctomapMsg()

bool planning_scene::PlanningScene::getOctomapMsg ( octomap_msgs::msg::OctomapWithPose &  octomap) const

Construct a message (octomap) with the octomap data from the planning_scene.

Definition at line 740 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getParent()

const PlanningSceneConstPtr& planning_scene::PlanningScene::getParent ( ) const
inline

Get the parent scene (with respect to which the diffs are maintained). This may be empty.

Definition at line 145 of file planning_scene.h.

◆ getPlanningFrame()

const std::string& planning_scene::PlanningScene::getPlanningFrame ( ) const
inline

Get the frame in which planning is performed.

Definition at line 175 of file planning_scene.h.

Here is the caller graph for this function:

◆ getPlanningSceneDiffMsg()

void planning_scene::PlanningScene::getPlanningSceneDiffMsg ( moveit_msgs::msg::PlanningScene &  scene) const

Fill the message scene with the differences between this instance of PlanningScene with respect to the parent. If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg()

Definition at line 537 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getPlanningSceneMsg() [1/2]

void planning_scene::PlanningScene::getPlanningSceneMsg ( moveit_msgs::msg::PlanningScene &  scene) const

Construct a message (scene) with all the necessary data so that the scene can be later reconstructed to be exactly the same using setPlanningSceneMsg()

Definition at line 776 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getPlanningSceneMsg() [2/2]

void planning_scene::PlanningScene::getPlanningSceneMsg ( moveit_msgs::msg::PlanningScene &  scene,
const moveit_msgs::msg::PlanningSceneComponents &  comp 
) const

Construct a message (scene) with the data requested in comp. If all options in comp are filled, this will be a complete planning scene message.

Definition at line 797 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& planning_scene::PlanningScene::getRobotModel ( ) const
inline

Get the kinematic model for which the planning scene is maintained.

Definition at line 151 of file planning_scene.h.

Here is the caller graph for this function:

◆ getStateFeasibilityPredicate()

const StateFeasibilityFn& planning_scene::PlanningScene::getStateFeasibilityPredicate ( ) const
inline

Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation.

Definition at line 781 of file planning_scene.h.

◆ getTransforms() [1/2]

const moveit::core::Transforms & planning_scene::PlanningScene::getTransforms ( )

Get the set of fixed transforms from known frames to the planning frame. This variant is non-const and also updates the current state.

Definition at line 516 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getTransforms() [2/2]

const moveit::core::Transforms& planning_scene::PlanningScene::getTransforms ( ) const
inline

Get the set of fixed transforms from known frames to the planning frame.

Definition at line 182 of file planning_scene.h.

Here is the caller graph for this function:

◆ getTransformsNonConst()

moveit::core::Transforms & planning_scene::PlanningScene::getTransformsNonConst ( )

Get the set of fixed transforms from known frames to the planning frame.

Definition at line 523 of file planning_scene.cpp.

Here is the call graph for this function:

◆ getWorld()

const collision_detection::WorldConstPtr& planning_scene::PlanningScene::getWorld ( ) const
inline

Get the representation of the world.

Definition at line 252 of file planning_scene.h.

Here is the caller graph for this function:

◆ getWorldNonConst()

const collision_detection::WorldPtr& planning_scene::PlanningScene::getWorldNonConst ( )
inline

Get the representation of the world.

Definition at line 259 of file planning_scene.h.

◆ hasObjectColor()

bool planning_scene::PlanningScene::hasObjectColor ( const std::string &  id) const

Definition at line 1883 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ hasObjectType()

bool planning_scene::PlanningScene::hasObjectType ( const std::string &  id) const

Definition at line 1836 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ isEmpty() [1/3]

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::msg::PlanningScene &  msg)
static

Check if a message includes any information about a planning scene, or it is just a default, empty message.

Definition at line 101 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isEmpty() [2/3]

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::msg::PlanningSceneWorld &  msg)
static

Check if a message includes any information about a planning scene world, or it is just a default, empty message.

Definition at line 111 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isEmpty() [3/3]

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::msg::RobotState &  msg)
static

Check if a message includes any information about a robot state, or it is just a default, empty message.

Definition at line 106 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [1/8]

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::msg::RobotState &  start_state,
const moveit_msgs::msg::RobotTrajectory &  trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const moveit_msgs::msg::Constraints &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory.

Definition at line 2072 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [2/8]

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::msg::RobotState &  start_state,
const moveit_msgs::msg::RobotTrajectory &  trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory.

Definition at line 2063 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [3/8]

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::msg::RobotState &  start_state,
const moveit_msgs::msg::RobotTrajectory &  trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const std::vector< moveit_msgs::msg::Constraints > &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory.

Definition at line 2082 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [4/8]

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::msg::RobotState &  start_state,
const moveit_msgs::msg::RobotTrajectory &  trajectory,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility)

Definition at line 2054 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ isPathValid() [5/8]

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const moveit_msgs::msg::Constraints &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory.

Definition at line 2152 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [6/8]

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction).

Definition at line 2161 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [7/8]

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const moveit_msgs::msg::Constraints &  path_constraints,
const std::vector< moveit_msgs::msg::Constraints > &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory.

Definition at line 2095 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isPathValid() [8/8]

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = nullptr 
) const

Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility)

Definition at line 2169 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateColliding() [1/5]

bool planning_scene::PlanningScene::isStateColliding ( const 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 specified, collision checking is done for that group only. It is expected that the link transforms of state are up to date.

Definition at line 1951 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateColliding() [2/5]

bool planning_scene::PlanningScene::isStateColliding ( const moveit_msgs::msg::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 specified, collision checking is done for that group only.

Definition at line 1935 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateColliding() [3/5]

bool planning_scene::PlanningScene::isStateColliding ( const std::string &  group = "",
bool  verbose = false 
)

Check if the current state is in collision (with the environment or self collision). If a group name is specified, collision checking is done for that group only. Since the function is non-const, the current state transforms are updated before the collision check.

Definition at line 1943 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isStateColliding() [4/5]

bool planning_scene::PlanningScene::isStateColliding ( const std::string &  group = "",
bool  verbose = false 
) const
inline

Check if the current state is in collision (with the environment or self collision). If a group name is specified, collision checking is done for that group only. It is expected the current state transforms are up to date.

Definition at line 312 of file planning_scene.h.

Here is the call graph for this function:

◆ isStateColliding() [5/5]

bool planning_scene::PlanningScene::isStateColliding ( moveit::core::RobotState state,
const std::string &  group = "",
bool  verbose = false 
) const
inline

Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only. The link transforms for state are updated before the collision check.

Definition at line 321 of file planning_scene.h.

Here is the call graph for this function:

◆ isStateConstrained() [1/4]

bool planning_scene::PlanningScene::isStateConstrained ( const moveit::core::RobotState state,
const kinematic_constraints::KinematicConstraintSet constr,
bool  verbose = false 
) const

Check if a given state satisfies a set of constraints.

Definition at line 2007 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateConstrained() [2/4]

bool planning_scene::PlanningScene::isStateConstrained ( const moveit::core::RobotState state,
const moveit_msgs::msg::Constraints &  constr,
bool  verbose = false 
) const

Check if a given state satisfies a set of constraints.

Definition at line 1987 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateConstrained() [3/4]

bool planning_scene::PlanningScene::isStateConstrained ( const moveit_msgs::msg::RobotState &  state,
const kinematic_constraints::KinematicConstraintSet constr,
bool  verbose = false 
) const

Check if a given state satisfies a set of constraints.

Definition at line 1999 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateConstrained() [4/4]

bool planning_scene::PlanningScene::isStateConstrained ( const moveit_msgs::msg::RobotState &  state,
const moveit_msgs::msg::Constraints &  constr,
bool  verbose = false 
) const

Check if a given state satisfies a set of constraints.

Definition at line 1979 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isStateFeasible() [1/2]

bool planning_scene::PlanningScene::isStateFeasible ( const moveit::core::RobotState state,
bool  verbose = false 
) const

Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified.

Definition at line 1972 of file planning_scene.cpp.

◆ isStateFeasible() [2/2]

bool planning_scene::PlanningScene::isStateFeasible ( const moveit_msgs::msg::RobotState &  state,
bool  verbose = false 
) const

Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified.

Definition at line 1961 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isStateValid() [1/5]

bool planning_scene::PlanningScene::isStateValid ( const moveit::core::RobotState state,
const kinematic_constraints::KinematicConstraintSet constr,
const std::string &  group = "",
bool  verbose = false 
) const

Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well.

Definition at line 2043 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateValid() [2/5]

bool planning_scene::PlanningScene::isStateValid ( const moveit::core::RobotState state,
const moveit_msgs::msg::Constraints &  constr,
const std::string &  group = "",
bool  verbose = false 
) const

Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well.

Definition at line 2033 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateValid() [3/5]

bool planning_scene::PlanningScene::isStateValid ( const moveit::core::RobotState state,
const std::string &  group = "",
bool  verbose = false 
) const

Check if a given state is valid. This means checking for collisions and feasibility.

Definition at line 2013 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateValid() [4/5]

bool planning_scene::PlanningScene::isStateValid ( const moveit_msgs::msg::RobotState &  state,
const moveit_msgs::msg::Constraints &  constr,
const std::string &  group = "",
bool  verbose = false 
) const

Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well.

Definition at line 2025 of file planning_scene.cpp.

Here is the call graph for this function:

◆ isStateValid() [5/5]

bool planning_scene::PlanningScene::isStateValid ( const moveit_msgs::msg::RobotState &  state,
const std::string &  group = "",
bool  verbose = false 
) const

Check if a given state is valid. This means checking for collisions and feasibility.

Definition at line 2019 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ knowsFrameTransform() [1/2]

bool planning_scene::PlanningScene::knowsFrameTransform ( const moveit::core::RobotState state,
const std::string &  id 
) const

Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object.

Definition at line 1824 of file planning_scene.cpp.

Here is the call graph for this function:

◆ knowsFrameTransform() [2/2]

bool planning_scene::PlanningScene::knowsFrameTransform ( const std::string &  id) const

Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object.

Definition at line 1819 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ loadGeometryFromStream() [1/2]

bool planning_scene::PlanningScene::loadGeometryFromStream ( std::istream &  in)

Load the geometry of the planning scene from a stream.

Definition at line 905 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ loadGeometryFromStream() [2/2]

bool planning_scene::PlanningScene::loadGeometryFromStream ( std::istream &  in,
const Eigen::Isometry3d &  offset 
)

Load the geometry of the planning scene from a stream at a certain location using offset.

Definition at line 910 of file planning_scene.cpp.

Here is the call graph for this function:

◆ operator=()

PlanningScene& planning_scene::PlanningScene::operator= ( const PlanningScene )
delete

PlanningScene cannot be copy-assigned.

◆ printKnownObjects()

void planning_scene::PlanningScene::printKnownObjects ( std::ostream &  out = std::cout) const

Outputs debug information about the planning scene contents.

Definition at line 2236 of file planning_scene.cpp.

Here is the call graph for this function:

◆ processAttachedCollisionObjectMsg()

bool planning_scene::PlanningScene::processAttachedCollisionObjectMsg ( const moveit_msgs::msg::AttachedCollisionObject &  object)

Definition at line 1360 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCollisionObjectMsg()

bool planning_scene::PlanningScene::processCollisionObjectMsg ( const moveit_msgs::msg::CollisionObject &  object)

Definition at line 1578 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ processOctomapMsg() [1/2]

void planning_scene::PlanningScene::processOctomapMsg ( const octomap_msgs::msg::Octomap &  map)

Definition at line 1266 of file planning_scene.cpp.

Here is the call graph for this function:

◆ processOctomapMsg() [2/2]

void planning_scene::PlanningScene::processOctomapMsg ( const octomap_msgs::msg::OctomapWithPose &  map)

Definition at line 1304 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processOctomapPtr()

void planning_scene::PlanningScene::processOctomapPtr ( const std::shared_ptr< const octomap::OcTree > &  octree,
const Eigen::Isometry3d &  t 
)

Definition at line 1327 of file planning_scene.cpp.

◆ processPlanningSceneWorldMsg()

bool planning_scene::PlanningScene::processPlanningSceneWorldMsg ( const moveit_msgs::msg::PlanningSceneWorld &  world)

Definition at line 1229 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ pushDiffs()

void planning_scene::PlanningScene::pushDiffs ( const PlanningScenePtr &  scene)

If there is a parent specified for this scene, then the diffs with respect to that parent are applied to a specified planning scene, whatever that scene may be. If there is no parent specified, this function is a no-op.

Definition at line 304 of file planning_scene.cpp.

Here is the call graph for this function:

◆ removeAllCollisionObjects()

void planning_scene::PlanningScene::removeAllCollisionObjects ( )

Clear all collision objects in planning scene.

Definition at line 1292 of file planning_scene.cpp.

Here is the call graph for this function:

◆ removeObjectColor()

void planning_scene::PlanningScene::removeObjectColor ( const std::string &  id)

Definition at line 1929 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ removeObjectType()

void planning_scene::PlanningScene::removeObjectType ( const std::string &  id)

Definition at line 1867 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ saveGeometryToStream()

void planning_scene::PlanningScene::saveGeometryToStream ( std::ostream &  out) const

Save the geometry of the planning scene to a stream, as plain text.

Definition at line 863 of file planning_scene.cpp.

Here is the call graph for this function:

◆ setAttachedBodyUpdateCallback()

void planning_scene::PlanningScene::setAttachedBodyUpdateCallback ( const moveit::core::AttachedBodyCallback callback)

Set the callback to be triggered when changes are made to the current scene state.

Definition at line 493 of file planning_scene.cpp.

◆ setCollisionObjectUpdateCallback()

void planning_scene::PlanningScene::setCollisionObjectUpdateCallback ( const collision_detection::World::ObserverCallbackFn callback)

Set the callback to be triggered when changes are made to the current scene world.

Definition at line 500 of file planning_scene.cpp.

◆ setCurrentState() [1/2]

void planning_scene::PlanningScene::setCurrentState ( const moveit::core::RobotState state)

Set the current robot state.

Definition at line 1092 of file planning_scene.cpp.

Here is the call graph for this function:

◆ setCurrentState() [2/2]

void planning_scene::PlanningScene::setCurrentState ( const moveit_msgs::msg::RobotState &  state)

Set the current robot state to be state. If not all joint values are specified, the previously maintained joint values are kept.

Definition at line 1059 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setMotionFeasibilityPredicate()

void planning_scene::PlanningScene::setMotionFeasibilityPredicate ( const MotionFeasibilityFn fn)
inline

Specify a predicate that decides whether motion segments are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation.

Definition at line 788 of file planning_scene.h.

◆ setName()

void planning_scene::PlanningScene::setName ( const std::string &  name)
inline

Set the name of the planning scene.

Definition at line 123 of file planning_scene.h.

◆ setObjectColor()

void planning_scene::PlanningScene::setObjectColor ( const std::string &  id,
const std_msgs::msg::ColorRGBA &  color 
)

Definition at line 1917 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ setObjectType()

void planning_scene::PlanningScene::setObjectType ( const std::string &  id,
const object_recognition_msgs::msg::ObjectType &  type 
)

Definition at line 1860 of file planning_scene.cpp.

Here is the caller graph for this function:

◆ setPlanningSceneDiffMsg()

bool planning_scene::PlanningScene::setPlanningSceneDiffMsg ( const moveit_msgs::msg::PlanningScene &  scene)

Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff (is_diff member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. Data from the message is only appended (and in cases such as e.g., the robot state, is overwritten).

Definition at line 1153 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setPlanningSceneMsg()

bool planning_scene::PlanningScene::setPlanningSceneMsg ( const moveit_msgs::msg::PlanningScene &  scene)

Set this instance of a planning scene to be the same as the one serialized in the scene message, even if the message itself is marked as being a diff (is_diff member)

Definition at line 1204 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setStateFeasibilityPredicate()

void planning_scene::PlanningScene::setStateFeasibilityPredicate ( const StateFeasibilityFn fn)
inline

Specify a predicate that decides whether states are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation. This is useful for setting up problem specific constraints (e.g., stability)

Definition at line 774 of file planning_scene.h.

◆ shapesAndPosesFromCollisionObjectMessage()

bool planning_scene::PlanningScene::shapesAndPosesFromCollisionObjectMessage ( const moveit_msgs::msg::CollisionObject &  object,
Eigen::Isometry3d &  object_pose_in_header_frame,
std::vector< shapes::ShapeConstPtr > &  shapes,
EigenSTL::vector_Isometry3d &  shape_poses 
)

Takes the object message and returns the object pose, shapes and shape poses. If the object pose is empty (identity) but the shape pose is set, this uses the shape pose as the object pose. The shape pose becomes the identity instead.

Definition at line 1620 of file planning_scene.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ usePlanningSceneMsg()

bool planning_scene::PlanningScene::usePlanningSceneMsg ( const moveit_msgs::msg::PlanningScene &  scene)

Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set.

Definition at line 1238 of file planning_scene.cpp.

Here is the call graph for this function:

Friends And Related Function Documentation

◆ CollisionDetector

friend struct CollisionDetector
friend

Enumerates the available collision detectors.

Definition at line 1008 of file planning_scene.h.

Member Data Documentation

◆ DEFAULT_SCENE_NAME

const std::string planning_scene::PlanningScene::DEFAULT_SCENE_NAME = "(noname)"
static

Definition at line 112 of file planning_scene.h.

◆ OCTOMAP_NS

const std::string planning_scene::PlanningScene::OCTOMAP_NS = "<octomap>"
static

Definition at line 111 of file planning_scene.h.


The documentation for this class was generated from the following files: