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

#include <collision_robot_hybrid.h>

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

Public Member Functions

void checkSelfCollisionDistanceField (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state) const
 
void checkSelfCollisionDistanceField (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state, GroupStateRepresentationPtr &gsr) const
 
void checkSelfCollisionDistanceField (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm) const
 
void checkSelfCollisionDistanceField (const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const robot_state::RobotState &state, const collision_detection::AllowedCollisionMatrix &acm, GroupStateRepresentationPtr &gsr) const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionRobotHybrid (const robot_model::RobotModelConstPtr &kmodel)
 
 CollisionRobotHybrid (const robot_model::RobotModelConstPtr &kmodel, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, double size_x=3.0, double size_y=3.0, double size_z=4.0, bool use_signed_distance_field=false, double resolution=.02, double collision_tolerance=0.0, double max_propogation_distance=.25, double padding=0.0, double scale=1.0)
 
 CollisionRobotHybrid (const CollisionRobotHybrid &other)
 
const CollisionRobotDistanceFieldConstPtr getCollisionRobotDistanceField () const
 
void initializeRobotDistanceField (const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, double size_x, double size_y, double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
 
- Public Member Functions inherited from collision_detection::CollisionRobotFCL
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
 Check for collision with a different robot (possibly a different kinematic model as well). Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
 Check for collision with a different robot (possibly a different kinematic model as well). Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2) const
 Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkOtherCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const CollisionRobot &other_robot, const robot_state::RobotState &other_state1, const robot_state::RobotState &other_state2, const AllowedCollisionMatrix &acm) const
 Check for collision with a different robot (possibly a different kinematic model as well), in a continuous fashion. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
 Check for self collision. Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2) const
 Check for self collision in a continuous manner. Any collision between any pair of links is checked for, NO collisions are ignored. More...
 
