42 #include <bullet/btBulletCollisionCommon.h>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.core.collision_detection.bullet");
56 observer_handle_ =
getWorld()->addObserver(
59 for (
const std::pair<const std::string, urdf::LinkSharedPtr>& link :
robot_model_->getURDF()->links_)
66 double padding,
double scale)
70 observer_handle_ =
getWorld()->addObserver(
73 for (
const std::pair<const std::string, urdf::LinkSharedPtr>& link :
robot_model_->getURDF()->links_)
85 observer_handle_ =
getWorld()->addObserver(
88 for (
const std::pair<const std::string, urdf::LinkSharedPtr>& link : other.
robot_model_->getURDF()->links_)
99 getWorld()->removeObserver(observer_handle_);
121 std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> cows;
129 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : cows)
132 manager_->setCollisionObjectsTransform(
137 for (
const std::string& link :
active_)
142 manager_->contactTest(res, req, acm,
true);
144 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : cows)
146 manager_->removeCollisionObject(cow->getName());
189 std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> attached_cows;
193 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
196 manager_->setCollisionObjectsTransform(
200 manager_->contactTest(res, req, acm,
false);
202 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
204 manager_->removeCollisionObject(cow->getName());
215 std::vector<collision_detection_bullet::CollisionObjectWrapperPtr> attached_cows;
218 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
226 for (
const std::string& link :
active_)
234 for (
const collision_detection_bullet::CollisionObjectWrapperPtr& cow : attached_cows)
243 RCLCPP_INFO(LOGGER,
"distanceSelf is not implemented for Bullet.");
249 RCLCPP_INFO(LOGGER,
"distanceRobot is not implemented for Bullet.");
254 std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types;
256 for (
const shapes::ShapeConstPtr& shape : obj->
shapes_)
258 if (shape->type == shapes::MESH)
264 auto cow = std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
266 collision_object_types,
false);
277 if (
manager_->hasCollisionObject(
id))
279 manager_->removeCollisionObject(
id);
290 if (
manager_->hasCollisionObject(
id))
292 manager_->removeCollisionObject(
id);
304 getWorld()->removeObserver(observer_handle_);
309 observer_handle_ =
getWorld()->addObserver(
316 void CollisionEnvBullet::notifyObjectChange(
const ObjectConstPtr& obj,
World::Action action)
321 manager_->removeCollisionObject(obj->id_);
331 std::vector<collision_detection_bullet::CollisionObjectWrapperPtr>& cows)
const
333 std::vector<const moveit::core::AttachedBody*> attached_bodies;
338 const EigenSTL::vector_Isometry3d& attached_body_transform = body->getGlobalCollisionBodyTransforms();
340 std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types(
345 collision_detection_bullet::CollisionObjectWrapperPtr cow =
346 std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
348 attached_body_transform, collision_object_types, body->getTouchLinks());
351 catch (std::exception&)
353 RCLCPP_ERROR_STREAM(LOGGER,
"Not adding " << body->getName() <<
" due to bad arguments.");
360 for (
const std::string& link : links)
368 RCLCPP_ERROR(LOGGER,
"Updating padding or scaling for unknown link: '%s'", link.c_str());
374 const moveit::core::RobotState& state,
const collision_detection_bullet::BulletDiscreteBVHManagerPtr& manager)
const
377 for (
const std::string& link :
active_)
386 if (!link->collision_array.empty())
388 const std::vector<urdf::CollisionSharedPtr>& col_array =
389 link->collision_array.empty() ? std::vector<urdf::CollisionSharedPtr>(1, link->collision) :
390 link->collision_array;
392 std::vector<shapes::ShapeConstPtr>
shapes;
394 std::vector<collision_detection_bullet::CollisionObjectType> collision_object_types;
396 for (
const auto& i : col_array)
398 if (i && i->geometry)
404 if (fabs(
getLinkScale(link->name) - 1.0) >= std::numeric_limits<double>::epsilon() ||
405 fabs(
getLinkPadding(link->name)) >= std::numeric_limits<double>::epsilon())
413 if (shape->type == shapes::MESH)
425 if (
manager_->hasCollisionObject(link->name))
427 manager_->removeCollisionObject(link->name);
433 collision_detection_bullet::CollisionObjectWrapperPtr cow =
434 std::make_shared<collision_detection_bullet::CollisionObjectWrapper>(
438 active_.push_back(cow->getName());
440 catch (std::exception&)
442 RCLCPP_ERROR_STREAM(LOGGER,
"Not adding " << link->name <<
" due to bad arguments.");
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static const std::string NAME
collision_detection_bullet::BulletCastBVHManagerPtr manager_CCD_
Handles continuous robot world collision checks.
void setWorld(const WorldPtr &world) override
void updateTransformsFromState(const moveit::core::RobotState &state, const collision_detection_bullet::BulletDiscreteBVHManagerPtr &manager) const
Updates the poses of the objects in the manager according to given robot state.
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
CollisionEnvBullet()=delete
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot l...
std::vector< std::string > active_
The active links where active refers to the group which can collide with everything.
void checkRobotCollisionHelperCCD(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const AllowedCollisionMatrix *acm) const
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkSelfCollision functions into a single function.
std::mutex collision_env_mutex_
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
void addLinkAsCollisionObject(const urdf::LinkSharedPtr &link)
Construts a bullet collision object out of a robot link.
collision_detection_bullet::BulletDiscreteBVHManagerPtr manager_
Handles self collision checks.
~CollisionEnvBullet() override
void updateManagedObject(const std::string &id)
Updates a managed collision object with its world representation.
void addAttachedOjects(const moveit::core::RobotState &state, std::vector< collision_detection_bullet::CollisionObjectWrapperPtr > &cows) const
All of the attached objects in the robot state are wrapped into bullet collision objects.
void addToManager(const World::Object *obj)
Adds a world object to the collision managers.
Provides the interface to the individual collision checking libraries.
virtual void setWorld(const WorldPtr &world)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
const WorldPtr & getWorld()
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Object defining bodies that can be attached to robot links.
const EigenSTL::vector_Isometry3d & getGlobalCollisionBodyTransforms() const
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guar...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return nullptr if not found.
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
Eigen::Isometry3d urdfPose2Eigen(const urdf::Pose &pose)
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
@ USE_SHAPE_TYPE
Infer the type from the type specified in the shapes::Shape class.
@ CONVEX_HULL
Use the mesh in shapes::Shape but make it a convex hulls collision object (if not convex it will be c...
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
const double MAX_DISTANCE_MARGIN
Representation of a collision checking request.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.
A representation of an object.
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string id_
The id for this object.
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.