Public Member Functions | Protected Member Functions | Protected Attributes | Friends
collision_detection::CollisionRobotDistanceField Class Reference

#include <collision_robot_distance_field.h>

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

List of all members.

Public Member Functions

virtual void checkOtherCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state) const
virtual void checkOtherCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state, const collision_detection::AllowedCollisionMatrix &acm) const
virtual void checkOtherCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state1, const moveit::core::RobotState &other_state2) const
virtual void checkOtherCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state1, const moveit::core::RobotState &other_state2, const collision_detection::AllowedCollisionMatrix &acm) const
virtual void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm) const
void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2) const
virtual void checkSelfCollision (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const collision_detection::AllowedCollisionMatrix &acm) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionRobotDistanceField (const robot_model::RobotModelConstPtr &kmodel)
 CollisionRobotDistanceField (const CollisionRobot &col_robot, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance, double padding)
 CollisionRobotDistanceField (const robot_model::RobotModelConstPtr &kmodel, const std::map< std::string, std::vector< CollisionSphere > > &link_body_decompositions, double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, 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, double padding=0.0, double scale=1.0)
 CollisionRobotDistanceField (const CollisionRobotDistanceField &other)
void createCollisionModelMarker (const moveit::core::RobotState &state, visualization_msgs::MarkerArray &model_markers) const
virtual double distanceOther (const moveit::core::RobotState &state, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state) const
virtual double distanceOther (const moveit::core::RobotState &state, const CollisionRobot &other_robot, const moveit::core::RobotState &other_state, const collision_detection::AllowedCollisionMatrix &acm) const
virtual double distanceSelf (const moveit::core::RobotState &state) const
virtual double distanceSelf (const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm) const
boost::shared_ptr< const
DistanceFieldCacheEntry
getLastDistanceFieldEntry () const
void initialize (const std::map< std::string, std::vector< CollisionSphere > > &link_body_decompositions, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)

Protected Member Functions

void addLinkBodyDecompositions (double resolution)
void addLinkBodyDecompositions (double resolution, const std::map< std::string, std::vector< CollisionSphere > > &link_body_decompositions)
void checkSelfCollisionHelper (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, boost::shared_ptr< GroupStateRepresentation > &gsr) const
bool compareCacheEntryToAllowedCollisionMatrix (const boost::shared_ptr< const DistanceFieldCacheEntry > &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
bool compareCacheEntryToState (const boost::shared_ptr< const DistanceFieldCacheEntry > &dfce, const moveit::core::RobotState &state) const
void generateCollisionCheckingStructures (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, boost::shared_ptr< GroupStateRepresentation > &gsr, bool generate_distance_field) const
boost::shared_ptr
< DistanceFieldCacheEntry
generateDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
boost::shared_ptr< const
DistanceFieldCacheEntry
getDistanceFieldCacheEntry (const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
void getGroupStateRepresentation (const boost::shared_ptr< const DistanceFieldCacheEntry > &dfce, const moveit::core::RobotState &state, boost::shared_ptr< GroupStateRepresentation > &gsr) const
bool getIntraGroupCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, boost::shared_ptr< GroupStateRepresentation > &gsr) const
bool getIntraGroupProximityGradients (boost::shared_ptr< GroupStateRepresentation > &gsr) const
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition (const moveit::core::LinkModel *ls) const
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition (const moveit::core::LinkModel *ls, unsigned int ind) const
bool getSelfCollisions (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, boost::shared_ptr< GroupStateRepresentation > &gsr) const
bool getSelfProximityGradients (boost::shared_ptr< GroupStateRepresentation > &gsr) const
virtual void updatedPaddingOrScaling (const std::vector< std::string > &links)
void updateGroupStateRepresentationState (const moveit::core::RobotState &state, boost::shared_ptr< GroupStateRepresentation > &gsr) const

Protected Attributes

double collision_tolerance_
boost::shared_ptr
< DistanceFieldCacheEntry
distance_field_cache_entry_
std::map< std::string,
std::map< std::string, bool > > 
in_group_update_map_
std::map< std::string,
unsigned int > 
link_body_decomposition_index_map_
std::vector
< BodyDecompositionConstPtr > 
link_body_decomposition_vector_
double max_propogation_distance_
Eigen::Vector3d origin_
planning_scene::PlanningScenePtr planning_scene_
std::map< std::string,
boost::shared_ptr
< GroupStateRepresentation > > 
pregenerated_group_state_representation_map_
double resolution_
Eigen::Vector3d size_
boost::mutex update_cache_lock_
bool use_signed_distance_field_

Friends

class CollisionWorldDistanceField

Detailed Description

Definition at line 56 of file collision_robot_distance_field.h.


Constructor & Destructor Documentation

collision_detection::CollisionRobotDistanceField::CollisionRobotDistanceField ( const robot_model::RobotModelConstPtr &  kmodel)

Definition at line 49 of file collision_robot_distance_field.cpp.

collision_detection::CollisionRobotDistanceField::CollisionRobotDistanceField ( const CollisionRobot col_robot,
const Eigen::Vector3d &  size,
const Eigen::Vector3d &  origin,
bool  use_signed_distance_field,
double  resolution,
double  collision_tolerance,
double  max_propogation_distance,
double  padding 
)

Definition at line 72 of file collision_robot_distance_field.cpp.

collision_detection::CollisionRobotDistanceField::CollisionRobotDistanceField ( const robot_model::RobotModelConstPtr &  kmodel,
const std::map< std::string, std::vector< CollisionSphere > > &  link_body_decompositions,
double  size_x = DEFAULT_SIZE_X,
double  size_y = DEFAULT_SIZE_Y,
double  size_z = DEFAULT_SIZE_Z,
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,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 61 of file collision_robot_distance_field.cpp.

Definition at line 84 of file collision_robot_distance_field.cpp.


Member Function Documentation

Definition at line 956 of file collision_robot_distance_field.cpp.

void collision_detection::CollisionRobotDistanceField::addLinkBodyDecompositions ( double  resolution,
const std::map< std::string, std::vector< CollisionSphere > > &  link_body_decompositions 
) [protected]

Definition at line 1045 of file collision_robot_distance_field.cpp.

virtual void collision_detection::CollisionRobotDistanceField::checkOtherCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state,
const CollisionRobot other_robot,
const moveit::core::RobotState other_state 
) const [inline, virtual]

Definition at line 116 of file collision_robot_distance_field.h.

Definition at line 123 of file collision_robot_distance_field.h.

virtual void collision_detection::CollisionRobotDistanceField::checkOtherCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const CollisionRobot other_robot,
const moveit::core::RobotState other_state1,
const moveit::core::RobotState other_state2 
) const [inline, virtual]