virtual void checkSelfCollision (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state1, const robot_state::RobotState &state2, const AllowedCollisionMatrix &acm) const
 Check for self collision. Allowed collisions specified by the allowed collision matrix are taken into account. More...
 
 CollisionRobotFCL (const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
 
 CollisionRobotFCL (const CollisionRobotFCL &other)
 
virtual void distanceOther (const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
 The distance to self-collision given the robot is at state state. More...
 
virtual void distanceSelf (const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const override
 The distance to self-collision given the robot is at state state. More...
 
- Public Member Functions inherited from collision_detection::CollisionRobot
 CollisionRobot (const robot_model::RobotModelConstPtr &model, double padding=0.0, double scale=1.0)
 Constructor. More...
 
 CollisionRobot (const CollisionRobot &other)
 A copy constructor. More...
 
double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
 The distance to another robot instance. More...
 
double distanceOther (const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix &acm) const
 The distance to another robot instance, ignoring distances between links that are allowed to always collide. More...
 
double distanceSelf (const robot_state::RobotState &state) const
 The distance to self-collision given the robot is at state state. More...
 
double distanceSelf (const robot_state::RobotState &state, const AllowedCollisionMatrix &acm) const
 The distance to self-collision given the robot is at state state, ignoring the distances between links that are allowed to always collide (as specified by acm) More...
 
double getLinkPadding (const std::string &link_name) const
 Get the link padding for a particular link. More...
 
const std::map< std::string, double > & getLinkPadding () const
 Get the link paddings as a map (from link names to padding value) More...
 
double getLinkScale (const std::string &link_name) const
 Set the scaling for a particular link. More...
 
const std::map< std::string, double > & getLinkScale () const
 Get the link scaling as a map (from link names to scale value) More...
 
void getPadding (std::vector< moveit_msgs::LinkPadding > &padding) const
 Get the link padding as a vector of messages. More...
 
const robot_model::RobotModelConstPtr & getRobotModel () const
 The kinematic model corresponding to this collision model. More...
 
void getScale (std::vector< moveit_msgs::LinkScale > &scale) const
 Get the link scaling as a vector of messages. More...
 
void setLinkPadding (const std::string &link_name, double padding)
 Set the link padding for a particular link. More...
 
void setLinkPadding (const std::map< std::string, double > &padding)
 Set the link paddings using a map (from link names to padding value) More...
 
void setLinkScale (const std::string &link_name, double scale)
 Set the scaling for a particular link. More...
 
void setLinkScale (const std::map< std::string, double > &scale)
 Set the link scaling using a map (from link names to scale value) More...
 
void setPadding (double padding)
 Set the link padding (for every link) More...
 
void setPadding (const std::vector< moveit_msgs::LinkPadding > &padding)
 Set the link padding from a vector of messages. More...
 
void setScale (double scale)
 Set the link scaling (for every link) More...
 
void setScale (const std::vector< moveit_msgs::LinkScale > &scale)
 Set the link scaling from a vector of messages. More...
 
virtual ~CollisionRobot ()
 

Protected Attributes

CollisionRobotDistanceFieldPtr crobot_distance_
 
- Protected Attributes inherited from collision_detection::CollisionRobotFCL
std::vector< FCLCollisionObjectConstPtrfcl_objs_
 
std::vector< FCLGeometryConstPtr > geoms_
 
- Protected Attributes inherited from collision_detection::CollisionRobot
std::map< std::string, double > link_padding_
 The internally maintained map (from link names to padding) More...
 
std::map< std::string, double > link_scale_
 The internally maintained map (from link names to scaling) More...
 
robot_model::RobotModelConstPtr robot_model_
 The kinematic model corresponding to this collision model. More...
 

Additional Inherited Members

- Protected Member Functions inherited from collision_detection::CollisionRobotFCL
void allocSelfCollisionBroadPhase (const robot_state::RobotState &state, FCLManager &manager) const
 
void checkOtherCollisionHelper (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
 
void checkSelfCollisionHelper (const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
 
void constructFCLObject (const robot_state::RobotState &state, FCLObject &fcl_obj) const
 
void getAttachedBodyObjects (const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
 
virtual void updatedPaddingOrScaling (const std::vector< std::string > &links)
 When the scale or padding is changed for a set of links by any of the functions in this class, updatedPaddingOrScaling() function is called. This function has an empty default implementation. The intention is to override this function in a derived class to allow for updating additional structures that may need such updating when link scale or padding changes. More...
 

Detailed Description

Definition at line 49 of file collision_robot_hybrid.h.

Constructor & Destructor Documentation

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

Definition at line 41 of file collision_robot_hybrid.cpp.

collision_detection::CollisionRobotHybrid::CollisionRobotHybrid ( const robot_model::RobotModelConstPtr &  kmodel,
const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions,
double  size_x = 3.0,
double  size_y = 3.0,
double  size_z = 4.0,
bool  use_signed_distance_field = false,
double  resolution = .02,
double  collision_tolerance = 0.0,
double  max_propogation_distance = .25,
double  padding = 0.0,
double  scale = 1.0 
)

Definition at line 46 of file collision_robot_hybrid.cpp.

collision_detection::CollisionRobotHybrid::CollisionRobotHybrid ( const CollisionRobotHybrid other)

Definition at line 58 of file collision_robot_hybrid.cpp.

Member Function Documentation

void collision_detection::CollisionRobotHybrid::checkSelfCollisionDistanceField ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const robot_state::RobotState state 
) const

Definition at line 64 of file collision_robot_hybrid.cpp.

void collision_detection::CollisionRobotHybrid::checkSelfCollisionDistanceField ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const robot_state::RobotState state,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 71 of file collision_robot_hybrid.cpp.

void collision_detection::CollisionRobotHybrid::checkSelfCollisionDistanceField ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const robot_state::RobotState state,
const collision_detection::AllowedCollisionMatrix acm 
) const

Definition at line 79 of file collision_robot_hybrid.cpp.

void collision_detection::CollisionRobotHybrid::checkSelfCollisionDistanceField ( const collision_detection::CollisionRequest req,
collision_detection::CollisionResult res,
const robot_state::RobotState state,
const collision_detection::AllowedCollisionMatrix acm,
GroupStateRepresentationPtr &  gsr 
) const

Definition at line 87 of file collision_robot_hybrid.cpp.

const CollisionRobotDistanceFieldConstPtr collision_detection::CollisionRobotHybrid::getCollisionRobotDistanceField ( ) const
inline

Definition at line 90 of file collision_robot_hybrid.h.

void collision_detection::CollisionRobotHybrid::initializeRobotDistanceField ( const std::map< std::string, std::vector< CollisionSphere >> &  link_body_decompositions,
double  size_x,
double  size_y,
double  size_z,
bool  use_signed_distance_field,
double  resolution,
double  collision_tolerance,
double  max_propogation_distance 
)
inline

Definition at line 65 of file collision_robot_hybrid.h.

Member Data Documentation

CollisionRobotDistanceFieldPtr collision_detection::CollisionRobotHybrid::crobot_distance_
protected

Definition at line 96 of file collision_robot_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 Wed Jul 10 2019 04:03:05