moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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>
Public Member Functions | |
PlanningScene (const PlanningScene &)=delete | |
PlanningScene cannot be copy-constructed. | |
PlanningScene & | operator= (const PlanningScene &)=delete |
PlanningScene cannot be copy-assigned. | |
PlanningScene (const moveit::core::RobotModelConstPtr &robot_model, const collision_detection::WorldPtr &world=std::make_shared< collision_detection::World >()) | |
construct using an existing RobotModel | |
PlanningScene (const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model, const collision_detection::WorldPtr &world=std::make_shared< collision_detection::World >()) | |
construct using a urdf and srdf. A RobotModel for the PlanningScene will be created using the urdf and srdf. | |
~PlanningScene () | |
const std::string & | getName () const |
Get the name of the planning scene. This is empty by default. | |
void | setName (const std::string &name) |
Set the name of the planning scene. | |
PlanningScenePtr | diff () const |
Return a new child PlanningScene that uses this one as parent. | |
PlanningScenePtr | diff (const moveit_msgs::msg::PlanningScene &msg) const |
Return a new child PlanningScene that uses this one as parent and has the diffs specified by msg applied. | |
const PlanningSceneConstPtr & | getParent () const |
Get the parent scene (with respect to which the diffs are maintained). This may be empty. | |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
Get the kinematic model for which the planning scene is maintained. | |
const moveit::core::RobotState & | getCurrentState () const |
Get the state at which the robot is assumed to be. | |
moveit::core::RobotState & | getCurrentStateNonConst () |
Get the state at which the robot is assumed to be. | |
moveit::core::RobotStatePtr | getCurrentStateUpdated (const moveit_msgs::msg::RobotState &update) const |
Get a copy of the current state with components overwritten by the state message update. | |
void | saveGeometryToStream (std::ostream &out) const |
Save the geometry of the planning scene to a stream, as plain text. | |
bool | loadGeometryFromStream (std::istream &in) |
Load the geometry of the planning scene from a stream. | |
bool | loadGeometryFromStream (std::istream &in, const Eigen::Isometry3d &offset) |
Load the geometry of the planning scene from a stream at a certain location using offset. | |
void | getPlanningSceneDiffMsg (moveit_msgs::msg::PlanningScene &scene) const |
Fill the message scene with the differences between this instance of PlanningScene with respect to the parent. If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg() | |
void | getPlanningSceneMsg (moveit_msgs::msg::PlanningScene &scene) const |
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed to be exactly the same using setPlanningSceneMsg() | |
void | getPlanningSceneMsg (moveit_msgs::msg::PlanningScene &scene, const moveit_msgs::msg::PlanningSceneComponents &comp) const |
Construct a message (scene) with the data requested in comp. If all options in comp are filled, this will be a complete planning scene message. | |
bool | getCollisionObjectMsg (moveit_msgs::msg::CollisionObject &collision_obj, const std::string &ns) const |
Construct a message (collision_object) with the collision object data from the planning_scene for the requested object. | |
void | getCollisionObjectMsgs (std::vector< moveit_msgs::msg::CollisionObject > &collision_objs) const |
Construct a vector of messages (collision_objects) with the collision object data for all objects in planning_scene. | |
bool | getAttachedCollisionObjectMsg (moveit_msgs::msg::AttachedCollisionObject &attached_collision_obj, const std::string &ns) const |
Construct a message (attached_collision_object) with the attached collision object data from the planning_scene for the requested object. | |
void | getAttachedCollisionObjectMsgs (std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs) const |
Construct a vector of messages (attached_collision_objects) with the attached collision object data for all objects in planning_scene. | |
bool | getOctomapMsg (octomap_msgs::msg::OctomapWithPose &octomap) const |
Construct a message (octomap) with the octomap data from the planning_scene. | |
void | getObjectColorMsgs (std::vector< moveit_msgs::msg::ObjectColor > &object_colors) const |
Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene. | |
bool | setPlanningSceneDiffMsg (const moveit_msgs::msg::PlanningScene &scene) |
Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff (is_diff member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. Data from the message is only appended (and in cases such as e.g., the robot state, is overwritten). | |
bool | setPlanningSceneMsg (const moveit_msgs::msg::PlanningScene &scene) |
Set this instance of a planning scene to be the same as the one serialized in the scene message, even if the message itself is marked as being a diff (is_diff member) | |
bool | usePlanningSceneMsg (const moveit_msgs::msg::PlanningScene &scene) |
Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set. | |
bool | shapesAndPosesFromCollisionObjectMessage (const moveit_msgs::msg::CollisionObject &object, Eigen::Isometry3d &object_pose_in_header_frame, std::vector< shapes::ShapeConstPtr > &shapes, EigenSTL::vector_Isometry3d &shape_poses) |
Takes the object message and returns the object pose, shapes and shape poses. If the object pose is empty (identity) but the shape pose is set, this uses the shape pose as the object pose. The shape pose becomes the identity instead. | |
bool | processCollisionObjectMsg (const moveit_msgs::msg::CollisionObject &object) |
bool | processAttachedCollisionObjectMsg (const moveit_msgs::msg::AttachedCollisionObject &object) |
bool | processPlanningSceneWorldMsg (const moveit_msgs::msg::PlanningSceneWorld &world) |
void | processOctomapMsg (const octomap_msgs::msg::OctomapWithPose &map) |
void | processOctomapMsg (const octomap_msgs::msg::Octomap &map) |
void | processOctomapPtr (const std::shared_ptr< const octomap::OcTree > &octree, const Eigen::Isometry3d &t) |
void | removeAllCollisionObjects () |
Clear all collision objects in planning scene. | |
void | setCurrentState (const moveit_msgs::msg::RobotState &state) |
Set the current robot state to be state. If not all joint values are specified, the previously maintained joint values are kept. | |
void | setCurrentState (const moveit::core::RobotState &state) |
Set the current robot state. | |
void | setAttachedBodyUpdateCallback (const moveit::core::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. | |
bool | hasObjectColor (const std::string &id) const |
const std_msgs::msg::ColorRGBA & | getObjectColor (const std::string &id) const |
Gets the current color of an object. | |
std::optional< std_msgs::msg::ColorRGBA > | getOriginalObjectColor (const std::string &id) const |
Tries to get the original color of an object, if one has been set before. | |
void | setObjectColor (const std::string &id, const std_msgs::msg::ColorRGBA &color) |
void | removeObjectColor (const std::string &id) |
void | getKnownObjectColors (ObjectColorMap &kc) const |
bool | hasObjectType (const std::string &id) const |
const object_recognition_msgs::msg::ObjectType & | getObjectType (const std::string &id) const |
void | setObjectType (const std::string &id, const object_recognition_msgs::msg::ObjectType &type) |
void | removeObjectType (const std::string &id) |
void | getKnownObjectTypes (ObjectTypeMap &kc) const |
void | clearDiffs () |
Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it exists) the parent CollisionDetector (if it exists) This function is a no-op if there is no parent planning scene. | |
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 | 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. | |
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) | |
const StateFeasibilityFn & | getStateFeasibilityPredicate () const |
Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones covered by collision checking and constraint evaluation. | |
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. | |
const MotionFeasibilityFn & | getMotionFeasibilityPredicate () 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. | |
bool | isStateFeasible (const moveit_msgs::msg::RobotState &state, bool verbose=false) const |
Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. | |
bool | isStateFeasible (const moveit::core::RobotState &state, bool verbose=false) const |
Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified. | |
bool | isStateConstrained (const moveit_msgs::msg::RobotState &state, const moveit_msgs::msg::Constraints &constr, bool verbose=false) const |
Check if a given state satisfies a set of constraints. | |
bool | isStateConstrained (const moveit::core::RobotState &state, const moveit_msgs::msg::Constraints &constr, bool verbose=false) const |
Check if a given state satisfies a set of constraints. | |
bool | isStateConstrained (const moveit_msgs::msg::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose=false) const |
Check if a given state satisfies a set of constraints. | |
bool | isStateConstrained (const moveit::core::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, bool verbose=false) const |
Check if a given state satisfies a set of constraints. | |
bool | isStateValid (const moveit_msgs::msg::RobotState &state, const std::string &group="", bool verbose=false) const |
Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent links of group. | |
bool | isStateValid (const moveit::core::RobotState &state, const std::string &group="", bool verbose=false) const |
Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent links of group. | |
bool | isStateValid (const moveit_msgs::msg::RobotState &state, const moveit_msgs::msg::Constraints &constr, const std::string &group="", bool verbose=false) const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group. | |
bool | isStateValid (const moveit::core::RobotState &state, const moveit_msgs::msg::Constraints &constr, const std::string &group="", bool verbose=false) const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group. | |
bool | isStateValid (const moveit::core::RobotState &state, const kinematic_constraints::KinematicConstraintSet &constr, const std::string &group="", bool verbose=false) const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group. | |
bool | isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). Includes descendent links of group. | |
bool | isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group. | |
bool | isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const moveit_msgs::msg::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group. | |
bool | isPathValid (const moveit_msgs::msg::RobotState &start_state, const moveit_msgs::msg::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group. | |
bool | isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group. | |
bool | isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const moveit_msgs::msg::Constraints &goal_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group. | |
bool | isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const moveit_msgs::msg::Constraints &path_constraints, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). Includes descendent links of group. | |
bool | isPathValid (const robot_trajectory::RobotTrajectory &trajectory, const std::string &group="", bool verbose=false, std::vector< std::size_t > *invalid_index=nullptr) const |
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). Includes descendent links of group. | |
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 (plus descendent links). The resulting costs are stored in costs. | |
void | getCostSources (const moveit::core::RobotState &state, std::size_t max_costs, std::set< collision_detection::CostSource > &costs) const |
Get the top max_costs cost sources for a specified state. The resulting costs are stored in costs. | |
void | getCostSources (const moveit::core::RobotState &state, std::size_t max_costs, const std::string &group_name, std::set< collision_detection::CostSource > &costs) const |
Get the top max_costs cost sources for a specified state, but only for group group_name (plus descendent links). The resulting costs are stored in costs. | |
void | printKnownObjects (std::ostream &out=std::cout) const |
Outputs debug information about the planning scene contents. | |
void | allocateCollisionDetector (const collision_detection::CollisionDetectorAllocatorPtr &allocator) |
Allocate a new collision detector and replace the previous one if there was any. | |
Reasoning about frames | |
const std::string & | getPlanningFrame () const |
Get the frame in which planning is performed. | |
const moveit::core::Transforms & | getTransforms () const |
Get the set of fixed transforms from known frames to the planning frame. | |
const moveit::core::Transforms & | 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. | |
moveit::core::Transforms & | getTransformsNonConst () |
Get the set of fixed transforms from known frames to the planning frame. | |
const Eigen::Isometry3d & | getFrameTransform (const std::string &id) const |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. | |
const Eigen::Isometry3d & | getFrameTransform (const std::string &id) |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. Because this function is non-const, the current state transforms are also updated, if needed. | |
const Eigen::Isometry3d & | getFrameTransform (moveit::core::RobotState &state, const std::string &id) const |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. This function also updates the link transforms of state. | |
const Eigen::Isometry3d & | getFrameTransform (const moveit::core::RobotState &state, const std::string &id) const |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. | |
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 moveit::core::RobotState &state, const std::string &id) const |
Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object. | |
Reasoning about the geometry of the planning scene | |
const std::string | getCollisionDetectorName () const |
const collision_detection::WorldConstPtr & | getWorld () const |
Get the representation of the world. | |
const collision_detection::WorldPtr & | getWorldNonConst () |
Get the representation of the world. | |
const collision_detection::CollisionEnvConstPtr & | getCollisionEnv () const |
Get the active collision environment. | |
const collision_detection::CollisionEnvConstPtr & | getCollisionEnvUnpadded () const |
Get the active collision detector for the robot. | |
const collision_detection::CollisionEnvConstPtr & | getCollisionEnv (const std::string &collision_detector_name) const |
Get a specific collision detector for the world. If not found return active CollisionWorld. | |
const collision_detection::CollisionEnvConstPtr & | getCollisionEnvUnpadded (const std::string &collision_detector_name) const |
Get a specific collision detector for the unpadded robot. If no found return active unpadded CollisionRobot. | |
const collision_detection::CollisionEnvPtr & | getCollisionEnvNonConst () |
Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot. | |
const collision_detection::AllowedCollisionMatrix & | getAllowedCollisionMatrix () const |
Get the allowed collision matrix. | |
collision_detection::AllowedCollisionMatrix & | getAllowedCollisionMatrixNonConst () |
Get the allowed collision matrix. | |
void | setAllowedCollisionMatrix (const collision_detection::AllowedCollisionMatrix &acm) |
Set 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 (plus descendent links). 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 (plus descendent links). It is expected the current state transforms are up to date. | |
bool | isStateColliding (moveit::core::RobotState &state, const std::string &group="", bool verbose=false) const |
Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only (plus descendent links). The link transforms for state are updated before the collision check. | |
bool | isStateColliding (const moveit::core::RobotState &state, const std::string &group="", bool verbose=false) const |
Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only (plus descendent links). It is expected that the link transforms of state are up to date. | |
bool | isStateColliding (const moveit_msgs::msg::RobotState &state, const std::string &group="", bool verbose=false) const |
Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only (plus descendent links). | |
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, moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in collision. This variant of the function takes a non-const robot_state and calls updateCollisionBodyTransforms() on it. | |
void | checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in collision. The collision transforms of robot_state are expected to be up to date. | |
void | checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm). This variant of the function takes a non-const robot_state and updates its link transforms if needed. | |
void | checkCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm). | |
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 moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. | |
void | checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of robot_state if needed. | |
void | checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const robot_state and calls updates the link transforms if needed. | |
void | checkCollisionUnpadded (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding. | |
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, moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in self collision. | |
void | checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state) const |
Check whether a specified state (robot_state) is in self collision. | |
void | checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm). The link transforms of robot_state are updated if needed. | |
void | checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm) | |
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, moveit::core::RobotState &robot_state) const |
Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed. | |
void | getCollidingLinks (std::vector< std::string > &links, const moveit::core::RobotState &robot_state) const |
Get the names of the links that are involved in collisions for the state robot_state. | |
void | getCollidingLinks (std::vector< std::string > &links, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm) | |
void | getCollidingLinks (std::vector< std::string > &links, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm) | |
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 moveit::core::RobotState &robot_state, const std::string &group_name="") const |
Get the names of the links that are involved in collisions for the state robot_state. Can be restricted to links part of or updated by group_name (plus descendent links) | |
void | getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, moveit::core::RobotState &robot_state, const std::string &group_name="") const |
Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name (plus descendent links) | |
void | getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm, const std::string &group_name="") const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm). Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name (plus descendent links) | |
void | getCollidingPairs (collision_detection::CollisionResult::ContactMap &contacts, const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm, const std::string &group_name="") const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm). Can be restricted to links part of or updated by group_name (plus descendent links) | |
Distance computation | |
double | distanceToCollision (moveit::core::RobotState &robot_state) const |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions) | |
double | distanceToCollision (const moveit::core::RobotState &robot_state) const |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions) | |
double | distanceToCollisionUnpadded (moveit::core::RobotState &robot_state) const |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding. | |
double | distanceToCollisionUnpadded (const moveit::core::RobotState &robot_state) const |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding. | |
double | distanceToCollision (moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide. | |
double | distanceToCollision (const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide. | |
double | distanceToCollisionUnpadded (moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide, if the robot has no padding. | |
double | distanceToCollisionUnpadded (const moveit::core::RobotState &robot_state, const collision_detection::AllowedCollisionMatrix &acm) const |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that always allowed to collide, if the robot has no padding. | |
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 Public Attributes | |
static const std::string | OCTOMAP_NS = "<octomap>" |
static const std::string | DEFAULT_SCENE_NAME = "(noname)" |
Friends | |
struct | CollisionDetector |
Enumerates the available collision detectors. | |
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 91 of file planning_scene.h.
|
delete |
PlanningScene cannot be copy-constructed.
planning_scene::PlanningScene::PlanningScene | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
const collision_detection::WorldPtr & | world = std::make_shared<collision_detection::World>() |
||
) |
construct using an existing RobotModel
Definition at line 154 of file planning_scene.cpp.
planning_scene::PlanningScene::PlanningScene | ( | const urdf::ModelInterfaceSharedPtr & | urdf_model, |
const srdf::ModelConstSharedPtr & | srdf_model, | ||
const collision_detection::WorldPtr & | world = std::make_shared<collision_detection::World>() |
||
) |
construct using a urdf and srdf. A RobotModel for the PlanningScene will be created using the urdf and srdf.
Definition at line 162 of file planning_scene.cpp.
planning_scene::PlanningScene::~PlanningScene | ( | ) |
Definition at line 182 of file planning_scene.cpp.
|
inline |
Allocate a new collision detector and replace the previous one if there was any.
The collision detector type is specified with (a shared pointer to) an allocator which is a subclass of CollisionDetectorAllocator. This identifies a combination of CollisionWorld/CollisionRobot which can be used together.
A new PlanningScene uses an FCL collision detector by default.
example: to add FCL collision detection (normally not necessary) call planning_scene->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
Definition at line 963 of file planning_scene.h.
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 394 of file planning_scene.cpp.
|
inline |
Check whether the current state is in collision. The current state is expected to be updated.
Definition at line 350 of file planning_scene.h.
void planning_scene::PlanningScene::checkCollision | ( | const collision_detection::CollisionRequest & | req, |
collision_detection::CollisionResult & | res, | ||
const moveit::core::RobotState & | robot_state | ||
) | const |
Check whether a specified state (robot_state) is in collision. The collision transforms of robot_state are expected to be up to date.
Definition at line 407 of file planning_scene.cpp.
void planning_scene::PlanningScene::checkCollision | ( | const collision_detection::CollisionRequest & | req, |
collision_detection::CollisionResult & | res, | ||
const moveit::core::RobotState & | robot_state, | ||
const collision_detection::AllowedCollisionMatrix & | acm | ||
) | const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm).
Definition at line 427 of file planning_scene.cpp.
|
inline |
Check whether a specified state (robot_state) is in collision. This variant of the function takes a non-const robot_state and calls updateCollisionBodyTransforms() on it.
Definition at line 357 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm). This variant of the function takes a non-const robot_state and updates its link transforms if needed.
Definition at line 373 of file planning_scene.h.
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 440 of file planning_scene.cpp.
|
inline |
Check whether the current state is in collision, but use a collision_detection::CollisionRobot instance that has no padding.
Definition at line 395 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding.
Definition at line 403 of file planning_scene.h.
void planning_scene::PlanningScene::checkCollisionUnpadded | ( | const collision_detection::CollisionRequest & | req, |
collision_detection::CollisionResult & | res, | ||
const moveit::core::RobotState & | robot_state, | ||
const collision_detection::AllowedCollisionMatrix & | acm | ||
) | const |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding.
Definition at line 453 of file planning_scene.cpp.
|
inline |
Check whether a specified state (robot_state) is in collision, but use a collision_detection::CollisionRobot instance that has no padding. Update the link transforms of robot_state if needed.
Definition at line 413 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in collision, with respect to a given allowed collision matrix (acm), but use a collision_detection::CollisionRobot instance that has no padding. This variant of the function takes a non-const robot_state and calls updates the link transforms if needed.
Definition at line 424 of file planning_scene.h.
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 414 of file planning_scene.cpp.
|
inline |
Check whether the current state is in self collision.
Definition at line 442 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in self collision.
Definition at line 457 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm)
Definition at line 476 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in self collision.
Definition at line 449 of file planning_scene.h.
|
inline |
Check whether a specified state (robot_state) is in self collision, with respect to a given allowed collision matrix (acm). The link transforms of robot_state are updated if needed.
Definition at line 466 of file planning_scene.h.
void planning_scene::PlanningScene::clearDiffs | ( | ) |
Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it exists) the parent CollisionDetector (if it exists) This function is a no-op if there is no parent planning scene.
Definition at line 316 of file planning_scene.cpp.
|
static |
Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not.
Definition at line 229 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 1161 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 robot_model_, robot_state_, scene_transforms_, and acm_ are not copied. They are shared with the parent. So if changes to these are made in the parent they will be visible in the child. But if any of these is modified (i.e. if the get*NonConst functions are called) in the child then a copy is made and subsequent changes to the corresponding member of the parent will no longer be visible in the child.
Definition at line 237 of file planning_scene.cpp.
PlanningScenePtr planning_scene::PlanningScene::diff | ( | const moveit_msgs::msg::PlanningScene & | msg | ) | const |
Return a new child PlanningScene that uses this one as parent and has the diffs specified by msg applied.
Definition at line 242 of file planning_scene.cpp.
|
inline |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions)
Definition at line 587 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide.
Definition at line 620 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions)
Definition at line 578 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide.
Definition at line 610 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding.
Definition at line 602 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that always allowed to collide, if the robot has no padding.
Definition at line 639 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision (ignoring self-collisions), if the robot has no padding.
Definition at line 594 of file planning_scene.h.
|
inline |
The distance between the robot model at state robot_state to the nearest collision, ignoring self-collisions and elements that are allowed to collide, if the robot has no padding.
Definition at line 629 of file planning_scene.h.
|
inline |
Get the allowed collision matrix.
Definition at line 292 of file planning_scene.h.
collision_detection::AllowedCollisionMatrix & planning_scene::PlanningScene::getAllowedCollisionMatrixNonConst | ( | ) |
Get the allowed collision matrix.
Definition at line 565 of file planning_scene.cpp.
bool planning_scene::PlanningScene::getAttachedCollisionObjectMsg | ( | moveit_msgs::msg::AttachedCollisionObject & | attached_collision_obj, |
const std::string & | ns | ||
) | const |
Construct a message (attached_collision_object) with the attached collision object data from the planning_scene for the requested object.
Definition at line 798 of file planning_scene.cpp.
void planning_scene::PlanningScene::getAttachedCollisionObjectMsgs | ( | std::vector< moveit_msgs::msg::AttachedCollisionObject > & | attached_collision_objs | ) | const |
Construct a vector of messages (attached_collision_objects) with the attached collision object data for all objects in planning_scene.
Definition at line 814 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 495 of file planning_scene.cpp.
|
inline |
Get the names of the links that are involved in collisions for the current state.
Definition at line 488 of file planning_scene.h.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state.
Definition at line 502 of file planning_scene.h.
void planning_scene::PlanningScene::getCollidingLinks | ( | std::vector< std::string > & | links, |
const moveit::core::RobotState & | robot_state, | ||
const collision_detection::AllowedCollisionMatrix & | acm | ||
) | const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm)
Definition at line 507 of file planning_scene.cpp.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed.
Definition at line 495 of file planning_scene.h.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm)
Definition at line 509 of file planning_scene.h.
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 468 of file planning_scene.cpp.
|
inline |
Get the names of the links that are involved in collisions for the current state.
Definition at line 526 of file planning_scene.h.
void planning_scene::PlanningScene::getCollidingPairs | ( | collision_detection::CollisionResult::ContactMap & | contacts, |
const moveit::core::RobotState & | robot_state, | ||
const collision_detection::AllowedCollisionMatrix & | acm, | ||
const std::string & | group_name = "" |
||
) | const |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm). Can be restricted to links part of or updated by group_name (plus descendent links)
Definition at line 480 of file planning_scene.cpp.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state. Can be restricted to links part of or updated by group_name (plus descendent links)
Definition at line 533 of file planning_scene.h.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state given the allowed collision matrix (acm). Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name (plus descendent links)
Definition at line 553 of file planning_scene.h.
|
inline |
Get the names of the links that are involved in collisions for the state robot_state. Update the link transforms for robot_state if needed. Can be restricted to links part of or updated by group_name (plus descendent links)
Definition at line 542 of file planning_scene.h.
|
inline |
|
inline |
Get the active collision environment.
Definition at line 268 of file planning_scene.h.
const collision_detection::CollisionEnvConstPtr & planning_scene::PlanningScene::getCollisionEnv | ( | const std::string & | collision_detector_name | ) | const |
Get a specific collision detector for the world. If not found return active CollisionWorld.
Definition at line 289 of file planning_scene.cpp.
const collision_detection::CollisionEnvPtr & planning_scene::PlanningScene::getCollisionEnvNonConst | ( | ) |
Get the representation of the collision robot This can be used to set padding and link scale on the active collision_robot.
Definition at line 526 of file planning_scene.cpp.
|
inline |
Get the active collision detector for the robot.
Definition at line 274 of file planning_scene.h.
const collision_detection::CollisionEnvConstPtr & planning_scene::PlanningScene::getCollisionEnvUnpadded | ( | const std::string & | collision_detector_name | ) | const |
Get a specific collision detector for the unpadded robot. If no found return active unpadded CollisionRobot.
Definition at line 302 of file planning_scene.cpp.
bool planning_scene::PlanningScene::getCollisionObjectMsg | ( | moveit_msgs::msg::CollisionObject & | collision_obj, |
const std::string & | ns | ||
) | const |
Construct a message (collision_object) with the collision object data from the planning_scene for the requested object.
Definition at line 746 of file planning_scene.cpp.
void planning_scene::PlanningScene::getCollisionObjectMsgs | ( | std::vector< moveit_msgs::msg::CollisionObject > & | collision_objs | ) | const |
Construct a vector of messages (collision_objects) with the collision object data for all objects in planning_scene.
Definition at line 784 of file planning_scene.cpp.
void planning_scene::PlanningScene::getCostSources | ( | const moveit::core::RobotState & | state, |
std::size_t | max_costs, | ||
const std::string & | group_name, | ||
std::set< collision_detection::CostSource > & | costs | ||
) | const |
Get the top max_costs cost sources for a specified state, but only for group group_name (plus descendent links). The resulting costs are stored in costs.
Definition at line 2403 of file planning_scene.cpp.
void planning_scene::PlanningScene::getCostSources | ( | const moveit::core::RobotState & | state, |
std::size_t | max_costs, | ||
std::set< collision_detection::CostSource > & | costs | ||
) | const |
Get the top max_costs cost sources for a specified state. The resulting costs are stored in costs.
Definition at line 2397 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 (plus descendent links). The resulting costs are stored in costs.
Definition at line 2361 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 2355 of file planning_scene.cpp.
|
inline |
Get the state at which the robot is assumed to be.
Definition at line 160 of file planning_scene.h.
moveit::core::RobotState & planning_scene::PlanningScene::getCurrentStateNonConst | ( | ) |
Get the state at which the robot is assumed to be.
Definition at line 531 of file planning_scene.cpp.
moveit::core::RobotStatePtr planning_scene::PlanningScene::getCurrentStateUpdated | ( | const moveit_msgs::msg::RobotState & | update | ) | const |
Get a copy of the current state with components overwritten by the state message update.
Definition at line 542 of file planning_scene.cpp.
const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform | ( | const moveit::core::RobotState & | state, |
const std::string & | id | ||
) | const |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not.
Definition at line 1940 of file planning_scene.cpp.
const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform | ( | const std::string & | id | ) |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not. Because this function is non-const, the current state transforms are also updated, if needed.
Definition at line 1928 of file planning_scene.cpp.
const Eigen::Isometry3d & planning_scene::PlanningScene::getFrameTransform | ( | const std::string & | id | ) | const |
Get the transform corresponding to the frame id. This will be known if id is a link name, an attached body id or a collision object. Return identity when no transform is available. Use knowsFrameTransform() to test if this function will be successful or not.
Definition at line 1923 of file planning_scene.cpp.
|
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 220 of file planning_scene.h.
void planning_scene::PlanningScene::getKnownObjectColors | ( | ObjectColorMap & | kc | ) | const |
void planning_scene::PlanningScene::getKnownObjectTypes | ( | ObjectTypeMap & | kc | ) | const |
Definition at line 2016 of file planning_scene.cpp.
|
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 815 of file planning_scene.h.
|
inline |
Get the name of the planning scene. This is empty by default.
Definition at line 119 of file planning_scene.h.
const std_msgs::msg::ColorRGBA & planning_scene::PlanningScene::getObjectColor | ( | const std::string & | id | ) | const |
Gets the current color of an object.
id | The string id of the target object. |
Definition at line 2040 of file planning_scene.cpp.
void planning_scene::PlanningScene::getObjectColorMsgs | ( | std::vector< moveit_msgs::msg::ObjectColor > & | object_colors | ) | const |
Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene.
Definition at line 843 of file planning_scene.cpp.
const object_recognition_msgs::msg::ObjectType & planning_scene::PlanningScene::getObjectType | ( | const std::string & | id | ) | const |
bool planning_scene::PlanningScene::getOctomapMsg | ( | octomap_msgs::msg::OctomapWithPose & | octomap | ) | const |
Construct a message (octomap) with the octomap data from the planning_scene.
Definition at line 822 of file planning_scene.cpp.
std::optional< std_msgs::msg::ColorRGBA > planning_scene::PlanningScene::getOriginalObjectColor | ( | const std::string & | id | ) | const |
Tries to get the original color of an object, if one has been set before.
id | The string id of the target object. |
Definition at line 2054 of file planning_scene.cpp.
|
inline |
Get the parent scene (with respect to which the diffs are maintained). This may be empty.
Definition at line 147 of file planning_scene.h.
|
inline |
Get the frame in which planning is performed.
Definition at line 177 of file planning_scene.h.
void planning_scene::PlanningScene::getPlanningSceneDiffMsg | ( | moveit_msgs::msg::PlanningScene & | scene | ) | const |
Fill the message scene with the differences between this instance of PlanningScene with respect to the parent. If there is no parent, everything is considered to be a diff and the function behaves like getPlanningSceneMsg()
Definition at line 598 of file planning_scene.cpp.
void planning_scene::PlanningScene::getPlanningSceneMsg | ( | moveit_msgs::msg::PlanningScene & | scene | ) | const |
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed to be exactly the same using setPlanningSceneMsg()
Definition at line 858 of file planning_scene.cpp.
void planning_scene::PlanningScene::getPlanningSceneMsg | ( | moveit_msgs::msg::PlanningScene & | scene, |
const moveit_msgs::msg::PlanningSceneComponents & | comp | ||
) | const |
Construct a message (scene) with the data requested in comp. If all options in comp are filled, this will be a complete planning scene message.
Definition at line 879 of file planning_scene.cpp.
|
inline |
Get the kinematic model for which the planning scene is maintained.
Definition at line 153 of file planning_scene.h.
|
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 801 of file planning_scene.h.
const moveit::core::Transforms & planning_scene::PlanningScene::getTransforms | ( | ) |
Get the set of fixed transforms from known frames to the planning frame. This variant is non-const and also updates the current state.
Definition at line 577 of file planning_scene.cpp.
|
inline |
Get the set of fixed transforms from known frames to the planning frame.
Definition at line 184 of file planning_scene.h.
moveit::core::Transforms & planning_scene::PlanningScene::getTransformsNonConst | ( | ) |
Get the set of fixed transforms from known frames to the planning frame.
Definition at line 584 of file planning_scene.cpp.
|
inline |
Get the representation of the world.
Definition at line 254 of file planning_scene.h.
|
inline |
Get the representation of the world.
Definition at line 261 of file planning_scene.h.
bool planning_scene::PlanningScene::hasObjectColor | ( | const std::string & | id | ) | const |
bool planning_scene::PlanningScene::hasObjectType | ( | const std::string & | id | ) | const |
bool planning_scene::PlanningScene::isPathValid | ( | const moveit_msgs::msg::RobotState & | start_state, |
const moveit_msgs::msg::RobotTrajectory & | trajectory, | ||
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const moveit_msgs::msg::Constraints & | goal_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group.
Definition at line 2246 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const moveit_msgs::msg::RobotState & | start_state, |
const moveit_msgs::msg::RobotTrajectory & | trajectory, | ||
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group.
Definition at line 2237 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const moveit_msgs::msg::RobotState & | start_state, |
const moveit_msgs::msg::RobotTrajectory & | trajectory, | ||
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const std::vector< moveit_msgs::msg::Constraints > & | goal_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group.
Definition at line 2256 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const moveit_msgs::msg::RobotState & | start_state, |
const moveit_msgs::msg::RobotTrajectory & | trajectory, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). Includes descendent links of group.
Definition at line 2228 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const robot_trajectory::RobotTrajectory & | trajectory, |
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const moveit_msgs::msg::Constraints & | goal_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group.
Definition at line 2330 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const robot_trajectory::RobotTrajectory & | trajectory, |
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). Includes descendent links of group.
Definition at line 2339 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isPathValid | ( | const robot_trajectory::RobotTrajectory & | trajectory, |
const moveit_msgs::msg::Constraints & | path_constraints, | ||
const std::vector< moveit_msgs::msg::Constraints > & | goal_constraints, | ||
const std::string & | group = "" , |
||
bool | verbose = false , |
||
std::vector< std::size_t > * | invalid_index = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance, feasibility and constraint satisfaction). It is also checked that the goal constraints are satisfied by the last state on the passed in trajectory. Includes descendent links of group.
Definition at line 2269 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 = nullptr |
||
) | const |
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibility). Includes descendent links of group.
Definition at line 2347 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateColliding | ( | const moveit::core::RobotState & | state, |
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only (plus descendent links). It is expected that the link transforms of state are up to date.
Definition at line 2121 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateColliding | ( | const moveit_msgs::msg::RobotState & | state, |
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is in collision (with the environment or self collision) If a group name is specified, collision checking is done for that group only (plus descendent links).
Definition at line 2101 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 (plus descendent links). Since the function is non-const, the current state transforms are updated before the collision check.
Definition at line 2109 of file planning_scene.cpp.
|
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 (plus descendent links). It is expected the current state transforms are up to date.
Definition at line 319 of file planning_scene.h.
|
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 (plus descendent links). The link transforms for state are updated before the collision check.
Definition at line 328 of file planning_scene.h.
bool planning_scene::PlanningScene::isStateConstrained | ( | const moveit::core::RobotState & | state, |
const kinematic_constraints::KinematicConstraintSet & | constr, | ||
bool | verbose = false |
||
) | const |
Check if a given state satisfies a set of constraints.
Definition at line 2181 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateConstrained | ( | const moveit::core::RobotState & | state, |
const moveit_msgs::msg::Constraints & | constr, | ||
bool | verbose = false |
||
) | const |
Check if a given state satisfies a set of constraints.
Definition at line 2157 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateConstrained | ( | const moveit_msgs::msg::RobotState & | state, |
const kinematic_constraints::KinematicConstraintSet & | constr, | ||
bool | verbose = false |
||
) | const |
Check if a given state satisfies a set of constraints.
Definition at line 2173 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateConstrained | ( | const moveit_msgs::msg::RobotState & | state, |
const moveit_msgs::msg::Constraints & | constr, | ||
bool | verbose = false |
||
) | const |
Check if a given state satisfies a set of constraints.
Definition at line 2149 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateFeasible | ( | const moveit::core::RobotState & | state, |
bool | verbose = false |
||
) | const |
Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified.
Definition at line 2142 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateFeasible | ( | const moveit_msgs::msg::RobotState & | state, |
bool | verbose = false |
||
) | const |
Check if a given state is feasible, in accordance to the feasibility predicate specified by setStateFeasibilityPredicate(). Returns true if no feasibility predicate was specified.
Definition at line 2131 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateValid | ( | const moveit::core::RobotState & | state, |
const kinematic_constraints::KinematicConstraintSet & | constr, | ||
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group.
Definition at line 2217 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateValid | ( | const moveit::core::RobotState & | state, |
const moveit_msgs::msg::Constraints & | constr, | ||
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group.
Definition at line 2207 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateValid | ( | const moveit::core::RobotState & | state, |
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent links of group.
Definition at line 2187 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateValid | ( | const moveit_msgs::msg::RobotState & | state, |
const moveit_msgs::msg::Constraints & | constr, | ||
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is valid. This means checking for collisions, feasibility and whether the user specified validity conditions hold as well. Includes descendent links of group.
Definition at line 2199 of file planning_scene.cpp.
bool planning_scene::PlanningScene::isStateValid | ( | const moveit_msgs::msg::RobotState & | state, |
const std::string & | group = "" , |
||
bool | verbose = false |
||
) | const |
Check if a given state is valid. This means checking for collisions and feasibility. Includes descendent links of group.
Definition at line 2193 of file planning_scene.cpp.
bool planning_scene::PlanningScene::knowsFrameTransform | ( | const moveit::core::RobotState & | state, |
const std::string & | id | ||
) | const |
Check if a transform to the frame id is known. This will be known if id is a link name, an attached body id or a collision object.
Definition at line 1965 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 1960 of file planning_scene.cpp.
bool planning_scene::PlanningScene::loadGeometryFromStream | ( | std::istream & | in | ) |
Load the geometry of the planning scene from a stream.
Definition at line 993 of file planning_scene.cpp.
bool planning_scene::PlanningScene::loadGeometryFromStream | ( | std::istream & | in, |
const Eigen::Isometry3d & | offset | ||
) |
Load the geometry of the planning scene from a stream at a certain location using offset.
Definition at line 998 of file planning_scene.cpp.
|
delete |
PlanningScene cannot be copy-assigned.
void planning_scene::PlanningScene::printKnownObjects | ( | std::ostream & | out = std::cout | ) | const |
Outputs debug information about the planning scene contents.
Definition at line 2416 of file planning_scene.cpp.
bool planning_scene::PlanningScene::processAttachedCollisionObjectMsg | ( | const moveit_msgs::msg::AttachedCollisionObject & | object | ) |
Definition at line 1441 of file planning_scene.cpp.
bool planning_scene::PlanningScene::processCollisionObjectMsg | ( | const moveit_msgs::msg::CollisionObject & | object | ) |
void planning_scene::PlanningScene::processOctomapMsg | ( | const octomap_msgs::msg::Octomap & | map | ) |
void planning_scene::PlanningScene::processOctomapMsg | ( | const octomap_msgs::msg::OctomapWithPose & | map | ) |
Definition at line 1383 of file planning_scene.cpp.
void planning_scene::PlanningScene::processOctomapPtr | ( | const std::shared_ptr< const octomap::OcTree > & | octree, |
const Eigen::Isometry3d & | t | ||
) |
Definition at line 1406 of file planning_scene.cpp.
bool planning_scene::PlanningScene::processPlanningSceneWorldMsg | ( | const moveit_msgs::msg::PlanningSceneWorld & | world | ) |
Definition at line 1302 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 338 of file planning_scene.cpp.
void planning_scene::PlanningScene::removeAllCollisionObjects | ( | ) |
Clear all collision objects in planning scene.
Definition at line 1369 of file planning_scene.cpp.
void planning_scene::PlanningScene::removeObjectColor | ( | const std::string & | id | ) |
void planning_scene::PlanningScene::removeObjectType | ( | const std::string & | id | ) |
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 949 of file planning_scene.cpp.
void planning_scene::PlanningScene::setAllowedCollisionMatrix | ( | const collision_detection::AllowedCollisionMatrix & | acm | ) |
Set the allowed collision matrix.
Definition at line 572 of file planning_scene.cpp.
void planning_scene::PlanningScene::setAttachedBodyUpdateCallback | ( | const moveit::core::AttachedBodyCallback & | callback | ) |
Set the callback to be triggered when changes are made to the current scene state.
Definition at line 549 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 556 of file planning_scene.cpp.
void planning_scene::PlanningScene::setCurrentState | ( | const moveit::core::RobotState & | state | ) |
Set the current robot state.
Definition at line 1156 of file planning_scene.cpp.
void planning_scene::PlanningScene::setCurrentState | ( | const moveit_msgs::msg::RobotState & | state | ) |
Set the current robot state to be state. If not all joint values are specified, the previously maintained joint values are kept.
Definition at line 1123 of file planning_scene.cpp.
|
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 808 of file planning_scene.h.
|
inline |
Set the name of the planning scene.
Definition at line 125 of file planning_scene.h.
void planning_scene::PlanningScene::setObjectColor | ( | const std::string & | id, |
const std_msgs::msg::ColorRGBA & | color | ||
) |
Definition at line 2077 of file planning_scene.cpp.
void planning_scene::PlanningScene::setObjectType | ( | const std::string & | id, |
const object_recognition_msgs::msg::ObjectType & | type | ||
) |
bool planning_scene::PlanningScene::setPlanningSceneDiffMsg | ( | const moveit_msgs::msg::PlanningScene & | scene | ) |
Apply changes to this planning scene as diffs, even if the message itself is not marked as being a diff (is_diff member). A parent is not required to exist. However, the existing data in the planning instance is not cleared. Data from the message is only appended (and in cases such as e.g., the robot state, is overwritten).
Definition at line 1220 of file planning_scene.cpp.
bool planning_scene::PlanningScene::setPlanningSceneMsg | ( | const moveit_msgs::msg::PlanningScene & | scene | ) |
Set this instance of a planning scene to be the same as the one serialized in the scene message, even if the message itself is marked as being a diff (is_diff member)
Definition at line 1273 of file planning_scene.cpp.
|
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 794 of file planning_scene.h.
bool planning_scene::PlanningScene::shapesAndPosesFromCollisionObjectMessage | ( | const moveit_msgs::msg::CollisionObject & | object, |
Eigen::Isometry3d & | object_pose_in_header_frame, | ||
std::vector< shapes::ShapeConstPtr > & | shapes, | ||
EigenSTL::vector_Isometry3d & | shape_poses | ||
) |
Takes the object message and returns the object pose, shapes and shape poses. If the object pose is empty (identity) but the shape pose is set, this uses the shape pose as the object pose. The shape pose becomes the identity instead.
Definition at line 1705 of file planning_scene.cpp.
bool planning_scene::PlanningScene::usePlanningSceneMsg | ( | const moveit_msgs::msg::PlanningScene & | scene | ) |
Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the message is set.
Definition at line 1311 of file planning_scene.cpp.
|
friend |
Enumerates the available collision detectors.
Definition at line 1007 of file planning_scene.h.
|
static |
Definition at line 114 of file planning_scene.h.
|
static |
Definition at line 113 of file planning_scene.h.