Go to the documentation of this file.
44 #include <boost/function.hpp>
45 #include <Eigen/Geometry>
81 Object(
const std::string& object_id) :
id_(object_id)
85 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
97 std::vector<shapes::ShapeConstPtr>
shapes_;
124 ObjectConstPtr
getObject(
const std::string& object_id)
const;
150 bool hasObject(
const std::string& object_id)
const;
161 const Eigen::Isometry3d&
getTransform(
const std::string& name)
const;
168 const Eigen::Isometry3d&
getTransform(
const std::string& name,
bool& frame_found)
const;
182 void addToObject(
const std::string& object_id,
const Eigen::Isometry3d& pose,
188 void addToObject(
const std::string& object_id,
const std::vector<shapes::ShapeConstPtr>&
shapes,
200 const Eigen::Isometry3d& shape_pose)
212 addToObject(object_id, Eigen::Isometry3d::Identity(), std::vector<shapes::ShapeConstPtr>{ shape },
219 const Eigen::Isometry3d& shape_pose);
228 bool moveObject(
const std::string& object_id,
const Eigen::Isometry3d& transform);
231 bool setObjectPose(
const std::string& object_id,
const Eigen::Isometry3d& pose);
334 const Eigen::Isometry3d& shape_pose);
ObserverHandle addObserver(const ObserverCallbackFn &callback)
register a callback function for notification of changes. callback will be called right after any cha...
const EigenSTL::vector_Isometry3d & getGlobalShapeTransforms(const std::string &object_id) const
Get the global transforms to the shapes of an object. This function is used to construct the collisio...
EigenSTL::vector_Isometry3d shape_poses_
The poses of the corresponding entries in shapes_, relative to the object pose.
bool setSubframesOfObject(const std::string &object_id, const moveit::core::FixedTransformsMap &subframe_poses)
Set subframes on an object. The frames are relative to the object pose.
void notifyAll(Action action)
bool moveShapesInObject(const std::string &object_id, const EigenSTL::vector_Isometry3d &shape_poses)
Update the pose of all shapes in an object. Shape size is verified. Returns true on success.
void addToObject(const std::string &object_id, const Eigen::Isometry3d &pose, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Add a pose and shape to an object. If the object already exists, this call will add the shape to the ...
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
bool moveObject(const std::string &object_id, const Eigen::Isometry3d &transform)
Move the object pose (thus moving all shapes and subframes in the object) according to the given tran...
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
bool removeShapeFromObject(const std::string &object_id, const shapes::ShapeConstPtr &shape)
Remove shape from object. Shape equality is verified by comparing pointers. Ownership of the object i...
std::vector< Observer * > observers_
All registered observers of this world representation.
bool moveShapeInObject(const std::string &object_id, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Update the pose of a shape in an object. Shape equality is verified by comparing pointers....
void updateGlobalPosesInternal(ObjectPtr &obj, bool update_shape_poses=true, bool update_subframe_poses=true)
Updates the global shape and subframe poses.
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
const Observer * observer_
Object(const std::string &object_id)
ObserverCallbackFn callback_
Maintain a representation of the environment.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
MOVEIT_CLASS_FORWARD(Shape)
MOVEIT_STRUCT_FORWARD(Object)
const_iterator begin() const
void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const
const_iterator end() const
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
ObserverHandle(const Observer *o)
void addToObject(const std::string &object_id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses)
Add a pose and shapes to an object in the map. This function makes repeated calls to addToObjectInter...
ObjectConstPtr getObject(const std::string &object_id) const
Get a particular object.
boost::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
void addToObject(const std::string &object_id, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses)
Add shapes to an object in the map. This function makes repeated calls to addToObjectInternal() to ad...
moveit::core::FixedTransformsMap subframe_poses_
Transforms from the object pose to subframes on the object. Use them to define points of interest on ...
bool knowsTransform(const std::string &name) const
Check if an object or subframe with given name exists in the collision world. A subframe name needs t...
const_iterator find(const std::string &object_id) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
moveit::core::FixedTransformsMap global_subframe_poses_
Transforms from the world frame to the object subframes.
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
void notify(const ObjectConstPtr &, Action)
std::map< std::string, ObjectPtr >::const_iterator const_iterator
std::map< std::string, ObjectPtr > objects_
A representation of an object.
Eigen::Isometry3d pose_
The object's pose. All shapes and subframes are defined relative to this frame. This frame is returne...
const Eigen::Isometry3d & getGlobalShapeTransform(const std::string &object_id, int shape_index) const
Get the global transform to a shape of an object with multiple shapes. shape_index is the index of th...
void ensureUnique(ObjectPtr &obj)
Make sure that the object named id is known only to this instance of the World. If the object is know...
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
void addToObject(const std::string &object_id, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
Add a shape to an object. If the object already exists, this call will add the shape to the object at...
virtual void addToObjectInternal(const ObjectPtr &obj, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose)
bool setObjectPose(const std::string &object_id, const Eigen::Isometry3d &pose)
Set the pose of an object. The pose is specified in the world frame.
std::shared_ptr< const Shape > ShapeConstPtr
const Eigen::Isometry3d & getTransform(const std::string &name) const
Get the transform to an object or subframe with given name. If name does not exist,...
bool removeObject(const std::string &object_id)
Remove a particular object. If there are no external pointers to the corresponding instance of Object...
Observer(const ObserverCallbackFn &callback)
void clearObjects()
Clear all objects. If there are no other pointers to corresponding instances of Objects,...
std::vector< std::string > getObjectIds() const
Get the list of Object ids.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15