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

List of all members.

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.
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.
PlanningScenePtr diff () const
 Return a new child PlanningScene that uses this one as parent.
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.
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.
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.
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.
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.
const robot_state::RobotStategetCurrentState () const
 Get the state at which the robot is assumed to be.
robot_state::RobotStategetCurrentStateNonConst ()
 Get the state at which the robot is assumed to be.
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.
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.
const std::string & getName () const
 Get the name of the planning scene. This is empty by default.
const std_msgs::ColorRGBA & getObjectColor (const std::string &id) const
const
object_recognition_msgs::ObjectType & 
getObjectType (const std::string &id) const
const PlanningSceneConstPtr & getParent () const
 Get the parent scene (whith respect to which the diffs are maintained). This may be empty.
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()
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()
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.
const
robot_model::RobotModelConstPtr & 
getRobotModel () const
 Get the kinematic model for which the planning scene is maintained.
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.
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)
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.
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.
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.
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.
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.
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).
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)
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
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.
void loadGeometryFromStream (std::istream &in)
 Load the geometry of the planning scene from a stream.
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.
 PlanningScene (const robot_model::RobotModelConstPtr &robot_model, collision_detection::WorldPtr world=collision_detection::WorldPtr(new collision_detection::World()))
 construct using an existing RobotModel
 PlanningScene (const boost::shared_ptr< const urdf::ModelInterface > &urdf_model, const boost::shared_ptr< const srdf::Model > &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.
void printKnownObjects (std::ostream &out) const
 Outputs debug information about the planning scene contents.
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 boost::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.
void removeAllCollisionObjects ()
 Clear all collision objects in planning scene.
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.
void setAttachedBodyUpdateCallback (const robot_state::AttachedBodyCallback &callback)
 Set the callback to be triggered when changes are made to the current scene state.
void setCollisionObjectUpdateCallback (const collision_detection::World::ObserverCallbackFn &callback)
 Set the callback to be triggered when changes are made to the current scene world.
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.
void setCurrentState (const robot_state::RobotState &state)
 Set the current robot state.
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.
void setName (const std::string &name)
 Set the name of the planning scene.
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).
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)
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)
bool usePlanningSceneMsg (const moveit_msgs::PlanningScene &scene)
 Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set.
 ~PlanningScene ()
Reasoning about frames
const std::string & getPlanningFrame () const
 Get the frame in which planning is performed.
const robot_state::TransformsgetTransforms () const
 Get the set of fixed transforms from known frames to the planning frame.
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.
robot_state::TransformsgetTransformsNonConst ()
 Get the set of fixed transforms from known frames to the planning frame.
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.
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.
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.
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.
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.
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.
Reasoning about the geometry of the planning scene
void addCollisionDetector (const collision_detection::CollisionDetectorAllocatorPtr &allocator)
 Add a new collision detector type.
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.
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().
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().
const
collision_detection::WorldConstPtr & 
getWorld () const
 Get the representation of the world.
const
collision_detection::WorldPtr & 
getWorldNonConst ()
const
collision_detection::CollisionWorldConstPtr & 
getCollisionWorld () const
 Get the active collision detector for the world.
const
collision_detection::CollisionRobotConstPtr & 
getCollisionRobot () const
 Get the active collision detector for the robot.
const
collision_detection::CollisionRobotConstPtr & 
getCollisionRobotUnpadded () const
 Get the active collision detector for the robot.
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.
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.
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.
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.
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.
const
collision_detection::AllowedCollisionMatrix
getAllowedCollisionMatrix () const
 Get the allowed collision matrix.
collision_detection::AllowedCollisionMatrixgetAllowedCollisionMatrixNonConst ()
 Get the allowed collision matrix.
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.
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.
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.
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.
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.
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.
void checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
 Check whether the current state is in collision. The current state is expected to be updated.
void 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.
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.
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.
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).
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.
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.
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.
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.
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.
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.
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
 Check whether the current state is in self collision.
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res) const
 Check whether the current state is in self collision.
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.
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.
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.
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)
void getCollidingLinks (std::vector< std::string > &links)
 Get the names of the links that are involved in collisions for the current state.
