37 #ifndef MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_ 38 #define MOVEIT_COLLISION_DETECTION_COLLISION_WORLD_ 40 #include <boost/utility.hpp> 181 bool verbose =
false)
const 238 bool verbose =
false)
const 259 virtual void setWorld(
const WorldPtr& world);
virtual void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const =0
Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.
Representation of a collision checking request.
const WorldPtr & getWorld()
const WorldConstPtr & getWorld() const
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
World::ObjectPtr ObjectPtr
virtual ~CollisionWorld()
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
Representation of a collision checking result.
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
const robot_model::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
Generic interface to collision detection.
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
double distanceWorld(const CollisionWorld &world, bool verbose=false) const
The shortest distance to another world instance (world)
World::ObjectConstPtr ObjectConstPtr
virtual void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const =0
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
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...
double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, bool verbose=false) const
Compute the shortest distance between a robot and the world.
double distance
The distance between two objects. If two objects are in collision, distance <= 0. ...
virtual void setWorld(const WorldPtr &world)
Perform collision checking with the environment. The collision world maintains a representation of th...
Representation of a robot's state. This includes position, velocity, acceleration and effort...
WorldConstPtr world_const_
virtual void checkCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
Check whether the robot model is in collision with itself or the world at a particular state...
bool verbose
Log debug information.
double distanceRobot(const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, bool verbose=false) const
Compute the shortest distance between a robot and the world.
double distanceWorld(const CollisionWorld &world, const AllowedCollisionMatrix &acm, bool verbose=false) const
The shortest distance to another world instance (world), ignoring the distances between world element...