Public Member Functions | Protected Attributes | List of all members
collision_detection::CollisionWorldHybrid Class Reference

#include <collision_world_hybrid.h>

Inheritance diagram for collision_detection::CollisionWorldHybrid:
Inheritance graph
[legend]

Public Member Functions

void checkCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
 
void checkCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
void checkCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 
void checkCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const
 
void checkRobotCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
 
void checkRobotCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
void checkRobotCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 
void checkRobotCollisionDistanceField (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) 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)
 
 CollisionWorldHybrid (const WorldPtr &world, 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)
 
 CollisionWorldHybrid (const CollisionWorldHybrid &other, const WorldPtr &world)
 
void getAllCollisions (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
void getCollisionGradients (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
 
const CollisionWorldDistanceFieldConstPtr getCollisionWorldDistanceField () const
 
virtual void setWorld (const WorldPtr &world)
 
virtual ~CollisionWorldHybrid ()
 
- Public Member Functions inherited from collision_detection::CollisionWorldFCL
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
 Check whether the robot model is in collision with the world. Any collisions between a robot link and the world are considered. Self collisions are not checked. More...
 
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 Check whether the robot model is in collision with the world. Allowed collisions are ignored. Self collisions are not checked. More...
 
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 robot states). Any collisions between a robot link and the world are considered. Self collisions are not checked. More...
 
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 robot states). Allowed collisions are ignored. Self collisions are not checked. More...
 
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. More...
 
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. More...
 
 CollisionWorldFCL ()
 
 CollisionWorldFCL (const WorldPtr &world)
 
 CollisionWorldFCL (const CollisionWorldFCL &other, const WorldPtr &world)
 
virtual void distanceRobot (const DistanceRequest &req, DistanceResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const override
 Compute the distance between a robot and the world. More...
 
virtual void distanceWorld (const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const override
 Compute the distance between another world. More...
 
virtual ~CollisionWorldFCL ()
 
- Public Member Functions inherited from collision_detection::CollisionWorld
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. Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 Check whether the robot model is in collision with itself or the world at a particular state. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkCollision (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 itself or the world in a continuous manner (between two robot states) Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkCollision (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 itself or the world in a continuous manner (between two robot states). Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
 CollisionWorld ()
 
 CollisionWorld (const WorldPtr &world)
 
 CollisionWorld (const CollisionWorld &other, const WorldPtr &world)
 A copy constructor. other should not be changed while the copy constructor is running. world must be the same world as used by other or a (not-yet-modified) copy of the world used by other. More...
 
double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, bool verbose=false) const
 Compute the shortest distance between a robot and the world. More...
 
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. More...
 
double distanceWorld (const CollisionWorld &world, bool verbose=false) const
 The shortest distance to another world instance (world) More...
 
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 elements that are allowed to collide (as specified by acm) More...
 
const WorldPtr & getWorld ()
 
const WorldConstPtr & getWorld () const
 
virtual ~CollisionWorld ()
 

Protected Attributes

CollisionWorldDistanceFieldPtr cworld_distance_
 
- Protected Attributes inherited from collision_detection::CollisionWorldFCL
std::map< std::string, FCLObjectfcl_objs_
 
std::unique_ptr< fcl::BroadPhaseCollisionManager > manager_
 

Additional Inherited Members

- Public Types inherited from collision_detection::CollisionWorld
typedef World::ObjectConstPtr ObjectConstPtr
 
typedef World::ObjectPtr ObjectPtr
 
- Protected Member Functions inherited from collision_detection::CollisionWorldFCL
void checkRobotCollisionHelper (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
 
void checkWorldCollisionHelper (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const
 
void constructFCLObject (const World::Object *obj, FCLObject &fcl_obj) const
 
void updateFCLObject (const std::string &id)
 

Detailed Description

Definition at line 48 of file collision_world_hybrid.h.

Constructor & Destructor Documentation

collision_detection::CollisionWorldHybrid::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 
)

Definition at line 41 of file collision_world_hybrid.cpp.

collision_detection::CollisionWorldHybrid::CollisionWorldHybrid ( const WorldPtr &  world,
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 
)
explicit

Definition at line 51 of file collision_world_hybrid.cpp.

collision_detection::CollisionWorldHybrid::CollisionWorldHybrid ( const CollisionWorldHybrid other,
const WorldPtr &  world 
)

Definition at line 60 of file collision_world_hybrid.cpp.

virtual collision_detection::CollisionWorldHybrid::~CollisionWorldHybrid ( )
inlinevirtual

Definition at line 64 of file collision_world_hybrid.h.

Member Function Documentation

void collision_detection::CollisionWorldHybrid::checkCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const

Definition at line 67 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 74 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const

Definition at line 82 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 90 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkRobotCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state 
) const

Definition at line 99 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkRobotCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 106 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkRobotCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm 
) const

Definition at line 114 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::checkRobotCollisionDistanceField ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 122 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::getAllCollisions ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 148 of file collision_world_hybrid.cpp.

void collision_detection::CollisionWorldHybrid::getCollisionGradients ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState state,
const AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 140 of file collision_world_hybrid.cpp.

const CollisionWorldDistanceFieldConstPtr collision_detection::CollisionWorldHybrid::getCollisionWorldDistanceField ( ) const
inline

Definition at line 104 of file collision_world_hybrid.h.

void collision_detection::CollisionWorldHybrid::setWorld ( const WorldPtr &  world)
virtual

set the world to use. This can be expensive unless the new and old world are empty. Passing NULL will result in a new empty world being created.

Reimplemented from collision_detection::CollisionWorldFCL.

Definition at line 131 of file collision_world_hybrid.cpp.

Member Data Documentation

CollisionWorldDistanceFieldPtr collision_detection::CollisionWorldHybrid::cworld_distance_
protected

Definition at line 110 of file collision_world_hybrid.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:34