Classes | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes
collision_detection::CollisionWorldDistanceField Class Reference

#include <collision_world_distance_field.h>

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

List of all members.

Classes

struct  DistanceFieldCacheEntry

Public Member Functions

virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
virtual void checkCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkRobotCollision (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
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
virtual void checkWorldCollision (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const
virtual void checkWorldCollision (const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix &acm) const
 CollisionWorldDistanceField (Eigen::Vector3d size=Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), Eigen::Vector3d origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE)
 CollisionWorldDistanceField (const WorldPtr &world, Eigen::Vector3d size=Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), Eigen::Vector3d origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE)
 CollisionWorldDistanceField (const CollisionWorldDistanceField &other, const WorldPtr &world)
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state) const
virtual double distanceRobot (const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
virtual double distanceWorld (const CollisionWorld &world) const
virtual double distanceWorld (const CollisionWorld &world, const AllowedCollisionMatrix &acm) const
void generateEnvironmentDistanceField (bool redo=true)
void getAllCollisions (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
void getCollisionGradients (const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
boost::shared_ptr< const
distance_field::DistanceField
getDistanceField () const
boost::shared_ptr< const
collision_detection::GroupStateRepresentation
getLastGroupStateRepresentation () const
virtual void setWorld (const WorldPtr &world)
virtual ~CollisionWorldDistanceField ()

Protected Member Functions

boost::shared_ptr
< DistanceFieldCacheEntry
generateDistanceFieldCacheEntry ()
bool getEnvironmentCollisions (const CollisionRequest &req, CollisionResult &res, const boost::shared_ptr< const distance_field::DistanceField > &env_distance_field, boost::shared_ptr< GroupStateRepresentation > &gsr) const
bool getEnvironmentProximityGradients (const boost::shared_ptr< const distance_field::DistanceField > &env_distance_field, boost::shared_ptr< GroupStateRepresentation > &gsr) const
void updateDistanceObject (const std::string &id, boost::shared_ptr< CollisionWorldDistanceField::DistanceFieldCacheEntry > &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)

Static Protected Member Functions

static void notifyObjectChange (CollisionWorldDistanceField *self, const ObjectConstPtr &obj, World::Action action)

Protected Attributes

double collision_tolerance_
boost::shared_ptr
< DistanceFieldCacheEntry
distance_field_cache_entry_
boost::shared_ptr
< collision_detection::GroupStateRepresentation
last_gsr_
double max_propogation_distance_
World::ObserverHandle observer_handle_
Eigen::Vector3d origin_
double resolution_
Eigen::Vector3d size_
boost::mutex update_cache_lock_
bool use_signed_distance_field_

Detailed Description

Definition at line 46 of file collision_world_distance_field.h.


Constructor & Destructor Documentation

collision_detection::CollisionWorldDistanceField::CollisionWorldDistanceField ( Eigen::Vector3d  size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z),
Eigen::Vector3d  origin = Eigen::Vector3d(0, 0, 0),
bool  use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
double  resolution = DEFAULT_RESOLUTION,
double  collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
double  max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE 
)

Definition at line 51 of file collision_world_distance_field.cpp.

collision_detection::CollisionWorldDistanceField::CollisionWorldDistanceField ( const WorldPtr &  world,
Eigen::Vector3d  size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z),
Eigen::Vector3d  origin = Eigen::Vector3d(0, 0, 0),
bool  use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD,
double  resolution = DEFAULT_RESOLUTION,
double  collision_tolerance = DEFAULT_COLLISION_TOLERANCE,
double  max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE 
) [explicit]

Definition at line 69 of file collision_world_distance_field.cpp.

Definition at line 89 of file collision_world_distance_field.cpp.

Definition at line 46 of file collision_world_distance_field.cpp.


Member Function Documentation

void collision_detection::CollisionWorldDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state 
) const [virtual]

Reimplemented from collision_detection::CollisionWorld.

Definition at line 107 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [virtual]

Definition at line 115 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm 
) const [virtual]

Reimplemented from collision_detection::CollisionWorld.

Definition at line 149 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::checkCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [virtual]

Definition at line 157 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state 
) const [virtual]
void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [virtual]

Definition at line 200 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm 
) const [virtual]
void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [virtual]

Definition at line 238 of file collision_world_distance_field.cpp.

virtual void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state1,
const robot_state::RobotState &  state2 
) const [inline, virtual]
virtual void collision_detection::CollisionWorldDistanceField::checkRobotCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state1,
const robot_state::RobotState &  state2,
const AllowedCollisionMatrix acm 
) const [inline, virtual]
virtual void collision_detection::CollisionWorldDistanceField::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world 
) const [inline, virtual]
virtual void collision_detection::CollisionWorldDistanceField::checkWorldCollision ( const CollisionRequest req,
CollisionResult res,
const CollisionWorld other_world,
const AllowedCollisionMatrix acm 
) const [inline, virtual]
virtual double collision_detection::CollisionWorldDistanceField::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState &  state 
) const [inline, virtual]
virtual double collision_detection::CollisionWorldDistanceField::distanceRobot ( const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm 
) const [inline, virtual]
virtual double collision_detection::CollisionWorldDistanceField::distanceWorld ( const CollisionWorld world) const [inline, virtual]
virtual double collision_detection::CollisionWorldDistanceField::distanceWorld ( const CollisionWorld world,
const AllowedCollisionMatrix acm 
) const [inline, virtual]

Definition at line 555 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::getAllCollisions ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const

Definition at line 301 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::getCollisionGradients ( const CollisionRequest req,
CollisionResult res,
const CollisionRobot robot,
const robot_state::RobotState &  state,
const AllowedCollisionMatrix acm,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const

Definition at line 269 of file collision_world_distance_field.cpp.

Definition at line 142 of file collision_world_distance_field.h.

bool collision_detection::CollisionWorldDistanceField::getEnvironmentCollisions ( const CollisionRequest req,
CollisionResult res,
const boost::shared_ptr< const distance_field::DistanceField > &  env_distance_field,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [protected]

Definition at line 332 of file collision_world_distance_field.cpp.

bool collision_detection::CollisionWorldDistanceField::getEnvironmentProximityGradients ( const boost::shared_ptr< const distance_field::DistanceField > &  env_distance_field,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [protected]

Definition at line 417 of file collision_world_distance_field.cpp.

Definition at line 147 of file collision_world_distance_field.h.

Definition at line 477 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::setWorld ( const WorldPtr &  world) [virtual]

Reimplemented from collision_detection::CollisionWorld.

Definition at line 456 of file collision_world_distance_field.cpp.

void collision_detection::CollisionWorldDistanceField::updateDistanceObject ( const std::string &  id,
boost::shared_ptr< CollisionWorldDistanceField::DistanceFieldCacheEntry > &  dfce,
EigenSTL::vector_Vector3d add_points,
EigenSTL::vector_Vector3d subtract_points 
) [protected]

Definition at line 503 of file collision_world_distance_field.cpp.


Member Data Documentation

Definition at line 181 of file collision_world_distance_field.h.

Definition at line 185 of file collision_world_distance_field.h.

Definition at line 186 of file collision_world_distance_field.h.

Definition at line 182 of file collision_world_distance_field.h.

Definition at line 187 of file collision_world_distance_field.h.

Definition at line 178 of file collision_world_distance_field.h.

Definition at line 180 of file collision_world_distance_field.h.

Definition at line 177 of file collision_world_distance_field.h.

Definition at line 184 of file collision_world_distance_field.h.

Definition at line 179 of file collision_world_distance_field.h.


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


moveit_experimental
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley , Jorge Nicho
autogenerated on Wed Jun 19 2019 19:24:03