Definition at line 131 of file collision_robot_distance_field.h.

virtual void collision_detection::CollisionRobotDistanceField::checkOtherCollision ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const moveit::core::RobotState state1,
const moveit::core::RobotState state2,
const CollisionRobot other_robot,
const moveit::core::RobotState other_state1,
const moveit::core::RobotState other_state2,
const collision_detection::AllowedCollisionMatrix acm 
) const [inline, virtual]

Definition at line 140 of file collision_robot_distance_field.h.

Definition at line 209 of file collision_robot_distance_field.cpp.

Definition at line 217 of file collision_robot_distance_field.cpp.

Definition at line 225 of file collision_robot_distance_field.cpp.

Definition at line 234 of file collision_robot_distance_field.cpp.

Definition at line 101 of file collision_robot_distance_field.h.

Definition at line 108 of file collision_robot_distance_field.h.

Definition at line 154 of file collision_robot_distance_field.cpp.

Definition at line 1312 of file collision_robot_distance_field.cpp.

bool collision_detection::CollisionRobotDistanceField::compareCacheEntryToState ( const boost::shared_ptr< const DistanceFieldCacheEntry > &  dfce,
const moveit::core::RobotState state 
) const [protected]

Definition at line 1252 of file collision_robot_distance_field.cpp.

void collision_detection::CollisionRobotDistanceField::createCollisionModelMarker ( const moveit::core::RobotState state,
visualization_msgs::MarkerArray &  model_markers 
) const

Definition at line 976 of file collision_robot_distance_field.cpp.

virtual double collision_detection::CollisionRobotDistanceField::distanceOther ( const moveit::core::RobotState state,
const CollisionRobot other_robot,
const moveit::core::RobotState other_state 
) const [inline, virtual]

Definition at line 162 of file collision_robot_distance_field.h.

virtual double collision_detection::CollisionRobotDistanceField::distanceOther ( const moveit::core::RobotState state,
const CollisionRobot other_robot,
const moveit::core::RobotState other_state,
const collision_detection::AllowedCollisionMatrix acm 
) const [inline, virtual]

