Go to the documentation of this file.
49 #include <moveit_msgs/PlanningScene.h>
50 #include <moveit_msgs/RobotTrajectory.h>
51 #include <moveit_msgs/Constraints.h>
52 #include <moveit_msgs/PlanningSceneComponents.h>
53 #include <octomap_msgs/OctomapWithPose.h>
54 #include <boost/noncopyable.hpp>
55 #include <boost/function.hpp>
56 #include <boost/concept_check.hpp>
60 #include <moveit/moveit_planning_scene_export.h>
162 using ObjectColorMap = std::map<std::string, std_msgs::ColorRGBA>;
165 using ObjectTypeMap = std::map<std::string, object_recognition_msgs::ObjectType>;
170 class PlanningScene :
private boost::noncopyable,
public std::enable_shared_from_this<PlanningScene>
175 const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
180 const collision_detection::WorldPtr& world = std::make_shared<collision_detection::World>());
182 static MOVEIT_PLANNING_SCENE_EXPORT
const std::string
OCTOMAP_NS;
188 const std::string&
getName()
const
209 PlanningScenePtr
diff()
const;
213 PlanningScenePtr
diff(
const moveit_msgs::PlanningScene& msg)
const;
216 const PlanningSceneConstPtr&
getParent()
const
222 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
345 bool exclusive =
false);
365 const collision_detection::WorldConstPtr&
getWorld()
const
379 const collision_detection::CollisionEnvConstPtr&
getCollisionEnv()
const
391 const collision_detection::CollisionEnvConstPtr&
getCollisionEnv(
const std::string& collision_detector_name)
const;
395 const collision_detection::CollisionEnvConstPtr&
432 bool isStateColliding(
const std::string& group =
"",
bool verbose =
false)
const
451 bool verbose =
false)
const;
455 bool isStateColliding(
const moveit_msgs::RobotState& state,
const std::string& group =
"",
bool verbose =
false)
const;
667 const std::string& group_name =
"")
const
678 const std::string& group_name =
"")
const;
784 void getPlanningSceneMsg(moveit_msgs::PlanningScene& scene,
const moveit_msgs::PlanningSceneComponents& comp)
const;
788 bool getCollisionObjectMsg(moveit_msgs::CollisionObject& collision_obj,
const std::string& ns)
const;
797 const std::string& ns)
const;
829 Eigen::Isometry3d& object_pose_in_header_frame,
830 std::vector<shapes::ShapeConstPtr>&
shapes,
840 void processOctomapPtr(
const std::shared_ptr<const octomap::OcTree>& octree,
const Eigen::Isometry3d& t);
863 const std_msgs::ColorRGBA&
getObjectColor(
const std::string&
id)
const;
864 void setObjectColor(
const std::string&
id,
const std_msgs::ColorRGBA& color);
870 const object_recognition_msgs::ObjectType&
getObjectType(
const std::string&
id)
const;
871 void setObjectType(
const std::string&
id,
const object_recognition_msgs::ObjectType& type);
884 void pushDiffs(
const PlanningScenePtr& scene);
922 bool isStateFeasible(
const moveit_msgs::RobotState& state,
bool verbose =
false)
const;
929 bool isStateConstrained(
const moveit_msgs::RobotState& state,
const moveit_msgs::Constraints& constr,
930 bool verbose =
false)
const;
934 bool verbose =
false)
const;
945 bool isStateValid(
const moveit_msgs::RobotState& state,
const std::string& group =
"",
bool verbose =
false)
const;
952 bool isStateValid(
const moveit_msgs::RobotState& state,
const moveit_msgs::Constraints& constr,
953 const std::string& group =
"",
bool verbose =
false)
const;
958 const std::string& group =
"",
bool verbose =
false)
const;
963 const std::string& group =
"",
bool verbose =
false)
const;
966 bool isPathValid(
const moveit_msgs::RobotState& start_state,
const moveit_msgs::RobotTrajectory& trajectory,
967 const std::string& group =
"",
bool verbose =
false,
968 std::vector<std::size_t>* invalid_index =
nullptr)
const;
973 bool isPathValid(
const moveit_msgs::RobotState& start_state,
const moveit_msgs::RobotTrajectory& trajectory,
974 const moveit_msgs::Constraints& path_constraints,
const std::string& group =
"",
975 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
980 bool isPathValid(
const moveit_msgs::RobotState& start_state,
const moveit_msgs::RobotTrajectory& trajectory,
981 const moveit_msgs::Constraints& path_constraints,
const moveit_msgs::Constraints& goal_constraints,
982 const std::string& group =
"",
bool verbose =
false,
983 std::vector<std::size_t>* invalid_index =
nullptr)
const;
988 bool isPathValid(
const moveit_msgs::RobotState& start_state,
const moveit_msgs::RobotTrajectory& trajectory,
989 const moveit_msgs::Constraints& path_constraints,
990 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group =
"",
991 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
997 const moveit_msgs::Constraints& path_constraints,
998 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group =
"",
999 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
1005 const moveit_msgs::Constraints& path_constraints,
const moveit_msgs::Constraints& goal_constraints,
1006 const std::string& group =
"",
bool verbose =
false,
1007 std::vector<std::size_t>* invalid_index =
nullptr)
const;
1012 const moveit_msgs::Constraints& path_constraints,
const std::string& group =
"",
1013 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
1017 bool verbose =
false, std::vector<std::size_t>* invalid_index =
nullptr)
const;
1022 std::set<collision_detection::CostSource>& costs,
double overlap_fraction = 0.9)
const;
1027 const std::string& group_name, std::set<collision_detection::CostSource>& costs,
1028 double overlap_fraction = 0.9)
const;
1032 std::set<collision_detection::CostSource>& costs)
const;
1037 std::set<collision_detection::CostSource>& costs)
const;
1044 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool isEmpty(
const moveit_msgs::PlanningScene& msg);
1048 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool
1049 isEmpty(
const moveit_msgs::PlanningSceneWorld& msg);
1052 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
static bool isEmpty(
const moveit_msgs::RobotState& msg);
1055 static PlanningScenePtr
clone(
const PlanningSceneConstPtr& scene);
1066 static moveit::core::RobotModelPtr
createRobotModel(
const urdf::ModelInterfaceSharedPtr& urdf_model,
1076 void writePoseToText(std::ostream& out,
const Eigen::Isometry3d& pose)
const;
1079 static void poseMsgToEigen(
const geometry_msgs::Pose& msg, Eigen::Isometry3d& out);
1086 collision_detection::CollisionDetectorAllocatorPtr
alloc_;
1087 collision_detection::CollisionEnvPtr
cenv_;
1088 collision_detection::CollisionEnvConstPtr
cenv_const_;
1093 CollisionDetectorConstPtr
parent_;
1095 const collision_detection::CollisionEnvConstPtr&
getCollisionEnv()
const
1129 collision_detection::WorldPtr
world_;
1135 std::map<std::string, CollisionDetectorPtr>
collision_;
1138 collision_detection::AllowedCollisionMatrixPtr
acm_;
collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrixNonConst()
Get the allowed collision matrix.
const moveit::core::RobotState & getCurrentState() const
Get the state at which the robot is assumed to be.
Core components of MoveIt.
const MotionFeasibilityFn & getMotionFeasibilityPredicate() const
Get the predicate that decides whether motion segments are considered valid or invalid for reasons be...
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,...
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
void setMotionFeasibilityPredicate(const MotionFeasibilityFn &fn)
Specify a predicate that decides whether motion segments are considered valid or invalid for reasons ...
void printKnownObjects(std::ostream &out=std::cout) const
Outputs debug information about the planning scene contents.
collision_detection::WorldDiffPtr world_diff_
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
double distanceToCollision(moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
PlanningScene(const moveit::core::RobotModelConstPtr &robot_model, const collision_detection::WorldPtr &world=std::make_shared< collision_detection::World >())
construct using an existing RobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
void getObjectColorMsgs(std::vector< moveit_msgs::ObjectColor > &object_colors) const
Construct a vector of messages (object_colors) with the colors of the objects from the planning_scene...
const collision_detection::WorldConstPtr & getWorld() const
Get the representation of the world.
bool hasObjectColor(const std::string &id) const
collision_detection::World::ObserverCallbackFn current_world_object_update_callback_
void getCollisionObjectMsgs(std::vector< moveit_msgs::CollisionObject > &collision_objs) const
Construct a vector of messages (collision_objects) with the collision object data for all objects in ...
bool processAttachedCollisionObjectMsg(const moveit_msgs::AttachedCollisionObject &object)
void pushDiffs(const PlanningScenePtr &scene)
If there is a parent specified for this scene, then the diffs with respect to that parent are applied...
MOVEIT_STRUCT_FORWARD(CollisionDetector)
const moveit::core::Transforms & getTransforms() const
Get the set of fixed transforms from known frames to the planning frame.
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.
const collision_detection::AllowedCollisionMatrix & getAllowedCollisionMatrix() const
Get the allowed collision matrix.
const object_recognition_msgs::ObjectType & getObjectType(const std::string &id) const
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 cost...
void copyPadding(const CollisionDetector &src)
boost::function< bool(const moveit::core::RobotState &, const moveit::core::RobotState &, bool)> MotionFeasibilityFn
This is the function signature for additional feasibility checks to be imposed on motions segments be...
void writePoseToText(std::ostream &out, const Eigen::Isometry3d &pose) const
PlanningSceneConstPtr parent_
void decoupleParent()
Make sure that all the data maintained in this scene is local. All unmodified data is copied from the...
void setCurrentState(const moveit_msgs::RobotState &state)
Set the current robot state to be state. If not all joint values are specified, the previously mainta...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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 pa...
const std_msgs::ColorRGBA & getObjectColor(const std::string &id) const
moveit::core::RobotStatePtr getCurrentStateUpdated(const moveit_msgs::RobotState &update) const
Get a copy of the current state with components overwritten by the state message update.
void getCollidingPairs(collision_detection::CollisionResult::ContactMap &contacts) const
Get the names of the links that are involved in collisions for the current state.
CollisionDetectorPtr active_collision_
Maintain a sequence of waypoints and the time durations between these waypoints.
void propogateRobotPadding()
Copy scale and padding from active CollisionRobot to other CollisionRobots. This should be called aft...
std::map< std::string, object_recognition_msgs::ObjectType > ObjectTypeMap
A map from object names (e.g., attached bodies, collision objects) to their types.
void processOctomapPtr(const std::shared_ptr< const octomap::OcTree > &octree, const Eigen::Isometry3d &t)
Representation of a collision checking request.
moveit::core::RobotState & getCurrentStateNonConst()
Get the state at which the robot is assumed to be.
bool getCollisionObjectMsg(moveit_msgs::CollisionObject &collision_obj, const std::string &ns) const
Construct a message (collision_object) with the collision object data from the planning_scene for the...
void clearDiffs()
Clear the diffs accumulated for this planning scene, with respect to: the parent PlanningScene (if it...
std::map< std::string, CollisionDetectorPtr > collision_
std::map< std::string, CollisionDetectorPtr >::iterator CollisionDetectorIterator
void getPlanningSceneMsg(moveit_msgs::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
std::map< std::string, CollisionDetectorPtr >::const_iterator CollisionDetectorConstIterator
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.
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 tra...
void getAttachedCollisionObjectMsgs(std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs) const
Construct a vector of messages (attached_collision_objects) with the attached collision object data f...
CollisionDetectorConstPtr parent_
collision_detection::World::ObserverHandle current_world_object_update_observer_handle_
static const MOVEIT_PLANNING_SCENE_EXPORT std::string DEFAULT_SCENE_NAME
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,...
const StateFeasibilityFn & getStateFeasibilityPredicate() const
Get the predicate that decides whether states are considered valid or invalid for reasons beyond ones...
Definition of a structure for the allowed collision matrix.
bool hasObjectType(const std::string &id) const
void getKnownObjectColors(ObjectColorMap &kc) const
moveit::core::RobotStatePtr robot_state_
const collision_detection::CollisionEnvConstPtr & getCollisionEnv() const
collision_detection::CollisionDetectorAllocatorPtr alloc_
bool isStateColliding(const std::string &group="", bool verbose=false)
Check if the current state is in collision (with the environment or self collision)....
void allocateCollisionDetectors()
void addCollisionDetector(const collision_detection::CollisionDetectorAllocatorPtr &allocator)
Add a new collision detector type.
MOVEIT_CLASS_FORWARD(PlanningScene)
boost::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
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 t...
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 instan...
const std::string & getActiveCollisionDetectorName() const
Representation of a collision checking result.
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded() const
collision_detection::WorldPtr world_
collision_detection::CollisionEnvPtr cenv_unpadded_
void removeObjectType(const std::string &id)
void setObjectType(const std::string &id, const object_recognition_msgs::ObjectType &type)
void removeAllCollisionObjects()
Clear all collision objects in planning scene.
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=nullptr) const
Check if a given path is valid. Each state is checked for validity (collision avoidance and feasibili...
std::shared_ptr< const Model > ModelConstSharedPtr
double distanceToCollisionUnpadded(moveit::core::RobotState &robot_state) const
The distance between the robot model at state robot_state to the nearest collision (ignoring self-col...
void setName(const std::string &name)
Set the name of the planning scene.
StateFeasibilityFn state_feasibility_
bool shapesAndPosesFromCollisionObjectMessage(const moveit_msgs::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 e...
collision_detection::WorldConstPtr world_const_
void getKnownObjectTypes(ObjectTypeMap &kc) const
boost::function< void(AttachedBody *body, bool attached)> AttachedBodyCallback
void getPlanningSceneDiffMsg(moveit_msgs::PlanningScene &scene) const
Fill the message scene with the differences between this instance of PlanningScene with respect to th...
A class that contains many different constraints, and can check RobotState *versus the full set....
std::map< std::string, std_msgs::ColorRGBA > ObjectColorMap
A map from object names (e.g., attached bodies, collision objects) to their colors.
bool readPoseFromText(std::istream &in, Eigen::Isometry3d &pose) const
std::unique_ptr< ObjectTypeMap > object_types_
boost::function< bool(const moveit::core::RobotState &, bool)> StateFeasibilityFn
This is the function signature for additional feasibility checks to be imposed on states (in addition...
std::unique_ptr< ObjectColorMap > object_colors_
const collision_detection::CollisionEnvConstPtr & getCollisionEnvUnpadded() const
Get the active collision detector for the robot.
void processOctomapMsg(const octomap_msgs::OctomapWithPose &map)
bool processCollisionObjectMove(const moveit_msgs::CollisionObject &object)
void setAttachedBodyUpdateCallback(const moveit::core::AttachedBodyCallback &callback)
Set the callback to be triggered when changes are made to the current scene state.
collision_detection::AllowedCollisionMatrixPtr acm_
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
void removeObjectColor(const std::string &id)
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
collision_detection::CollisionEnvConstPtr cenv_const_
bool loadGeometryFromStream(std::istream &in)
Load the geometry of the planning scene from a stream.
moveit::core::RobotModelConstPtr robot_model_
void getCollidingLinks(std::vector< std::string > &links)
Get the names of the links that are involved in collisions for the current state.
static PlanningScenePtr clone(const PlanningSceneConstPtr &scene)
Clone a planning scene. Even if the scene scene depends on a parent, the cloned scene will not.
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 di...
const std::string & getPlanningFrame() const
Get the frame in which planning is performed.
bool usePlanningSceneMsg(const moveit_msgs::PlanningScene &scene)
Call setPlanningSceneMsg() or setPlanningSceneDiffMsg() depending on how the is_diff member of the me...
void updateCollisionBodyTransforms()
Update the transforms for the collision bodies. This call is needed before calling collision checking...
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,...
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 setStateF...
bool getAttachedCollisionObjectMsg(moveit_msgs::AttachedCollisionObject &attached_collision_obj, const std::string &ns) const
Construct a message (attached_collision_object) with the attached collision object data from the plan...
void findParent(const PlanningScene &scene)
collision_detection::CollisionEnvPtr cenv_
const PlanningSceneConstPtr & getParent() const
Get the parent scene (whith respect to which the diffs are maintained). This may be empty.
MotionFeasibilityFn motion_feasibility_
const collision_detection::CollisionEnvPtr & getCollisionEnvNonConst()
Get the representation of the collision robot This can be used to set padding and link scale on the a...
static const MOVEIT_PLANNING_SCENE_EXPORT std::string OCTOMAP_NS
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
Check whether the current state is in self collision.
moveit::core::TransformsPtr scene_transforms_
bool processPlanningSceneWorldMsg(const moveit_msgs::PlanningSceneWorld &world)
moveit::core::AttachedBodyCallback current_state_attached_body_callback_
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,...
bool getOctomapMsg(octomap_msgs::OctomapWithPose &octomap) const
Construct a message (octomap) with the octomap data from the planning_scene.
void setCollisionObjectUpdateCallback(const collision_detection::World::ObserverCallbackFn &callback)
Set the callback to be triggered when changes are made to the current scene world.
collision_detection::CollisionEnvConstPtr cenv_unpadded_const_
moveit::core::Transforms & getTransformsNonConst()
Get the set of fixed transforms from known frames to the planning frame.
void setStateFeasibilityPredicate(const StateFeasibilityFn &fn)
Specify a predicate that decides whether states are considered valid or invalid for reasons beyond on...
This namespace includes the central class for representing planning scenes.
void saveGeometryToStream(std::ostream &out) const
Save the geometry of the planning scene to a stream, as plain text.
const collision_detection::WorldPtr & getWorldNonConst()
const collision_detection::CollisionEnvConstPtr & getCollisionEnv() const
Get the active collision environment.
bool processCollisionObjectRemove(const moveit_msgs::CollisionObject &object)
bool processCollisionObjectMsg(const moveit_msgs::CollisionObject &object)
friend struct CollisionDetector
static moveit::core::RobotModelPtr createRobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
PlanningScenePtr diff() const
Return a new child PlanningScene that uses this one as parent.
bool processCollisionObjectAdd(const moveit_msgs::CollisionObject &object)
static void poseMsgToEigen(const geometry_msgs::Pose &msg, Eigen::Isometry3d &out)
void setObjectColor(const std::string &id, const std_msgs::ColorRGBA &color)
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 alrea...
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15