144 namespace DistanceRequestTypes
173 void enableGroup(
const moveit::core::RobotModelConstPtr& robot_model)
175 if (robot_model->hasJointModelGroup(
group_name))
249 distance = std::numeric_limits<double>::max();
273 using DistanceMap = std::map<const std::pair<std::string, std::string>, std::vector<DistanceResultsData> >;
309 distance = std::numeric_limits<double>::max();
323 double distance = std::numeric_limits<double>::max();
332 using ContactMap = std::map<std::pair<std::string, std::string>, std::vector<Contact> >;
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Type
The types of bodies that are considered for collision.
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
@ ALL
Find all the contacts for a given pair.
@ GLOBAL
Find the global minimum.
@ LIMITED
Find a limited(max_contacts_per_body) set of contacts for a given pair.
@ SINGLE
Find the global minimum for each pair.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
std::map< const std::pair< std::string, std::string >, std::vector< DistanceResultsData > > DistanceMap
Mapping between the names of the collision objects and the DistanceResultData.
Vec3fX< details::Vec3Data< double > > Vector3d
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
virtual ~CollisionRequest()
bool verbose
Flag indicating whether information about detected collisions should be reported.
std::size_t max_cost_sources
When costs are computed, this value defines how many of the top cost sources should be returned.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool cost
If true, a collision cost is computed.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::function< bool(const CollisionResult &)> is_done
Function call that decides whether collision detection should stop.
bool detailed_distance
If true, return detailed distance information. Distance must be set to true as well.
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...
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
void print() const
Throttled warning printing the first collision pair, if any. All collisions are logged at DEBUG level...
std::map< std::pair< std::string, std::string >, std::vector< Contact > > ContactMap
A map returning the pairs of body ids in contact, plus their contact details.
DistanceResult distance_result
Distance data for each link.
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
double distance
Closest distance between two bodies.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
When collision costs are computed, this structure contains information about the partial cost incurre...
double getVolume() const
Get the volume of the AABB around the cost source.
std::array< double, 3 > aabb_max
The maximum bound of the AABB defining the volume responsible for this partial cost.
double cost
The partial cost (the probability of existence for the object there is a collision with)
std::array< double, 3 > aabb_min
The minimum bound of the AABB defining the volume responsible for this partial cost.
bool operator<(const CostSource &other) const
Order cost sources so that the most costly source is at the top.
Representation of a distance-reporting request.
const std::set< const moveit::core::LinkModel * > * active_components_only
The set of active components to check.
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on req_.
bool verbose
Log debug information.
std::string group_name
The group name.
std::size_t max_contacts_per_body
Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold)
double distance_threshold
bool enable_signed_distance
Indicate if a signed distance should be calculated in a collision.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
bool enable_nearest_points
Indicate if nearest point information should be calculated.
Result of a distance request.
DistanceMap distances
A map of distance data for each link in the req.active_components_only.
bool collision
Indicates if two objects were in collision.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
void clear()
Clear structure data.
Generic representation of the distance information for a pair of objects.
BodyType body_types[2]
The object body type.
bool operator<(const DistanceResultsData &other)
Compare if the distance is less than another.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d nearest_points[2]
The nearest points.
void clear()
Clear structure data.
bool operator>(const DistanceResultsData &other)
Compare if the distance is greater than another.
std::string link_names[2]
The object link names.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.