Go to the documentation of this file.
39 #include <boost/algorithm/string/predicate.hpp>
60 const Eigen::Isometry3d& shape_pose)
62 obj->shapes_.push_back(shape);
64 obj->shape_poses_.push_back(shape_pose);
65 obj->global_shape_poses_.push_back(
obj->pose_ * shape_pose);
69 const std::vector<shapes::ShapeConstPtr>&
shapes,
72 if (
shapes.size() != shape_poses.size())
74 ROS_ERROR_NAMED(
"collision_detection",
"Number of shapes and number of poses do not match. "
75 "Not adding this object to collision world.");
87 obj = std::make_shared<Object>(object_id);
94 for (std::size_t i = 0; i <
shapes.size(); ++i)
102 std::vector<std::string> ids;
104 ids.push_back(
object.first);
112 return ObjectConstPtr();
119 if (obj && !
obj.unique())
120 obj = std::make_shared<Object>(*obj);
131 std::map<std::string, ObjectPtr>::const_iterator it =
objects_.find(name);
136 for (
const std::pair<const std::string, ObjectPtr>&
object :
objects_)
139 if (boost::starts_with(
name,
object.first) &&
name[
object.first.length()] ==
'/')
141 return object.second->global_subframe_poses_.find(
name.substr(
object.first.length() + 1)) !=
142 object.second->global_subframe_poses_.end();
154 throw std::runtime_error(
"No transform found with name: " +
name);
158 const Eigen::Isometry3d&
World::getTransform(
const std::string& name,
bool& frame_found)
const
163 std::map<std::string, ObjectPtr>::const_iterator it =
objects_.find(name);
166 return it->second->pose_;
170 for (
const std::pair<const std::string, ObjectPtr>&
object :
objects_)
173 if (boost::starts_with(name,
object.first) && name[
object.first.length()] ==
'/')
175 auto it =
object.second->global_subframe_poses_.find(
name.substr(
object.first.length() + 1));
176 if (it !=
object.second->global_subframe_poses_.end())
185 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
187 return IDENTITY_TRANSFORM;
195 return it->second->global_shape_poses_[shape_index];
199 ROS_ERROR_STREAM(
"Could not find global shape transform for object " << object_id);
200 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
201 return IDENTITY_TRANSFORM;
210 return it->second->global_shape_poses_;
214 ROS_ERROR_STREAM(
"Could not find global shape transforms for object " << object_id);
216 return IDENTITY_TRANSFORM_VECTOR;
221 const Eigen::Isometry3d& shape_pose)
226 unsigned int n = it->second->shapes_.size();
227 for (
unsigned int i = 0; i < n; ++i)
228 if (it->second->shapes_[i] == shape)
232 it->second->shape_poses_[i] = shape_pose;
233 it->second->global_shape_poses_[i] = it->second->pose_ * shape_pose;
247 if (shape_poses.size() == it->second->shapes_.size())
249 for (std::size_t i = 0; i < shape_poses.size(); ++i)
252 it->second->shape_poses_[i] = shape_poses[i];
253 it->second->global_shape_poses_[i] = it->second->
pose_ * shape_poses[i];
267 if (
transform.isApprox(Eigen::Isometry3d::Identity()))
281 obj = std::make_shared<Object>(object_id);
301 unsigned int n = it->second->shapes_.size();
302 for (
unsigned int i = 0; i < n; ++i)
303 if (it->second->shapes_[i] == shape)
306 it->second->shapes_.erase(it->second->shapes_.begin() + i);
307 it->second->shape_poses_.erase(it->second->shape_poses_.begin() + i);
308 it->second->global_shape_poses_.erase(it->second->global_shape_poses_.begin() + i);
310 if (it->second->shapes_.empty())
345 auto obj_pair =
objects_.find(object_id);
350 for (
const auto& t : subframe_poses)
354 obj_pair->second->subframe_poses_ = subframe_poses;
355 obj_pair->second->global_subframe_poses_ = subframe_poses;
363 if (update_shape_poses)
364 for (
unsigned int i = 0; i <
obj->global_shape_poses_.size(); ++i)
365 obj->global_shape_poses_[i] =
obj->pose_ *
obj->shape_poses_[i];
368 if (update_subframe_poses)
370 for (
auto it_global_pose =
obj->global_subframe_poses_.begin(), it_local_pose =
obj->subframe_poses_.begin(),
371 end_poses =
obj->global_subframe_poses_.end();
372 it_global_pose != end_poses; ++it_global_pose, ++it_local_pose)
374 it_global_pose->second =
obj->pose_ * it_local_pose->second;
381 auto o =
new Observer(callback);
383 return ObserverHandle(o);
390 if (*obs == observer_handle.observer_)
401 for (std::map<std::string, ObjectPtr>::const_iterator it =
objects_.begin(); it !=
objects_.end(); ++it)
402 notify(it->second, action);
408 observer->callback_(obj, action);
415 if (observer == observer_handle.
observer_)
419 observer->callback_(
object.second, action);
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...
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.
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...
#define ROS_ERROR_STREAM(args)
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.
const Observer * observer_
Maintain a representation of the environment.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
#define ROS_ERROR_NAMED(name,...)
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
CollisionObject< S > * obj
void notifyObserverAllObjects(const ObserverHandle observer_handle, Action action) const
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
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
#define ASSERT_ISOMETRY(transform)
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...
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 > objects_
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...
const geometry_msgs::Pose * 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 know...
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...
void clearObjects()
Clear all objects. If there are no other pointers to corresponding instances of Objects,...
geometry_msgs::TransformStamped t
std::vector< std::string > getObjectIds() const
Get the list of Object ids.
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sat Dec 21 2024 03:23:42