void getCollidingLinks (std::vector< std::string > &links) const
 Get the names of the links that are involved in collisions for the current state.
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.
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.
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)
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)
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.
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts) const
 Get the names of the links that are involved in collisions for the current state.
void getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, const robot_state::RobotState &kstate) const
 Get the names of the links that are involved in collisions for the state kstate.
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.
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.
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)
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)
double distanceToCollision (const robot_state::RobotState &kstate) const
 The distance between the robot model at state kstate to the nearest collision (ignoring self-collisions)
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.
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.
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.
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.
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.
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.

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.
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.
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.
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.

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 getPlanningSceneMsgCollisionObject (moveit_msgs::PlanningScene &scene, const std::string &ns) const
void getPlanningSceneMsgCollisionObjects (moveit_msgs::PlanningScene &scene) const
void getPlanningSceneMsgObjectColors (moveit_msgs::PlanningScene &scene_msg) const
void getPlanningSceneMsgOctomap (moveit_msgs::PlanningScene &scene) const
void initialize ()
 MOVEIT_CLASS_FORWARD (CollisionDetector)
 PlanningScene (const PlanningSceneConstPtr &parent)

Static Private Member Functions

static robot_model::RobotModelPtr createRobotModel (const boost::shared_ptr< const urdf::ModelInterface > &urdf_model, const boost::shared_ptr< const srdf::Model > &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_
boost::scoped_ptr< ObjectColorMapobject_colors_
boost::scoped_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 977 of file planning_scene.h.

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

Definition at line 976 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 121 of file planning_scene.cpp.

planning_scene::PlanningScene::PlanningScene ( const boost::shared_ptr< const urdf::ModelInterface > &  urdf_model,
const boost::shared_ptr< const srdf::Model > &  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.

Definition at line 146 of file planning_scene.cpp.

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

Definition at line 186 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 282 of file planning_scene.cpp.

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.

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

Definition at line 390 of file planning_scene.h.

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

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.

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

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.

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

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

Definition at line 433 of file planning_scene.h.

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

Definition at line 441 of file planning_scene.h.

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

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

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

Check whether the current state is in self collision.

Definition at line 539 of file planning_scene.cpp.

Check whether the current state is in self collision.

Definition at line 478 of file planning_scene.h.

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

Definition at line 485 of file planning_scene.h.

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

Definition at line 493 of file planning_scene.h.

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

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

Definition at line 511 of file planning_scene.h.

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

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

robot_model::RobotModelPtr planning_scene::PlanningScene::createRobotModel ( const boost::shared_ptr< const urdf::ModelInterface > &  urdf_model,
const boost::shared_ptr< const srdf::Model > &  srdf_model 
) [static, private]

Definition at line 176 of file planning_scene.cpp.

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

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

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

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

Definition at line 606 of file planning_scene.h.

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

Definition at line 614 of file planning_scene.h.

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

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

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

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

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

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

Definition at line 270 of file planning_scene.h.

Get the allowed collision matrix.

Definition at line 337 of file planning_scene.h.

Get the allowed collision matrix.

Definition at line 679 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 606 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 523 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 530 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 537 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 544 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 614 of file planning_scene.cpp.

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

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

Definition at line 561 of file planning_scene.h.

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

Definition at line 567 of file planning_scene.h.

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

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

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

Definition at line 593 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 364 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 301 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 387 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 632 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 307 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 401 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 294 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 373 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 2162 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 2170 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 2205 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 2211 of file planning_scene.cpp.

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

Definition at line 149 of file planning_scene.h.

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

Definition at line 643 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 655 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 1756 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 1761 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 204 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 1769 of file planning_scene.cpp.

Definition at line 1882 of file planning_scene.cpp.

Definition at line 1848 of file planning_scene.cpp.

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

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

Definition at line 1868 of file planning_scene.cpp.

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

Definition at line 1820 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 136 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 166 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 703 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 875 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 911 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsgCollisionObject ( moveit_msgs::PlanningScene &  scene,
const std::string &  ns 
) const [private]

Definition at line 814 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsgCollisionObjects ( moveit_msgs::PlanningScene &  scene) const [private]

Definition at line 846 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsgObjectColors ( moveit_msgs::PlanningScene &  scene_msg) const [private]

Definition at line 896 of file planning_scene.cpp.

void planning_scene::PlanningScene::getPlanningSceneMsgOctomap ( moveit_msgs::PlanningScene &  scene) const [private]

Definition at line 855 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 142 of file planning_scene.h.

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

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

Definition at line 173 of file planning_scene.h.

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

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

Definition at line 692 of file planning_scene.cpp.

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

Get the representation of the world.

Definition at line 280 of file planning_scene.h.

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

Definition at line 287 of file planning_scene.h.

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

Definition at line 1858 of file planning_scene.cpp.

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

Definition at line 1810 of file planning_scene.cpp.

Definition at line 152 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 98 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 116 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 104 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 2031 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 2041 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 2051 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 2062 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 2076 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 2134 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 2144 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 2153 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 1913 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 359 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 368 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 1921 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 1905 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 1950 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 1958 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 1970 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 1979 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 1932 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 1943 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 1993 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 1986 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 2000 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 2009 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 2020 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 1790 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 1795 of file planning_scene.cpp.

Load the geometry of the planning scene from a stream.

Definition at line 1010 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 1015 of file planning_scene.cpp.

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

Outputs debug information about the planning scene contents.

Definition at line 2224 of file planning_scene.cpp.

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

Definition at line 1376 of file planning_scene.cpp.

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

Definition at line 1620 of file planning_scene.cpp.

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

Definition at line 1320 of file planning_scene.cpp.

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

Definition at line 1286 of file planning_scene.cpp.

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

Definition at line 1342 of file planning_scene.cpp.

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

Definition at line 1269 of file planning_scene.cpp.

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

Clear all collision objects in planning scene.

Definition at line 1312 of file planning_scene.cpp.

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

Definition at line 1899 of file planning_scene.cpp.

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

Definition at line 1842 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 978 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 322 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 347 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 662 of file planning_scene.cpp.

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

Definition at line 669 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 1066 of file planning_scene.cpp.

Set the current robot state.

Definition at line 1098 of file planning_scene.cpp.

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

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

Definition at line 1892 of file planning_scene.cpp.

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

Definition at line 1834 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 1173 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 1236 of file planning_scene.cpp.

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


Friends And Related Function Documentation

friend struct CollisionDetector [friend]

Definition at line 974 of file planning_scene.h.


Member Data Documentation

collision_detection::AllowedCollisionMatrixPtr planning_scene::PlanningScene::acm_ [private]

Definition at line 1003 of file planning_scene.h.

CollisionDetectorPtr planning_scene::PlanningScene::active_collision_ [private]

Definition at line 1001 of file planning_scene.h.

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

Definition at line 1000 of file planning_scene.h.

robot_state::AttachedBodyCallback planning_scene::PlanningScene::current_state_attached_body_callback_ [private]

Definition at line 989 of file planning_scene.h.

Definition at line 997 of file planning_scene.h.

Definition at line 998 of file planning_scene.h.

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

Definition at line 101 of file planning_scene.h.

robot_state::TransformsPtr planning_scene::PlanningScene::ftf_ [private]

Definition at line 992 of file planning_scene.h.

robot_model::RobotModelConstPtr planning_scene::PlanningScene::kmodel_ [private]

Definition at line 986 of file planning_scene.h.

robot_state::RobotStatePtr planning_scene::PlanningScene::kstate_ [private]

Definition at line 988 of file planning_scene.h.

Definition at line 1006 of file planning_scene.h.

std::string planning_scene::PlanningScene::name_ [private]

Definition at line 982 of file planning_scene.h.

Definition at line 1008 of file planning_scene.h.

Definition at line 1011 of file planning_scene.h.

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

Definition at line 100 of file planning_scene.h.

PlanningSceneConstPtr planning_scene::PlanningScene::parent_ [private]

Definition at line 984 of file planning_scene.h.

Definition at line 1005 of file planning_scene.h.

collision_detection::WorldPtr planning_scene::PlanningScene::world_ [private]

Definition at line 994 of file planning_scene.h.

collision_detection::WorldConstPtr planning_scene::PlanningScene::world_const_ [private]

Definition at line 995 of file planning_scene.h.

collision_detection::WorldDiffPtr planning_scene::PlanningScene::world_diff_ [private]

Definition at line 996 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 Mon Jul 24 2017 02:20:45