41 #include <boost/bind.hpp> 52 bool use_signed_distance_field,
double resolution,
53 double collision_tolerance,
double max_propogation_distance)
70 Eigen::Vector3d origin,
bool use_signed_distance_field,
72 double max_propogation_distance)
90 const WorldPtr& world)
111 GroupStateRepresentationPtr gsr;
117 GroupStateRepresentationPtr& gsr)
const 140 catch (
const std::bad_cast& e)
142 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
153 GroupStateRepresentationPtr gsr;
160 GroupStateRepresentationPtr& gsr)
const 183 catch (
const std::bad_cast& e)
185 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
196 GroupStateRepresentationPtr gsr;
202 GroupStateRepresentationPtr& gsr)
const 208 DistanceFieldCacheEntryConstPtr dfce;
222 catch (
const std::bad_cast& e)
224 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
233 GroupStateRepresentationPtr gsr;
240 GroupStateRepresentationPtr& gsr)
const 246 DistanceFieldCacheEntryPtr dfce;
260 catch (
const std::bad_cast& e)
262 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
271 GroupStateRepresentationPtr& gsr)
const 289 catch (
const std::bad_cast& e)
291 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
301 GroupStateRepresentationPtr& gsr)
const 319 catch (
const std::bad_cast& e)
321 ROS_ERROR_STREAM(
"Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what());
330 GroupStateRepresentationPtr& gsr)
const 332 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
334 bool is_link = i < gsr->dfce_->link_names_.size();
335 std::string link_name = i < gsr->dfce_->link_names_.size() ? gsr->dfce_->link_names_[i] :
"attached";
336 if (is_link && !gsr->dfce_->link_has_geometry_[i])
341 const std::vector<CollisionSphere>* collision_spheres_1;
346 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
347 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
351 collision_spheres_1 =
352 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
353 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
358 std::vector<unsigned int> colls;
365 for (
unsigned int j = 0; j < colls.size(); j++)
370 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[colls[j]];
377 gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[colls[j]];
379 con.
body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
391 gsr->gradients_[i].collision =
true;
413 const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr)
const 415 bool in_collision =
false;
416 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
418 bool is_link = i < gsr->dfce_->link_names_.size();
420 if (is_link && !gsr->dfce_->link_has_geometry_[i])
425 const std::vector<CollisionSphere>* collision_spheres_1;
429 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
430 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
434 collision_spheres_1 =
435 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
436 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
478 self->updateDistanceObject(obj->id_, self->distance_field_cache_entry_, add_points, subtract_points);
482 self->distance_field_cache_entry_->distance_field_->removePointsFromField(subtract_points);
486 self->distance_field_cache_entry_->distance_field_->removePointsFromField(subtract_points);
487 self->distance_field_cache_entry_->distance_field_->addPointsToField(add_points);
491 self->distance_field_cache_entry_->distance_field_->addPointsToField(add_points);
494 ROS_DEBUG_NAMED(
"collision_distance_field",
"Modifying object %s took %lf s", obj->id_.c_str(),
502 std::map<std::string, std::vector<PosedBodyPointDecompositionPtr>>::iterator cur_it =
503 dfce->posed_body_point_decompositions_.find(
id);
504 if (cur_it != dfce->posed_body_point_decompositions_.end())
506 for (
unsigned int i = 0; i < cur_it->second.size(); i++)
508 subtract_points.insert(subtract_points.end(), cur_it->second[i]->getCollisionPoints().begin(),
509 cur_it->second[i]->getCollisionPoints().end());
513 World::ObjectConstPtr
object =
getWorld()->getObject(
id);
516 ROS_DEBUG_STREAM(
"Updating/Adding Object '" << object->id_ <<
"' with " << object->shapes_.size()
517 <<
" shapes to CollisionWorldDistanceField");
518 std::vector<PosedBodyPointDecompositionPtr> shape_points;
519 for (
unsigned int i = 0; i <
object->shapes_.size(); i++)
525 std::shared_ptr<const octomap::OcTree> octree = octree_shape->
octree;
527 shape_points.push_back(std::make_shared<PosedBodyPointDecomposition>(octree));
533 shape_points.push_back(std::make_shared<PosedBodyPointDecomposition>(bd, object->shape_poses_[i]));
536 add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(),
537 shape_points.back()->getCollisionPoints().end());
540 dfce->posed_body_point_decompositions_[id] = shape_points;
544 ROS_DEBUG_STREAM(
"Removing Object '" <<
id <<
"' from CollisionWorldDistanceField");
545 dfce->posed_body_point_decompositions_.erase(
id);
562 dfce->distance_field_->addPointsToField(add_points);
bool getIntraGroupProximityGradients(GroupStateRepresentationPtr &gsr) const
void generateCollisionCheckingStructures(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const
Representation of a collision checking request.
const WorldPtr & getWorld()
double collision_tolerance_
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
bool getCollisionSphereGradients(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
virtual void checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with itself or the world at a particular state...
A body attached to a robot link.
ContactMap contacts
A map returning the pairs of ids of the bodies in contact, plus information about the contacts themse...
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
void updateDistanceObject(const std::string &id, CollisionWorldDistanceField::DistanceFieldCacheEntryPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
Representation of a collision checking result.
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry()
CollisionWorldDistanceField(Eigen::Vector3d size=Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), Eigen::Vector3d origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE)
std::map< std::string, ObjectPtr >::const_iterator const_iterator
Generic interface to collision detection.
double max_propogation_distance_
World::ObserverHandle observer_handle_
std::size_t contact_count
Number of contacts returned.
virtual ~CollisionWorldDistanceField()
bool collision
True if collision was found, false otherwise.
World::ObjectConstPtr ObjectConstPtr
#define ROS_DEBUG_NAMED(name,...)
std::shared_ptr< const octomap::OcTree > octree
std::size_t max_contacts
Overall maximum number of contacts to compute.
static const double resolution
static void notifyObjectChange(CollisionWorldDistanceField *self, const ObjectConstPtr &obj, World::Action action)
void updateGroupStateRepresentationState(const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
bool getEnvironmentCollisions(const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
This class represents a collision model of the robot and can be used for self collision checks (to ch...
bool use_signed_distance_field_
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot) ...
bool contacts
If true, compute contacts.
bool getIntraGroupCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
#define ROS_DEBUG_STREAM(args)
virtual void setWorld(const WorldPtr &world)
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
A body in the environment.
virtual void setWorld(const WorldPtr &world)
Perform collision checking with the environment. The collision world maintains a representation of th...
Representation of a robot's state. This includes position, velocity, acceleration and effort...
A DistanceField implementation that uses a vector propagation method. Distances propagate outward fro...
#define ROS_ERROR_STREAM(args)
static const std::string NAME_
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
bool getSelfProximityGradients(GroupStateRepresentationPtr &gsr) const
DistanceFieldCacheEntryPtr distance_field_cache_entry_
bool getCollisionSphereCollision(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance)
bool getSelfCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
std::shared_ptr< const Shape > ShapeConstPtr