Classes | Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Static Private Member Functions | Private 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]

Classes

struct  CollisionDetector
 

Public Member Functions

void clearDiffs ()
 Clear the diffs accumulated for this planning scene, with respect to the parent. This function is a no-op if there is no parent specified. 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...
 
PlanningScenePtr diff () const
 Return a new child PlanningScene that uses this one as parent. More...
 
PlanningScenePtr diff (const moveit_msgs::PlanningScene &msg) const
 Return a new child PlanningScene that uses this one as parent and has the diffs specified by msg applied. More...
 
bool getAttachedCollisionObjectMsg (moveit_msgs::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::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 getCollisionObjectMsg (moveit_msgs::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::CollisionObject > &collision_objs) const
 Construct a vector of messages (collision_objects) with the collision object data for all objects in planning_scene. 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 robot_state::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 robot_state::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...
 
const robot_state::RobotStategetCurrentState () const
 Get the state at which the robot is assumed to be. More...
 
robot_state::RobotStategetCurrentStateNonConst ()
 Get the state at which the robot is assumed to be. More...
 
robot_state::RobotStatePtr getCurrentStateUpdated (const moveit_msgs::RobotState &update) const
 Get a copy of the current state with components overwritten by the state message update. More...
 
void getKnownObjectColors (ObjectColorMap &kc) const
 
void getKnownObjectTypes (ObjectTypeMap &kc) const
 
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...
 
const std::string & getName () const
 Get the name of the planning scene. This is empty by default. More...
 
const std_msgs::ColorRGBA & getObjectColor (const std::string &id) const
 
void getObjectColorMsgs (std::vector< moveit_msgs::ObjectColor > &object_colors) const
 Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene. More...
 
const object_recognition_msgs::ObjectType & getObjectType (const std::string &id) const
 
bool getOctomapMsg (octomap_msgs::OctomapWithPose &octomap) const
 Construct a message (octomap) with the octomap data from the planning_scene. More...
 
const PlanningSceneConstPtr & getParent () const
 Get the parent scene (whith respect to which the diffs are maintained). This may be empty. More...
 
void getPlanningSceneDiffMsg (moveit_msgs::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::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::PlanningScene &scene, const moveit_msgs::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...
 
const robot_model::RobotModelConstPtr & getRobotModel () const
 Get the kinematic model for which the planning scene is maintained. 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...
 
bool hasObjectColor (const std::string &id) const
 
bool hasObjectType (const std::string &id) const
 
bool isPathValid (const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility) More...
 
bool isPathValid (const moveit_msgs::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const moveit_msgs::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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::RobotState &start_state, const moveit_msgs::RobotTrajectory &trajectory, const moveit_msgs::Constraints &path_constraints, const std::vector< moveit_msgs::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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::Constraints &path_constraints, const std::vector< moveit_msgs::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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::Constraints &path_constraints, const moveit_msgs::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=NULL) 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=NULL) const
 Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility) More...
 
