37 #ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_DISTANCE_FIELD_ 38 #define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_DISTANCE_FIELD_ 62 Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0),
70 Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0),
90 GroupStateRepresentationPtr& gsr)
const;
103 GroupStateRepresentationPtr& gsr)
const;
124 bool verbose =
false)
const 138 bool verbose =
false)
const 154 virtual void setWorld(
const WorldPtr& world);
156 void generateEnvironmentDistanceField(
bool redo =
true);
160 return distance_field_cache_entry_->distance_field_;
170 GroupStateRepresentationPtr& gsr)
const;
174 GroupStateRepresentationPtr& gsr)
const;
177 DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry();
179 void updateDistanceObject(
const std::string&
id, CollisionWorldDistanceField::DistanceFieldCacheEntryPtr& dfce,
183 const distance_field::DistanceFieldConstPtr& env_distance_field,
184 GroupStateRepresentationPtr& gsr)
const;
186 bool getEnvironmentProximityGradients(
const distance_field::DistanceFieldConstPtr& env_distance_field,
187 GroupStateRepresentationPtr& gsr)
const;
Representation of a collision checking request.
static const double DEFAULT_RESOLUTION
double collision_tolerance_
virtual double distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm, bool verbose=false) const
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
GroupStateRepresentationPtr last_gsr_
virtual void distanceRobot(const DistanceRequest &req, DistanceResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Compute the distance between a robot and the world.
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
Check whether the robot model is in collision with the world in a continuous manner (between two robo...
virtual double distanceWorld(const CollisionWorld &world, bool verbose=false) const
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
boost::mutex update_cache_lock_
static const double DEFAULT_SIZE_Z
Representation of a collision checking result.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const
static const double DEFAULT_MAX_PROPOGATION_DISTANCE
Generic interface to collision detection.
double max_propogation_distance_
virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const
Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.
World::ObserverHandle observer_handle_
virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
World::ObjectConstPtr ObjectConstPtr
static const double DEFAULT_COLLISION_TOLERANCE
static const double resolution
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static const double DEFAULT_SIZE_Y
This class represents a collision model of the robot and can be used for self collision checks (to ch...
bool use_signed_distance_field_
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const
Check whether a given set of objects is in collision with objects from another world. Allowed collisions are ignored. Any contacts are considered.
static const double DEFAULT_SIZE_X
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
Check whether the robot model is in collision with the world in a continuous manner (between two robo...
distance_field::DistanceFieldConstPtr getDistanceField() const
Perform collision checking with the environment. The collision world maintains a representation of th...
static const bool DEFAULT_USE_SIGNED_DISTANCE_FIELD
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
virtual double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, bool verbose=false) const
distance_field::DistanceFieldPtr distance_field_
std::map< std::string, std::vector< PosedBodyPointDecompositionPtr > > posed_body_point_decompositions_
DistanceFieldCacheEntryPtr distance_field_cache_entry_
virtual void distanceWorld(const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const
Compute the distance between another world.