Maintain a representation of the environment. More...
#include <world.h>
Classes | |
class | Action |
Represents an action that occurred on an object in the world. Several bits may be set indicating several things happened to the object. If the DESTROY bit is set, other bits will not be set. More... | |
struct | Object |
A representation of an object. More... | |
class | Observer |
class | ObserverHandle |
Public Types | |
enum | ActionBits { UNINITIALIZED = 0, CREATE = 1, DESTROY = 2, MOVE_SHAPE = 4, ADD_SHAPE = 8, REMOVE_SHAPE = 16 } |
using | const_iterator = std::map< std::string, ObjectPtr >::const_iterator |
using | ObserverCallbackFn = boost::function< void(const ObjectConstPtr &, Action)> |
Public Member Functions | |
ObserverHandle | addObserver (const ObserverCallbackFn &callback) |
register a callback function for notification of changes. callback will be called right after any change occurs to any Object. observer is the object which is requesting the changes. It is only used for identifying the callback in removeObserver(). More... | |
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 object at the specified pose. Otherwise, the object is created and the specified shape is added. This calls addToObjectInternal(). shape_pose is defined relative to the object's pose, not to the world frame. More... | |
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 addToObjectInternal() to add the shapes one by one. More... | |
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 the specified pose. Otherwise, the object is created and the specified shape is added. This calls addToObjectInternal(). shape_pose is defined relative to the object's pose, not to the world frame. More... | |
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 add the shapes one by one. More... | |
const_iterator | begin () const |
void | clearObjects () |
Clear all objects. If there are no other pointers to corresponding instances of Objects, the memory is freed. More... | |
const_iterator | end () const |
const_iterator | find (const std::string &object_id) const |
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 the object (counting from 0) and needs to be valid. This function is used to construct the collision environment. More... | |
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 collision environment. More... | |
ObjectConstPtr | getObject (const std::string &object_id) const |
Get a particular object. More... | |
std::vector< std::string > | getObjectIds () const |
Get the list of Object ids. More... | |
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, a std::runtime_error is thrown. A subframe name needs to be prefixed with the object's name separated by a slash. The transform is global (relative to the world origin). The returned transform is guaranteed to be a valid isometry. More... | |
const Eigen::Isometry3d & | getTransform (const std::string &name, bool &frame_found) const |
Get the transform to an object or subframe with given name. If name does not exist, returns an identity transform and sets frame_found to false. A subframe name needs to be prefixed with the object's name separated by a slash. The transform is global (relative to the world origin). The returned transform is guaranteed to be a valid isometry. More... | |
bool | hasObject (const std::string &object_id) const |
Check if a particular object exists in the collision world. More... | |
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 to be prefixed with the object's name separated by a slash. More... | |
MOVEIT_STRUCT_FORWARD (Object) | |
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 transform specified in world frame. The transform is relative to and changes the object pose. It does not replace it. More... | |
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. Returns true on success. More... | |
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. More... | |
void | notifyObserverAllObjects (const ObserverHandle observer_handle, Action action) const |
bool | removeObject (const std::string &object_id) |
Remove a particular object. If there are no external pointers to the corresponding instance of Object, the memory is freed. Returns true on success and false if no such object was found. More... | |
void | removeObserver (const ObserverHandle observer_handle) |
remove a notifier callback More... | |
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 is renounced (i.e. object is deleted if no external references exist) if this was the last shape in the object. Returns true on success and false if the object did not exist or did not contain the shape. More... | |
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. More... | |
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. More... | |
std::size_t | size () const |
World () | |
Constructor. More... | |
World (const World &other) | |
A copy constructor. other should not be changed while the copy constructor is running This does copy on write and should be quick. More... | |
virtual | ~World () |
Private Member Functions | |
virtual void | addToObjectInternal (const ObjectPtr &obj, const shapes::ShapeConstPtr &shape, const Eigen::Isometry3d &shape_pose) |
void | ensureUnique (ObjectPtr &obj) |
Make sure that the object named id is known only to this instance of the World. If the object is known outside of it, a clone is made so that it can be safely modified later on. More... | |
void | notify (const ObjectConstPtr &, Action) |
void | notifyAll (Action action) |
void | updateGlobalPosesInternal (ObjectPtr &obj, bool update_shape_poses=true, bool update_subframe_poses=true) |
Updates the global shape and subframe poses. More... | |
Private Attributes | |
std::map< std::string, ObjectPtr > | objects_ |
std::vector< Observer * > | observers_ |
All registered observers of this world representation. More... | |
using collision_detection::World::const_iterator = std::map<std::string, ObjectPtr>::const_iterator |
using collision_detection::World::ObserverCallbackFn = boost::function<void(const ObjectConstPtr&, Action)> |
collision_detection::World::World | ( | const World & | other | ) |
World::ObserverHandle collision_detection::World::addObserver | ( | const ObserverCallbackFn & | callback | ) |
register a callback function for notification of changes. callback will be called right after any change occurs to any Object. observer is the object which is requesting the changes. It is only used for identifying the callback in removeObserver().
|
inline |
Add a pose and shape to an object. If the object already exists, this call will add the shape to the object at the specified pose. Otherwise, the object is created and the specified shape is added. This calls addToObjectInternal(). shape_pose is defined relative to the object's pose, not to the world frame.
void collision_detection::World::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 addToObjectInternal() to add the shapes one by one.
|
inline |
Add a shape to an object. If the object already exists, this call will add the shape to the object at the specified pose. Otherwise, the object is created and the specified shape is added. This calls addToObjectInternal(). shape_pose is defined relative to the object's pose, not to the world frame.
|
inline |
Add shapes to an object in the map. This function makes repeated calls to addToObjectInternal() to add the shapes one by one.
|
inlineprivatevirtual |
|
inline |
void collision_detection::World::clearObjects | ( | ) |
|
inline |
|
private |
|
inline |
const Eigen::Isometry3d & collision_detection::World::getGlobalShapeTransform | ( | const std::string & | object_id, |
int | shape_index | ||
) | const |
const EigenSTL::vector_Isometry3d & collision_detection::World::getGlobalShapeTransforms | ( | const std::string & | object_id | ) | const |
World::ObjectConstPtr collision_detection::World::getObject | ( | const std::string & | object_id | ) | const |
std::vector< std::string > collision_detection::World::getObjectIds | ( | ) | const |
const Eigen::Isometry3d & collision_detection::World::getTransform | ( | const std::string & | name | ) | const |
Get the transform to an object or subframe with given name. If name does not exist, a std::runtime_error is thrown. A subframe name needs to be prefixed with the object's name separated by a slash. The transform is global (relative to the world origin). The returned transform is guaranteed to be a valid isometry.
const Eigen::Isometry3d & collision_detection::World::getTransform | ( | const std::string & | name, |
bool & | frame_found | ||
) | const |
Get the transform to an object or subframe with given name. If name does not exist, returns an identity transform and sets frame_found to false. A subframe name needs to be prefixed with the object's name separated by a slash. The transform is global (relative to the world origin). The returned transform is guaranteed to be a valid isometry.
bool collision_detection::World::hasObject | ( | const std::string & | object_id | ) | const |
bool collision_detection::World::knowsTransform | ( | const std::string & | name | ) | const |
collision_detection::World::MOVEIT_STRUCT_FORWARD | ( | Object | ) |
bool collision_detection::World::moveObject | ( | const std::string & | object_id, |
const Eigen::Isometry3d & | transform | ||
) |
bool collision_detection::World::moveShapeInObject | ( | const std::string & | object_id, |
const shapes::ShapeConstPtr & | shape, | ||
const Eigen::Isometry3d & | shape_pose | ||
) |
bool collision_detection::World::moveShapesInObject | ( | const std::string & | object_id, |
const EigenSTL::vector_Isometry3d & | shape_poses | ||
) |
|
private |
|
private |
void collision_detection::World::notifyObserverAllObjects | ( | const ObserverHandle | observer_handle, |
Action | action | ||
) | const |
bool collision_detection::World::removeObject | ( | const std::string & | object_id | ) |
void collision_detection::World::removeObserver | ( | const ObserverHandle | observer_handle | ) |
bool collision_detection::World::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 is renounced (i.e. object is deleted if no external references exist) if this was the last shape in the object. Returns true on success and false if the object did not exist or did not contain the shape.
bool collision_detection::World::setObjectPose | ( | const std::string & | object_id, |
const Eigen::Isometry3d & | pose | ||
) |
bool collision_detection::World::setSubframesOfObject | ( | const std::string & | object_id, |
const moveit::core::FixedTransformsMap & | subframe_poses | ||
) |
|
inline |
|
private |
|
private |
|
private |