37 #ifndef MOVEIT_COLLISION_DETECTION_WORLD_ 38 #define MOVEIT_COLLISION_DETECTION_WORLD_ 46 #include <boost/function.hpp> 47 #include <Eigen/Geometry> 82 Object(
const std::string&
id) : id_(id)
111 std::vector<std::string> getObjectIds()
const;
114 ObjectConstPtr getObject(
const std::string&
id)
const;
121 return objects_.begin();
124 const_iterator
end()
const 126 return objects_.end();
131 return objects_.size();
134 const_iterator
find(
const std::string&
id)
const 136 return objects_.find(
id);
140 bool hasObject(
const std::string&
id)
const;
147 void addToObject(
const std::string&
id,
const std::vector<shapes::ShapeConstPtr>&
shapes,
154 void addToObject(
const std::string&
id,
const shapes::ShapeConstPtr& shape,
const Eigen::Affine3d& pose);
158 bool moveShapeInObject(
const std::string&
id,
const shapes::ShapeConstPtr& shape,
const Eigen::Affine3d& pose);
161 bool moveObject(
const std::string&
id,
const Eigen::Affine3d& transform);
175 bool removeObject(
const std::string&
id);
249 void notify(
const ObjectConstPtr&,
Action);
252 void notifyAll(
Action action);
257 void ensureUnique(ObjectPtr& obj);
261 const Eigen::Affine3d& pose);
270 Observer(
const ObserverCallbackFn& callback) : callback_(callback)
ObserverCallbackFn callback_
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
std::vector< Observer * > observers_
const_iterator end() const
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Maintain a representation of the environment.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Object(const std::string &id)
std::map< std::string, ObjectPtr >::const_iterator const_iterator
Generic interface to collision detection.
const Observer * observer_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
boost::function< void(const ObjectConstPtr &, Action)> ObserverCallbackFn
MOVEIT_CLASS_FORWARD(Shape)
A representation of an object.
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
ObserverHandle(const Observer *o)
#define MOVEIT_STRUCT_FORWARD(C)
std::map< std::string, ObjectPtr > objects_
Observer(const ObserverCallbackFn &callback)
const_iterator begin() const
EigenSTL::vector_Affine3d shape_poses_
The poses of the corresponding entries in shapes_.
const_iterator find(const std::string &id) const
std::shared_ptr< const Shape > ShapeConstPtr