37 #ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_HYBRID_H_ 38 #define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_HYBRID_H_ 46 class CollisionRobotHybrid;
53 Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0),
bool use_signed_distance_field =
false,
54 double resolution = .02,
double collision_tolerance = 0.0,
55 double max_propogation_distance = .25);
57 explicit CollisionWorldHybrid(
const WorldPtr& world, Eigen::Vector3d size = Eigen::Vector3d(3, 3, 4),
58 Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0),
59 bool use_signed_distance_field =
false,
double resolution = .02,
60 double collision_tolerance = 0.0,
double max_propogation_distance = .25);
79 GroupStateRepresentationPtr& gsr)
const;
92 GroupStateRepresentationPtr& gsr)
const;
94 virtual void setWorld(
const WorldPtr& world);
98 GroupStateRepresentationPtr& gsr)
const;
102 GroupStateRepresentationPtr& gsr)
const;
Representation of a collision checking request.
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
virtual ~CollisionWorldHybrid()
void checkRobotCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Representation of a collision checking result.
CollisionWorldDistanceFieldPtr cworld_distance_
virtual void setWorld(const WorldPtr &world)
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...
This class represents a collision model of the robot and can be used for self collision checks (to ch...
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
void checkCollisionDistanceField(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Representation of a robot's state. This includes position, velocity, acceleration and effort...
const CollisionWorldDistanceFieldConstPtr getCollisionWorldDistanceField() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionWorldHybrid(Eigen::Vector3d size=Eigen::Vector3d(3, 3, 4), Eigen::Vector3d origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=false, double resolution=.02, double collision_tolerance=0.0, double max_propogation_distance=.25)