38 #include <geometric_shapes/check_isometry.h>
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection.world");
53 objects_ = other.objects_;
58 while (!observers_.empty())
62 inline void World::addToObjectInternal(
const ObjectPtr& obj,
const shapes::ShapeConstPtr& shape,
63 const Eigen::Isometry3d& shape_pose)
65 obj->shapes_.push_back(shape);
66 ASSERT_ISOMETRY(shape_pose)
67 obj->shape_poses_.push_back(shape_pose);
68 obj->global_shape_poses_.push_back(obj->pose_ * shape_pose);
72 const std::vector<shapes::ShapeConstPtr>&
shapes,
73 const EigenSTL::vector_Isometry3d& shape_poses)
75 if (
shapes.size() != shape_poses.size())
78 "Number of shapes and number of poses do not match. Not adding this object to collision world.");
87 ObjectPtr& obj = objects_[object_id];
90 obj = std::make_shared<Object>(object_id);
97 for (std::size_t i = 0; i <
shapes.size(); ++i)
98 addToObjectInternal(obj,
shapes[i], shape_poses[i]);
105 std::vector<std::string> ids;
106 for (
const auto&
object : objects_)
107 ids.push_back(
object.first);
113 const auto it = objects_.find(object_id);
114 if (it == objects_.end())
115 return ObjectConstPtr();
120 void World::ensureUnique(ObjectPtr& obj)
122 if (obj && !obj.unique())
123 obj = std::make_shared<Object>(*obj);
128 return objects_.find(object_id) != objects_.end();
134 const std::map<std::string, ObjectPtr>::const_iterator it = objects_.find(
name);
135 if (it != objects_.end())
139 for (
const std::pair<const std::string, ObjectPtr>&
object : objects_)
143 if (
name.rfind(
object.first, 0) == 0 &&
name[
object.first.length()] ==
'/')
145 return object.second->global_subframe_poses_.find(
name.substr(
object.first.length() + 1)) !=
146 object.second->global_subframe_poses_.end();
158 throw std::runtime_error(
"No transform found with name: " +
name);
167 const std::map<std::string, ObjectPtr>::const_iterator it = objects_.find(
name);
168 if (it != objects_.end())
170 return it->second->pose_;
174 for (
const std::pair<const std::string, ObjectPtr>&
object : objects_)
178 if (
name.rfind(
object.first, 0) == 0 &&
name[
object.first.length()] ==
'/')
180 const auto it =
object.second->global_subframe_poses_.find(
name.substr(
object.first.length() + 1));
181 if (it !=
object.second->global_subframe_poses_.end())
190 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
192 return IDENTITY_TRANSFORM;
197 const auto it = objects_.find(object_id);
198 if (it != objects_.end())
200 return it->second->global_shape_poses_[shape_index];
204 RCLCPP_ERROR_STREAM(LOGGER,
"Could not find global shape transform for object " << object_id);
205 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
206 return IDENTITY_TRANSFORM;
212 const auto it = objects_.find(object_id);
213 if (it != objects_.end())
215 return it->second->global_shape_poses_;
219 RCLCPP_ERROR_STREAM(LOGGER,
"Could not find global shape transforms for object " << object_id);
220 static const EigenSTL::vector_Isometry3d IDENTITY_TRANSFORM_VECTOR;
221 return IDENTITY_TRANSFORM_VECTOR;
226 const Eigen::Isometry3d& shape_pose)
228 const auto it = objects_.find(object_id);
229 if (it != objects_.end())
231 const unsigned int n = it->second->shapes_.size();
232 for (
unsigned int i = 0; i < n; ++i)
233 if (it->second->shapes_[i] == shape)
235 ensureUnique(it->second);
236 ASSERT_ISOMETRY(shape_pose)
237 it->second->shape_poses_[i] = shape_pose;
238 it->second->global_shape_poses_[i] = it->second->pose_ * shape_pose;
249 const auto it = objects_.find(object_id);
250 if (it == objects_.end())
252 if (transform.isApprox(Eigen::Isometry3d::Identity()))
255 ASSERT_ISOMETRY(transform)
256 return setObjectPose(object_id, transform * it->second->pose_);
261 ASSERT_ISOMETRY(pose);
262 ObjectPtr& obj = objects_[object_id];
266 obj = std::make_shared<Object>(object_id);
276 updateGlobalPosesInternal(obj);
283 const auto it = objects_.find(object_id);
284 if (it != objects_.end())
286 const unsigned int n = it->second->shapes_.size();
287 for (
unsigned int i = 0; i < n; ++i)
288 if (it->second->shapes_[i] == shape)
290 ensureUnique(it->second);
291 it->second->shapes_.erase(it->second->shapes_.begin() + i);
292 it->second->shape_poses_.erase(it->second->shape_poses_.begin() + i);
293 it->second->global_shape_poses_.erase(it->second->global_shape_poses_.begin() + i);
295 if (it->second->shapes_.empty())
312 const auto it = objects_.find(object_id);
313 if (it != objects_.end())
330 const auto obj_pair = objects_.find(object_id);
331 if (obj_pair == objects_.end())
335 for (
const auto& t : subframe_poses)
337 ASSERT_ISOMETRY(t.second)
339 obj_pair->second->subframe_poses_ = subframe_poses;
340 obj_pair->second->global_subframe_poses_ = subframe_poses;
341 updateGlobalPosesInternal(obj_pair->second,
false,
true);
345 void World::updateGlobalPosesInternal(ObjectPtr& obj,
bool update_shape_poses,
bool update_subframe_poses)
348 if (update_shape_poses)
349 for (
unsigned int i = 0; i < obj->global_shape_poses_.size(); ++i)
350 obj->global_shape_poses_[i] = obj->pose_ * obj->shape_poses_[i];
353 if (update_subframe_poses)
355 for (
auto it_global_pose = obj->global_subframe_poses_.begin(), it_local_pose = obj->subframe_poses_.begin(),
356 end_poses = obj->global_subframe_poses_.end();
357 it_global_pose != end_poses; ++it_global_pose, ++it_local_pose)
359 it_global_pose->second = obj->pose_ * it_local_pose->second;
366 const auto o =
new Observer(callback);
367 observers_.push_back(o);
373 for (
auto obs = observers_.begin(); obs != observers_.end(); ++obs)
375 if (*obs == observer_handle.observer_)
378 observers_.erase(obs);
384 void World::notifyAll(Action
action)
386 for (std::map<std::string, ObjectPtr>::const_iterator it = objects_.begin(); it != objects_.end(); ++it)
387 notify(it->second,
action);
390 void World::notify(
const ObjectConstPtr& obj, Action
action)
392 for (Observer* observer : observers_)
393 observer->callback_(obj,
action);
398 for (
auto observer : observers_)
400 if (observer == observer_handle.observer_)
403 for (
const auto&
object : objects_)
404 observer->callback_(
object.second,
action);
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,...
void removeObserver(const ObserverHandle observer_handle)
remove a notifier callback
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...
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 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...
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.
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,...
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.
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...