bool isStateConstrained (const moveit_msgs::RobotState &state, const moveit_msgs::Constraints &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateConstrained (const robot_state::RobotState &state, const moveit_msgs::Constraints &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateConstrained (const moveit_msgs::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 robot_state::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose=false) const
 Check if a given state satisfies a set of constraints. More...
 
bool isStateFeasible (const moveit_msgs::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 robot_state::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 isStateValid (const moveit_msgs::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 robot_state::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::RobotState &state, const moveit_msgs::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 robot_state::RobotState &state, const moveit_msgs::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 robot_state::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...
 
void loadGeometryFromStream (std::istream &in)
 Load the geometry of the planning scene from a stream. More...
 
void loadGeometryFromStream (std::istream &in, const Eigen::Affine3d &offset)
 Load the geometry of the planning scene from a stream at a certain location using offset. More...
 
 PlanningScene (const robot_model::RobotModelConstPtr &robot_model, collision_detection::WorldPtr world=collision_detection::WorldPtr(new collision_detection::World()))
 construct using an existing RobotModel More...
 
 PlanningScene (const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model, collision_detection::WorldPtr world=collision_detection::WorldPtr(new collision_detection::World()))
 construct using a urdf and srdf. A RobotModel for the PlanningScene will be created using the urdf and srdf. More...
 
void printKnownObjects (std::ostream &out) const
 Outputs debug information about the planning scene contents. More...
 
bool processAttachedCollisionObjectMsg (const moveit_msgs::AttachedCollisionObject &object)
 
bool processCollisionObjectMsg (const moveit_msgs::CollisionObject &object)
 
void processOctomapMsg (const octomap_msgs::OctomapWithPose &map)
 
void processOctomapMsg (const octomap_msgs::Octomap &map)
 
void processOctomapPtr (const std::shared_ptr< const octomap::OcTree > &octree, const Eigen::Affine3d &t)
 
bool processPlanningSceneWorldMsg (const moveit_msgs::PlanningSceneWorld &world)
 
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 removeAllCollisionObjects ()
 Clear all collision objects in planning scene. More...
 
void removeObjectColor (const std::string &id)
 
void removeObjectType (const std::string &id)
 
void saveGeometryToStream (std::ostream &out) const
 Save the geometry of the planning scene to a stream, as plain text. More...
 
void setAttachedBodyUpdateCallback (const robot_state::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...
 
void setCurrentState (const moveit_msgs::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 robot_state::RobotState &state)
 Set the current robot state. 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...
 
void setName (const std::string &name)
 Set the name of the planning scene. More...
 
void setObjectColor (const std::string &id, const std_msgs::ColorRGBA &color)
 
void setObjectType (const std::string &id, const object_recognition_msgs::ObjectType &type)
 
bool setPlanningSceneDiffMsg (const moveit_msgs::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::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...
 
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...
 
bool usePlanningSceneMsg (const moveit_msgs::PlanningScene &scene)
 Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set. More...
 
 ~PlanningScene ()
 
Reasoning about frames
const std::string & getPlanningFrame () const
 Get the frame in which planning is performed. More...
 
const robot_state::TransformsgetTransforms () const
 Get the set of fixed transforms from known frames to the planning frame. More...
 
const robot_state::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...
 
robot_state::TransformsgetTransformsNonConst ()
 Get the set of fixed transforms from known frames to the planning frame. More...
 
const Eigen::Affine3d & 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::Affine3d & 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::Affine3d & getFrameTransform (robot_state::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::Affine3d & getFrameTransform (const robot_state::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 robot_state::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
void addCollisionDetector (const collision_detection::CollisionDetectorAllocatorPtr &allocator)
 Add a new collision detector type. More...
 
void setActiveCollisionDetector (const collision_detection::CollisionDetectorAllocatorPtr &allocator, bool exclusive=false)
 Set the type of collision detector to use. Calls addCollisionDetector() to add it if it has not already been added. More...
 
bool setActiveCollisionDetector (const std::string &collision_detector_name)
 Set the type of collision detector to use. This type must have already been added with addCollisionDetector(). More...
 
const std::string & getActiveCollisionDetectorName () const
 
void getCollisionDetectorNames (std::vector< std::string > &names) const
 get the types of collision detector that have already been added. These are the types which can be passed to setActiveCollisionDetector(). More...
 
const collision_detection::WorldConstPtr & getWorld () const
 Get the representation of the world. More...
 
const collision_detection::WorldPtr & getWorldNonConst ()
 
const collision_detection::CollisionWorldConstPtr & getCollisionWorld () const
 Get the active collision detector for the world. More...
 
const collision_detection::CollisionRobotConstPtr & getCollisionRobot () const
 Get the active collision detector for the robot. More...
 
const collision_detection::CollisionRobotConstPtr & getCollisionRobotUnpadded () const
 Get the active collision detector for the robot. More...
 
const collision_detection::CollisionWorldConstPtr & getCollisionWorld (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::CollisionRobotConstPtr & getCollisionRobot (const std::string &collision_detector_name) const
 Get a specific collision detector for the padded robot. If no found return active CollisionRobot. More...
 
const collision_detection::CollisionRobotConstPtr & getCollisionRobotUnpadded (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::CollisionRobotPtr & getCollisionRobotNonConst ()
 Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot. NOTE: After modifying padding and scale on the active robot call propogateRobotPadding() to copy it to all the other collision detectors. More...
 
void propogateRobotPadding ()
 Copy scale and padding from active CollisionRobot to other CollisionRobots. This should be called after any changes are made to the scale or padding of the active CollisionRobot. This has no effect on the unpadded CollisionRobots. 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 (robot_state::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 robot_state::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::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, robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) is in collision. This variant of the function takes a non-const kstate and calls updateCollisionBodyTransforms() on it. More...
 
void checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) is in collision. The collision transforms of kstate are expected to be up to date. More...
 
void checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) is in collision, with respect to a given allowed collision matrix (acm). This variant of the function takes a non-const kstate and updates its link transforms if needed. More...
 
void checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) 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 robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) 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, robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of kstate if needed. More...
 
void checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) 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 kstate and calls updates the link transforms if needed. More...
 
void checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) 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, robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) is in self collision. More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &kstate) const
 Check whether a specified state (kstate) is in self collision. More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) is in self collision, with respect to a given allowed collision matrix (acm). The link transforms of kstate are updated if needed. More...
 
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Check whether a specified state (kstate) 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, robot_state::RobotState &kstate) const
 Get the names of the links that are involved in collisions for the state kstate. Update the link transforms for kstate if needed. More...
 
