44 #include <Eigen/Geometry>
45 #include <eigen_stl_containers/eigen_stl_vector_container.h>
80 Object(
const std::string& object_id) :
id_(object_id)
96 std::vector<shapes::ShapeConstPtr>
shapes_;
123 ObjectConstPtr
getObject(
const std::string& object_id)
const;
130 return objects_.begin();
135 return objects_.end();
140 return objects_.size();
145 return objects_.find(object_id);
149 bool hasObject(
const std::string& object_id)
const;
167 const Eigen::Isometry3d&
getTransform(
const std::string&
name,
bool& frame_found)
const;
181 void addToObject(
const std::string& object_id,
const Eigen::Isometry3d& pose,
182 const std::vector<shapes::ShapeConstPtr>&
shapes,
const EigenSTL::vector_Isometry3d& shape_poses);
187 void addToObject(
const std::string& object_id,
const std::vector<shapes::ShapeConstPtr>&
shapes,
188 const EigenSTL::vector_Isometry3d& shape_poses)
198 void addToObject(
const std::string& object_id,
const Eigen::Isometry3d& pose,
const shapes::ShapeConstPtr& shape,
199 const Eigen::Isometry3d& shape_pose)
201 addToObject(object_id, pose, std::vector<shapes::ShapeConstPtr>{ shape }, EigenSTL::vector_Isometry3d{ shape_pose });
209 void addToObject(
const std::string& object_id,
const shapes::ShapeConstPtr& shape,
const Eigen::Isometry3d& shape_pose)
211 addToObject(object_id, Eigen::Isometry3d::Identity(), std::vector<shapes::ShapeConstPtr>{ shape },
212 EigenSTL::vector_Isometry3d{ shape_pose });
217 bool moveShapeInObject(
const std::string& object_id,
const shapes::ShapeConstPtr& shape,
218 const Eigen::Isometry3d& shape_pose);
224 bool moveObject(
const std::string& object_id,
const Eigen::Isometry3d& transform);
227 bool setObjectPose(
const std::string& object_id,
const Eigen::Isometry3d& pose);
297 const Observer* observer_;
318 void notify(
const ObjectConstPtr& ,
Action );
326 void ensureUnique(ObjectPtr& obj);
329 virtual void addToObjectInternal(
const ObjectPtr& obj,
const shapes::ShapeConstPtr& shape,
330 const Eigen::Isometry3d& shape_pose);
333 void updateGlobalPosesInternal(ObjectPtr& obj,
bool update_shape_poses =
true,
bool update_subframe_poses =
true);
336 std::map<std::string, ObjectPtr> objects_;
349 std::vector<Observer*> observers_;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Maintain a representation of the environment.
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,...
const_iterator find(const std::string &object_id) const
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
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...
std::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
bool removeObject(const std::string &object_id)
Remove a particular object. If there are no external pointers to the corresponding instance of Object...
std::map< std::string, ObjectPtr >::const_iterator const_iterator
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....
MOVEIT_STRUCT_FORWARD(Object)
void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const
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...
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 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...
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...
ObserverHandle addObserver(const ObserverCallbackFn &callback)
register a callback function for notification of changes. callback will be called right after any cha...
const_iterator begin() const
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.
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 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...
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 ...
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...
void clearObjects()
Clear all objects. If there are no other pointers to corresponding instances of Objects,...
const_iterator end() const
ObjectConstPtr getObject(const std::string &object_id) const
Get a particular object.
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...
std::vector< std::string > getObjectIds() const
Get the list of Object ids.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
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...
MOVEIT_CLASS_FORWARD(Shape)
A representation of an object.
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
moveit::core::FixedTransformsMap subframe_poses_
Transforms from the object pose to subframes on the object. Use them to define points of interest on ...
Eigen::Isometry3d pose_
The object's pose. All shapes and subframes are defined relative to this frame. This frame is returne...
Object(const std::string &object_id)
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.
EigenSTL::vector_Isometry3d shape_poses_
The poses of the corresponding entries in shapes_, relative to the object pose.
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.