Definition at line 167 of file collision_robot_distance_field.h.

virtual double collision_detection::CollisionRobotDistanceField::distanceSelf ( const moveit::core::RobotState state) const [inline, virtual]

Definition at line 153 of file collision_robot_distance_field.h.

Definition at line 157 of file collision_robot_distance_field.h.

void collision_detection::CollisionRobotDistanceField::generateCollisionCheckingStructures ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
boost::shared_ptr< GroupStateRepresentation > &  gsr,
bool  generate_distance_field 
) const [protected]

Definition at line 135 of file collision_robot_distance_field.cpp.

boost::shared_ptr< DistanceFieldCacheEntry > collision_detection::CollisionRobotDistanceField::generateDistanceFieldCacheEntry ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
bool  generate_distance_field 
) const [protected]

Definition at line 703 of file collision_robot_distance_field.cpp.

boost::shared_ptr< const DistanceFieldCacheEntry > collision_detection::CollisionRobotDistanceField::getDistanceFieldCacheEntry ( const std::string &  group_name,
const moveit::core::RobotState state,
const collision_detection::AllowedCollisionMatrix acm 
) const [protected]

Definition at line 178 of file collision_robot_distance_field.cpp.

void collision_detection::CollisionRobotDistanceField::getGroupStateRepresentation ( const boost::shared_ptr< const DistanceFieldCacheEntry > &  dfce,
const moveit::core::RobotState state,
boost::shared_ptr< GroupStateRepresentation > &  gsr 
) const [protected]

std::cerr << "Attached " << dfce->attached_body_names_[i] << " index " << dfce->attached_body_link_state_indices_[i] << std::endl;

Definition at line 1153 of file collision_robot_distance_field.cpp.

Definition at line 407 of file collision_robot_distance_field.cpp.

Definition at line 636 of file collision_robot_distance_field.cpp.

Definition at line 174 of file collision_robot_distance_field.h.

Definition at line 1085 of file collision_robot_distance_field.cpp.

PosedBodySphereDecompositionPtr collision_detection::CollisionRobotDistanceField::getPosedLinkBodySphereDecomposition ( const moveit::core::LinkModel ls,
unsigned int  ind 
) const [protected]

Definition at line 1076 of file collision_robot_distance_field.cpp.

Definition at line 248 of file collision_robot_distance_field.cpp.

Definition at line 329 of file collision_robot_distance_field.cpp.

void collision_detection::CollisionRobotDistanceField::initialize ( const std::map< std::string, std::vector< CollisionSphere > > &  link_body_decompositions,
const Eigen::Vector3d &  size,
const Eigen::Vector3d &  origin,
bool  use_signed_distance_field,
double  resolution,
double  collision_tolerance,
double  max_propogation_distance 
)

Definition at line 101 of file collision_robot_distance_field.cpp.

virtual void collision_detection::CollisionRobotDistanceField::updatedPaddingOrScaling ( const std::vector< std::string > &  links) [inline, protected, virtual]

Reimplemented from collision_detection::CollisionRobot.

Definition at line 239 of file collision_robot_distance_field.h.

Definition at line 1098 of file collision_robot_distance_field.cpp.


Friends And Related Function Documentation

friend class CollisionWorldDistanceField [friend]

Definition at line 58 of file collision_robot_distance_field.h.


Member Data Documentation

Definition at line 245 of file collision_robot_distance_field.h.

Definition at line 252 of file collision_robot_distance_field.h.

std::map<std::string, std::map<std::string, bool> > collision_detection::CollisionRobotDistanceField::in_group_update_map_ [protected]

Definition at line 253 of file collision_robot_distance_field.h.

Definition at line 249 of file collision_robot_distance_field.h.

Definition at line 248 of file collision_robot_distance_field.h.

Definition at line 246 of file collision_robot_distance_field.h.

Definition at line 242 of file collision_robot_distance_field.h.

planning_scene::PlanningScenePtr collision_detection::CollisionRobotDistanceField::planning_scene_ [protected]

Definition at line 256 of file collision_robot_distance_field.h.

Definition at line 254 of file collision_robot_distance_field.h.

Definition at line 244 of file collision_robot_distance_field.h.

Definition at line 239 of file collision_robot_distance_field.h.

Definition at line 251 of file collision_robot_distance_field.h.

Definition at line 243 of file collision_robot_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