void getCollidingLinks (std::vector< std::string > &links, const robot_state::RobotState &kstate) const
 Get the names of the links that are involved in collisions for the state kstate. More...
 
void getCollidingLinks (std::vector< std::string > &links, robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Get the names of the links that are involved in collisions for the state kstate given the allowed collision matrix (acm) More...
 
void getCollidingLinks (std::vector< std::string > &links, const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Get the names of the links that are involved in collisions for the state kstate 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 robot_state::RobotState &kstate) const
 Get the names of the links that are involved in collisions for the state kstate. More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, robot_state::RobotState &kstate) const
 Get the names of the links that are involved in collisions for the state kstate. Update the link transforms for kstate if needed. More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Get the names of the links that are involved in collisions for the state kstate given the allowed collision matrix (acm). Update the link transforms for kstate if needed. More...
 
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 Get the names of the links that are involved in collisions for the state kstate given the allowed collision matrix (acm) More...
 
Distance computation
double distanceToCollision (robot_state::RobotState &kstate) const
 The distance between the robot model at state kstate to the nearest collision (ignoring self-collisions) More...
 
double distanceToCollision (const robot_state::RobotState &kstate) const
 The distance between the robot model at state kstate to the nearest collision (ignoring self-collisions) More...
 
double distanceToCollisionUnpadded (robot_state::RobotState &kstate) const
 The distance between the robot model at state kstate to the nearest collision (ignoring self-collisions), if the robot has no padding. More...
 
double distanceToCollisionUnpadded (const robot_state::RobotState &kstate) const
 The distance between the robot model at state kstate to the nearest collision (ignoring self-collisions), if the robot has no padding. More...
 
