37 #ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_ 38 #define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_ 45 #include <boost/thread/mutex.hpp> 57 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
58 double size_x = 3.0,
double size_y = 3.0,
double size_z = 4.0,
59 bool use_signed_distance_field =
false,
double resolution = .02,
60 double collision_tolerance = 0.0,
double max_propogation_distance = .25,
double padding = 0.0,
66 double size_x,
double size_y,
double size_z,
bool use_signed_distance_field,
67 double resolution,
double collision_tolerance,
double max_propogation_distance)
69 crobot_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z),
70 Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance,
71 max_propogation_distance);
80 GroupStateRepresentationPtr& gsr)
const;
89 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...
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state) const
void initializeRobotDistanceField(const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, double size_x, double size_y, double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionRobotHybrid(const robot_model::RobotModelConstPtr &kmodel)