47 const robot_model::RobotModelConstPtr& kmodel,
48 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
double size_x,
double size_y,
49 double size_z,
bool use_signed_distance_field,
double resolution,
double collision_tolerance,
50 double max_propogation_distance,
double padding,
double scale)
54 kmodel, link_body_decompositions, size_x, size_y, size_z, use_signed_distance_field, resolution,
55 collision_tolerance, max_propogation_distance, padding, scale));
74 GroupStateRepresentationPtr& gsr)
const 91 GroupStateRepresentationPtr& gsr)
const const CollisionRobotDistanceFieldConstPtr getCollisionRobotDistanceField() const
Representation of a collision checking request.
Representation of a collision checking result.
CollisionRobotDistanceFieldPtr crobot_distance_
Generic interface to collision detection.
static const double resolution
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state) const
Representation of a robot's state. This includes position, velocity, acceleration and effort...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionRobotHybrid(const robot_model::RobotModelConstPtr &kmodel)