double distanceToCollision (robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 The distance between the robot model at state kstate to the nearest collision, ignoring self-collisions and elements that are allowed to collide. More...
 
double distanceToCollision (const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 The distance between the robot model at state kstate to the nearest collision, ignoring self-collisions and elements that are allowed to collide. More...
 
double distanceToCollisionUnpadded (robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 The distance between the robot model at state kstate to the nearest collision, ignoring self-collisions and elements that are allowed to collide, if the robot has no padding. More...
 
double distanceToCollisionUnpadded (const robot_state::RobotState &kstate, const collision_detection::AllowedCollisionMatrix &acm) const
 The distance between the robot model at state kstate 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 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 bool isEmpty (const moveit_msgs::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::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::RobotState &msg)
 Check if a message includes any information about a robot state, or it is just a default, empty message. More...
 

Static Public Attributes

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

Private Types

typedef std::map< std::string, CollisionDetectorPtr >::const_iterator CollisionDetectorConstIterator
 
typedef std::map< std::string, CollisionDetectorPtr >::iterator CollisionDetectorIterator
 

Private Member Functions

void allocateCollisionDetectors ()
 
void allocateCollisionDetectors (CollisionDetector &detector)
 
void initialize ()
 
 MOVEIT_STRUCT_FORWARD (CollisionDetector)
 
 PlanningScene (const PlanningSceneConstPtr &parent)
 

Static Private Member Functions

static robot_model::RobotModelPtr createRobotModel (const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
 

Private Attributes

collision_detection::AllowedCollisionMatrixPtr acm_
 
CollisionDetectorPtr active_collision_
 
std::map< std::string, CollisionDetectorPtr > collision_
 
robot_state::AttachedBodyCallback current_state_attached_body_callback_
 
collision_detection::World::ObserverCallbackFn current_world_object_update_callback_
 
collision_detection::World::ObserverHandle current_world_object_update_observer_handle_
 
robot_state::TransformsPtr ftf_
 
robot_model::RobotModelConstPtr kmodel_
 
robot_state::RobotStatePtr kstate_
 
MotionFeasibilityFn motion_feasibility_
 
std::string name_
 
std::unique_ptr< ObjectColorMapobject_colors_
 
std::unique_ptr< ObjectTypeMapobject_types_
 
PlanningSceneConstPtr parent_
 
StateFeasibilityFn state_feasibility_
 
collision_detection::WorldPtr world_
 
collision_detection::WorldConstPtr world_const_
 
collision_detection::WorldDiffPtr world_diff_
 

Friends

struct CollisionDetector
 

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 87 of file planning_scene.h.

Member Typedef Documentation

typedef std::map<std::string, CollisionDetectorPtr>::const_iterator planning_scene::PlanningScene::CollisionDetectorConstIterator
private

Definition at line 994 of file planning_scene.h.

typedef std::map<std::string, CollisionDetectorPtr>::iterator planning_scene::PlanningScene::CollisionDetectorIterator
private

Definition at line 993 of file planning_scene.h.

Constructor & Destructor Documentation

planning_scene::PlanningScene::PlanningScene ( const robot_model::RobotModelConstPtr &  robot_model,
collision_detection::WorldPtr  world = collision_detection::WorldPtr(new collision_detection::World()) 
)

construct using an existing RobotModel

Definition at line 122 of file planning_scene.cpp.

planning_scene::PlanningScene::PlanningScene ( const urdf::ModelInterfaceSharedPtr &  urdf_model,
const srdf::ModelConstSharedPtr srdf_model,
collision_detection::WorldPtr  world = collision_detection::WorldPtr(new 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 128 of file planning_scene.cpp.

planning_scene::PlanningScene::~PlanningScene ( )

Definition at line 145 of file planning_scene.cpp.

planning_scene::PlanningScene::PlanningScene ( const PlanningSceneConstPtr &  parent)
private

Definition at line 184 of file planning_scene.cpp.

Member Function Documentation

void planning_scene::PlanningScene::addCollisionDetector ( const collision_detection::CollisionDetectorAllocatorPtr &  allocator)

Add a new collision detector type.

A 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 ve used together.

This does nothing if this type of collision detector has already been added.

A new PlanningScene contains an FCL collision detector. This FCL collision detector will always be available unless it is removed by calling setActiveCollisionDetector() with exclusive=true.

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

Definition at line 278 of file planning_scene.cpp.

void planning_scene::PlanningScene::allocateCollisionDetectors ( )
private
void planning_scene::PlanningScene::allocateCollisionDetectors ( CollisionDetector detector)
private
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 516 of file planning_scene.cpp.

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 389 of file planning_scene.h.

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

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

Definition at line 396 of file planning_scene.h.

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

Check whether a specified state (kstate) is in collision. The collision transforms of kstate are expected to be up to date.

Definition at line 525 of file planning_scene.cpp.

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

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

Definition at line 411 of file planning_scene.h.

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

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

Definition at line 548 of file planning_scene.cpp.

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 560 of file planning_scene.cpp.

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 432 of file planning_scene.h.

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

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

Definition at line 440 of file planning_scene.h.

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

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

Definition at line 449 of file planning_scene.h.

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

Check whether a specified state (kstate) 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 kstate and calls updates the link transforms if needed.

Definition at line 459 of file planning_scene.h.

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

Check whether a specified state (kstate) 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 569 of file planning_scene.cpp.

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 539 of file planning_scene.cpp.

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 477 of file planning_scene.h.

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

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

Definition at line 484 of file planning_scene.h.

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

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

Definition at line 492 of file planning_scene.h.

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

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

Definition at line 501 of file planning_scene.h.

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

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

Definition at line 510 of file planning_scene.h.

void planning_scene::PlanningScene::clearDiffs ( )

Clear the diffs accumulated for this planning scene, with respect to the parent. This function is a no-op if there is no parent specified.

Definition at line 413 of file planning_scene.cpp.

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 224 of file planning_scene.cpp.

robot_model::RobotModelPtr planning_scene::PlanningScene::createRobotModel ( const urdf::ModelInterfaceSharedPtr &  urdf_model,
const srdf::ModelConstSharedPtr srdf_model 
)
staticprivate

Definition at line 174 of file planning_scene.cpp.

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 1129 of file planning_scene.cpp.

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 kmodel_, kstate_, ftf_, 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 232 of file planning_scene.cpp.

PlanningScenePtr planning_scene::PlanningScene::diff ( const moveit_msgs::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 237 of file planning_scene.cpp.

double planning_scene::PlanningScene::distanceToCollision ( robot_state::RobotState kstate) const
inline

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

Definition at line 605 of file planning_scene.h.

double planning_scene::PlanningScene::distanceToCollision ( const robot_state::RobotState kstate) const
inline

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

Definition at line 613 of file planning_scene.h.

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

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

Definition at line 635 of file planning_scene.h.

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

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

Definition at line 644 of file planning_scene.h.

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( robot_state::RobotState kstate) const
inline

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

Definition at line 620 of file planning_scene.h.

double planning_scene::PlanningScene::distanceToCollisionUnpadded ( const robot_state::RobotState kstate) const
inline

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

Definition at line 628 of file planning_scene.h.

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

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

Definition at line 652 of file planning_scene.h.

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

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

Definition at line 661 of file planning_scene.h.

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

Definition at line 269 of file planning_scene.h.

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

Get the allowed collision matrix.

Definition at line 336 of file planning_scene.h.

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

Get the allowed collision matrix.

Definition at line 675 of file planning_scene.cpp.

bool planning_scene::PlanningScene::getAttachedCollisionObjectMsg ( moveit_msgs::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 855 of file planning_scene.cpp.

void planning_scene::PlanningScene::getAttachedCollisionObjectMsgs ( std::vector< moveit_msgs::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 871 of file planning_scene.cpp.

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 605 of file planning_scene.cpp.

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 522 of file planning_scene.h.

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

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

Definition at line 529 of file planning_scene.h.

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

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

Definition at line 536 of file planning_scene.h.

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

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

Definition at line 543 of file planning_scene.h.

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

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

Definition at line 613 of file planning_scene.cpp.

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 584 of file planning_scene.cpp.

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 560 of file planning_scene.h.

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
const robot_state::RobotState kstate 
) const
inline

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

Definition at line 566 of file planning_scene.h.

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
robot_state::RobotState kstate 
) const
inline

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

Definition at line 574 of file planning_scene.h.

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
robot_state::RobotState kstate,
const collision_detection::AllowedCollisionMatrix acm 
) const
inline

Get the names of the links that are involved in collisions for the state kstate given the allowed collision matrix (acm). Update the link transforms for kstate if needed.

Definition at line 583 of file planning_scene.h.

void planning_scene::PlanningScene::getCollidingPairs ( collision_detection::CollisionResult::ContactMap contacts,
const robot_state::RobotState kstate,
const collision_detection::AllowedCollisionMatrix acm 
) const

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

Definition at line 592 of file planning_scene.cpp.

void planning_scene::PlanningScene::getCollisionDetectorNames ( std::vector< std::string > &  names) const

get the types of collision detector that have already been added. These are the types which can be passed to setActiveCollisionDetector().

Definition at line 360 of file planning_scene.cpp.

bool planning_scene::PlanningScene::getCollisionObjectMsg ( moveit_msgs::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 813 of file planning_scene.cpp.

void planning_scene::PlanningScene::getCollisionObjectMsgs ( std::vector< moveit_msgs::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 843 of file planning_scene.cpp.

const collision_detection::CollisionRobotConstPtr& planning_scene::PlanningScene::getCollisionRobot ( ) const
inline

Get the active collision detector for the robot.

Definition at line 300 of file planning_scene.h.

const collision_detection::CollisionRobotConstPtr & planning_scene::PlanningScene::getCollisionRobot ( const std::string &  collision_detector_name) const

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

Definition at line 384 of file planning_scene.cpp.

const collision_detection::CollisionRobotPtr & planning_scene::PlanningScene::getCollisionRobotNonConst ( )

Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot. NOTE: After modifying padding and scale on the active robot call propogateRobotPadding() to copy it to all the other collision detectors.

Definition at line 630 of file planning_scene.cpp.

const collision_detection::CollisionRobotConstPtr& planning_scene::PlanningScene::getCollisionRobotUnpadded ( ) const
inline

Get the active collision detector for the robot.

Definition at line 306 of file planning_scene.h.

const collision_detection::CollisionRobotConstPtr & planning_scene::PlanningScene::getCollisionRobotUnpadded ( 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 399 of file planning_scene.cpp.

const collision_detection::CollisionWorldConstPtr& planning_scene::PlanningScene::getCollisionWorld ( ) const
inline

Get the active collision detector for the world.

Definition at line 293 of file planning_scene.h.

const collision_detection::CollisionWorldConstPtr & planning_scene::PlanningScene::getCollisionWorld ( const std::string &  collision_detector_name) const

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

Definition at line 369 of file planning_scene.cpp.

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 2198 of file planning_scene.cpp.

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 2204 of file planning_scene.cpp.

void planning_scene::PlanningScene::getCostSources ( const robot_state::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 2238 of file planning_scene.cpp.

void planning_scene::PlanningScene::getCostSources ( const robot_state::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 2244 of file planning_scene.cpp.

const robot_state::RobotState& planning_scene::PlanningScene::getCurrentState ( ) const
inline

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

Definition at line 148 of file planning_scene.h.

robot_state::RobotState & planning_scene::PlanningScene::getCurrentStateNonConst ( )

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

Definition at line 641 of file planning_scene.cpp.

robot_state::RobotStatePtr planning_scene::PlanningScene::getCurrentStateUpdated ( const moveit_msgs::RobotState &  update) const

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

Definition at line 652 of file planning_scene.cpp.

const Eigen::Affine3d & 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 1803 of file planning_scene.cpp.

const Eigen::Affine3d & 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 1808 of file planning_scene.cpp.

const Eigen::Affine3d& planning_scene::PlanningScene::getFrameTransform ( robot_state::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 203 of file planning_scene.h.

const Eigen::Affine3d & planning_scene::PlanningScene::getFrameTransform ( const robot_state::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 1816 of file planning_scene.cpp.

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

Definition at line 1929 of file planning_scene.cpp.

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

Definition at line 1895 of file planning_scene.cpp.

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 811 of file planning_scene.h.

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

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

Definition at line 105 of file planning_scene.h.

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

Definition at line 1915 of file planning_scene.cpp.

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

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

Definition at line 901 of file planning_scene.cpp.

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

Definition at line 1868 of file planning_scene.cpp.

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

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

Definition at line 879 of file planning_scene.cpp.

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

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

Definition at line 135 of file planning_scene.h.

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

Get the frame in which planning is performed.

Definition at line 165 of file planning_scene.h.

void planning_scene::PlanningScene::getPlanningSceneDiffMsg ( moveit_msgs::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 699 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsg ( moveit_msgs::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 916 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsg ( moveit_msgs::PlanningScene &  scene,
const moveit_msgs::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 937 of file planning_scene.cpp.

const robot_model::RobotModelConstPtr& planning_scene::PlanningScene::getRobotModel ( ) const
inline

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

Definition at line 141 of file planning_scene.h.

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 797 of file planning_scene.h.

const robot_state::Transforms& planning_scene::PlanningScene::getTransforms ( ) const
inline

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

Definition at line 172 of file planning_scene.h.

const robot_state::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 682 of file planning_scene.cpp.

robot_state::Transforms & planning_scene::PlanningScene::getTransformsNonConst ( )

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

Definition at line 688 of file planning_scene.cpp.

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

Get the representation of the world.

Definition at line 279 of file planning_scene.h.

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

Definition at line 286 of file planning_scene.h.

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

Definition at line 1905 of file planning_scene.cpp.

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

Definition at line 1858 of file planning_scene.cpp.

void planning_scene::PlanningScene::initialize ( )
private

Definition at line 151 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::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 99 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::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 117 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isEmpty ( const moveit_msgs::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 105 of file planning_scene.cpp.

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

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

Definition at line 2075 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::RobotState &  start_state,
const moveit_msgs::RobotTrajectory &  trajectory,
const moveit_msgs::Constraints &  path_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = NULL 
) 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 2084 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::RobotState &  start_state,
const moveit_msgs::RobotTrajectory &  trajectory,
const moveit_msgs::Constraints &  path_constraints,
const moveit_msgs::Constraints &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = NULL 
) 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 2093 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isPathValid ( const moveit_msgs::RobotState &  start_state,
const moveit_msgs::RobotTrajectory &  trajectory,
const moveit_msgs::Constraints &  path_constraints,
const std::vector< moveit_msgs::Constraints > &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = NULL 
) 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 2103 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const moveit_msgs::Constraints &  path_constraints,
const std::vector< moveit_msgs::Constraints > &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = NULL 
) 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 2116 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isPathValid ( const robot_trajectory::RobotTrajectory trajectory,
const moveit_msgs::Constraints &  path_constraints,
const moveit_msgs::Constraints &  goal_constraints,
const std::string &  group = "",
bool  verbose = false,
std::vector< std::size_t > *  invalid_index = NULL 
) 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 2173 of file planning_scene.cpp.

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

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

Definition at line 2182 of file planning_scene.cpp.

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

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

Definition at line 2190 of file planning_scene.cpp.

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 1964 of file planning_scene.cpp.

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 358 of file planning_scene.h.

bool planning_scene::PlanningScene::isStateColliding ( robot_state::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 367 of file planning_scene.h.

bool planning_scene::PlanningScene::isStateColliding ( const robot_state::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 1972 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateColliding ( const moveit_msgs::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 1957 of file planning_scene.cpp.

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

Check if a given state satisfies a set of constraints.

Definition at line 2000 of file planning_scene.cpp.

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

Check if a given state satisfies a set of constraints.

Definition at line 2008 of file planning_scene.cpp.

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

Check if a given state satisfies a set of constraints.

Definition at line 2020 of file planning_scene.cpp.

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

Check if a given state satisfies a set of constraints.

Definition at line 2028 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateFeasible ( const moveit_msgs::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 1982 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateFeasible ( const robot_state::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 1993 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateValid ( const moveit_msgs::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 2040 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateValid ( const robot_state::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 2034 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateValid ( const moveit_msgs::RobotState &  state,
const moveit_msgs::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 2046 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateValid ( const robot_state::RobotState state,
const moveit_msgs::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 2054 of file planning_scene.cpp.

bool planning_scene::PlanningScene::isStateValid ( const robot_state::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 2064 of file planning_scene.cpp.

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 1838 of file planning_scene.cpp.

bool planning_scene::PlanningScene::knowsFrameTransform ( const robot_state::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 1843 of file planning_scene.cpp.

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

Load the geometry of the planning scene from a stream.

Definition at line 1036 of file planning_scene.cpp.

void planning_scene::PlanningScene::loadGeometryFromStream ( std::istream &  in,
const Eigen::Affine3d &  offset 
)

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

Definition at line 1041 of file planning_scene.cpp.

planning_scene::PlanningScene::MOVEIT_STRUCT_FORWARD ( CollisionDetector  )
private
void planning_scene::PlanningScene::printKnownObjects ( std::ostream &  out) const

Outputs debug information about the planning scene contents.

Definition at line 2257 of file planning_scene.cpp.

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

Definition at line 1403 of file planning_scene.cpp.

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

Definition at line 1657 of file planning_scene.cpp.

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

Definition at line 1347 of file planning_scene.cpp.

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

Definition at line 1308 of file planning_scene.cpp.

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

Definition at line 1370 of file planning_scene.cpp.

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

Definition at line 1291 of file planning_scene.cpp.

void planning_scene::PlanningScene::propogateRobotPadding ( )

Copy scale and padding from active CollisionRobot to other CollisionRobots. This should be called after any changes are made to the scale or padding of the active CollisionRobot. This has no effect on the unpadded CollisionRobots.

Definition at line 256 of file planning_scene.cpp.

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 457 of file planning_scene.cpp.

void planning_scene::PlanningScene::removeAllCollisionObjects ( )

Clear all collision objects in planning scene.

Definition at line 1335 of file planning_scene.cpp.

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

Definition at line 1951 of file planning_scene.cpp.

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

Definition at line 1889 of file planning_scene.cpp.

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 1004 of file planning_scene.cpp.

void planning_scene::PlanningScene::setActiveCollisionDetector ( const collision_detection::CollisionDetectorAllocatorPtr &  allocator,
bool  exclusive = false 
)

Set the type of collision detector to use. Calls addCollisionDetector() to add it if it has not already been added.

If exclusive is true then all other collision detectors will be removed and only this one will be available.

example: to use FCL collision call planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());

Definition at line 317 of file planning_scene.cpp.

bool planning_scene::PlanningScene::setActiveCollisionDetector ( const std::string &  collision_detector_name)

Set the type of collision detector to use. This type must have already been added with addCollisionDetector().

Returns true on success, false if collision_detector_name is not the name of a collision detector that has been previously added with addCollisionDetector().

Definition at line 342 of file planning_scene.cpp.

void planning_scene::PlanningScene::setAttachedBodyUpdateCallback ( const robot_state::AttachedBodyCallback callback)

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

Definition at line 659 of file planning_scene.cpp.

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 666 of file planning_scene.cpp.

void planning_scene::PlanningScene::setCurrentState ( const moveit_msgs::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 1092 of file planning_scene.cpp.

void planning_scene::PlanningScene::setCurrentState ( const robot_state::RobotState state)

Set the current robot state.

Definition at line 1124 of file planning_scene.cpp.

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 804 of file planning_scene.h.

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

Set the name of the planning scene.

Definition at line 111 of file planning_scene.h.

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

Definition at line 1939 of file planning_scene.cpp.

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

Definition at line 1882 of file planning_scene.cpp.

bool planning_scene::PlanningScene::setPlanningSceneDiffMsg ( const moveit_msgs::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 1199 of file planning_scene.cpp.

bool planning_scene::PlanningScene::setPlanningSceneMsg ( const moveit_msgs::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 1258 of file planning_scene.cpp.

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 790 of file planning_scene.h.

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

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

Definition at line 1300 of file planning_scene.cpp.

Friends And Related Function Documentation

friend struct CollisionDetector
friend

Definition at line 991 of file planning_scene.h.

Member Data Documentation

collision_detection::AllowedCollisionMatrixPtr planning_scene::PlanningScene::acm_
private

Definition at line 1020 of file planning_scene.h.

CollisionDetectorPtr planning_scene::PlanningScene::active_collision_
private

Definition at line 1018 of file planning_scene.h.

std::map<std::string, CollisionDetectorPtr> planning_scene::PlanningScene::collision_
private

Definition at line 1017 of file planning_scene.h.

robot_state::AttachedBodyCallback planning_scene::PlanningScene::current_state_attached_body_callback_
private

Definition at line 1006 of file planning_scene.h.

collision_detection::World::ObserverCallbackFn planning_scene::PlanningScene::current_world_object_update_callback_
private

Definition at line 1014 of file planning_scene.h.

collision_detection::World::ObserverHandle planning_scene::PlanningScene::current_world_object_update_observer_handle_
private

Definition at line 1015 of file planning_scene.h.

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

Definition at line 100 of file planning_scene.h.

robot_state::TransformsPtr planning_scene::PlanningScene::ftf_
private

Definition at line 1009 of file planning_scene.h.

robot_model::RobotModelConstPtr planning_scene::PlanningScene::kmodel_
private

Definition at line 1003 of file planning_scene.h.

robot_state::RobotStatePtr planning_scene::PlanningScene::kstate_
private

Definition at line 1005 of file planning_scene.h.

MotionFeasibilityFn planning_scene::PlanningScene::motion_feasibility_
private

Definition at line 1023 of file planning_scene.h.

std::string planning_scene::PlanningScene::name_
private

Definition at line 999 of file planning_scene.h.

std::unique_ptr<ObjectColorMap> planning_scene::PlanningScene::object_colors_
private

Definition at line 1025 of file planning_scene.h.

std::unique_ptr<ObjectTypeMap> planning_scene::PlanningScene::object_types_
private

Definition at line 1028 of file planning_scene.h.

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

Definition at line 99 of file planning_scene.h.

PlanningSceneConstPtr planning_scene::PlanningScene::parent_
private

Definition at line 1001 of file planning_scene.h.

StateFeasibilityFn planning_scene::PlanningScene::state_feasibility_
private

Definition at line 1022 of file planning_scene.h.

collision_detection::WorldPtr planning_scene::PlanningScene::world_
private

Definition at line 1011 of file planning_scene.h.

collision_detection::WorldConstPtr planning_scene::PlanningScene::world_const_
private

Definition at line 1012 of file planning_scene.h.

collision_detection::WorldDiffPtr planning_scene::PlanningScene::world_diff_
private

Definition at line 1013 of file planning_scene.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:34