Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
LinkToCollision Class Reference

#include <link_to_collision.hpp>

Public Types

typedef std::unordered_map< std::string, std::vector< std::string > > MapSelfCollisions_t
 

Public Member Functions

bool getMarkerShapeFromType (const uint32_t &shape_type, const Eigen::Vector3d &abs_pos, const Eigen::Quaterniond &quat_pos, const std::string &link_of_interest, const Eigen::Vector3d &dimension, PtrIMarkerShape_t &segment_of_interest_marker_shape)
 
bool getMarkerShapeFromType (const uint32_t &shape_type, const geometry_msgs::Pose &pose, const std::string &link_of_interest, const Eigen::Vector3d &dimension, PtrIMarkerShape_t &segment_of_interest_marker_shape)
 
bool getMarkerShapeFromUrdf (const Eigen::Vector3d &abs_pos, const Eigen::Quaterniond &quat_pos, const std::string &link_of_interest, PtrIMarkerShape_t &segment_of_interest_marker_shape)
 
MapSelfCollisions_t::iterator getSelfCollisionsIterBegin ()
 
MapSelfCollisions_t::iterator getSelfCollisionsIterEnd ()
 
bool ignoreSelfCollisionPart (const std::string &link_of_interest, const std::string &self_collision_obstacle_link)
 
bool initFile (const std::string &root_frame_id, const std::string &urdf_file_name)
 
bool initParameter (const std::string &root_frame_id, const std::string &urdf_param)
 
bool initSelfCollision (XmlRpc::XmlRpcValue &self_collision_params, boost::scoped_ptr< ShapesManager > &sm)
 
 LinkToCollision ()
 
 ~LinkToCollision ()
 

Private Types

typedef std::unordered_map< std::string, std::vector< std::string > >::iterator MapIter_t
 
typedef urdf::BoxSharedPtr PtrBox_t
 
typedef urdf::CollisionSharedPtr PtrCollision_t
 
typedef urdf::LinkConstSharedPtr PtrConstLink_t
 
typedef urdf::CylinderSharedPtr PtrCylinder_t
 
typedef urdf::GeometrySharedPtr PtrGeometry_t
 
typedef urdf::LinkSharedPtr PtrLink_t
 
typedef urdf::MeshSharedPtr PtrMesh_t
 
typedef urdf::SphereSharedPtr PtrSphere_t
 
typedef std::vector< PtrLink_tVecPtrLink_t
 

Private Member Functions

void createSpecificMarkerShape (const std::string &link_of_interest, const geometry_msgs::Pose &pose, const std_msgs::ColorRGBA &col, const PtrGeometry_t &geometry, PtrIMarkerShape_t &segment_of_interest_marker_shape)
 first: link to be considered 'obstacle', second: links of component to be considered for self-collision checking More...
 
void poseURDFToMsg (const urdf::Pose &urdf_pose, geometry_msgs::Pose &msg_pose)
 

Private Attributes

urdf::Model model_
 
std::string root_frame_id_
 
std::unordered_map< std::string, std::vector< std::string > > self_collision_map_
 
bool success_
 

Detailed Description

Definition at line 47 of file link_to_collision.hpp.

Member Typedef Documentation

typedef std::unordered_map<std::string, std::vector<std::string> >::iterator LinkToCollision::MapIter_t
private

Definition at line 59 of file link_to_collision.hpp.

typedef std::unordered_map<std::string, std::vector<std::string> > LinkToCollision::MapSelfCollisions_t

Definition at line 89 of file link_to_collision.hpp.

typedef urdf::BoxSharedPtr LinkToCollision::PtrBox_t
private

Definition at line 56 of file link_to_collision.hpp.

typedef urdf::CollisionSharedPtr LinkToCollision::PtrCollision_t
private

Definition at line 53 of file link_to_collision.hpp.

typedef urdf::LinkConstSharedPtr LinkToCollision::PtrConstLink_t
private

Definition at line 50 of file link_to_collision.hpp.

typedef urdf::CylinderSharedPtr LinkToCollision::PtrCylinder_t
private

Definition at line 58 of file link_to_collision.hpp.

typedef urdf::GeometrySharedPtr LinkToCollision::PtrGeometry_t
private

Definition at line 54 of file link_to_collision.hpp.

typedef urdf::LinkSharedPtr LinkToCollision::PtrLink_t
private

Definition at line 51 of file link_to_collision.hpp.

typedef urdf::MeshSharedPtr LinkToCollision::PtrMesh_t
private

Definition at line 55 of file link_to_collision.hpp.

typedef urdf::SphereSharedPtr LinkToCollision::PtrSphere_t
private

Definition at line 57 of file link_to_collision.hpp.

typedef std::vector<PtrLink_t> LinkToCollision::VecPtrLink_t
private

Definition at line 52 of file link_to_collision.hpp.

Constructor & Destructor Documentation

LinkToCollision::LinkToCollision ( )

Definition at line 26 of file link_to_collision.cpp.

LinkToCollision::~LinkToCollision ( )

Definition at line 31 of file link_to_collision.cpp.

Member Function Documentation

void LinkToCollision::createSpecificMarkerShape ( const std::string &  link_of_interest,
const geometry_msgs::Pose pose,
const std_msgs::ColorRGBA &  col,
const PtrGeometry_t geometry,
PtrIMarkerShape_t segment_of_interest_marker_shape 
)
private

first: link to be considered 'obstacle', second: links of component to be considered for self-collision checking

Private method to create a specific marker shape for the output pointer.

Parameters
link_of_interestThe name of the link of interest.
poseThe pose of the frame (root of the frame).
colThe color.
geometryA pointer to a URDF geometry object.
segment_of_interest_marker_shapeThe pointer for that a marker shape shall be created.

Definition at line 181 of file link_to_collision.cpp.

bool LinkToCollision::getMarkerShapeFromType ( const uint32_t &  shape_type,
const Eigen::Vector3d &  abs_pos,
const Eigen::Quaterniond &  quat_pos,
const std::string &  link_of_interest,
const Eigen::Vector3d &  dimension,
PtrIMarkerShape_t segment_of_interest_marker_shape 
)

Tries to create a MarkerShape by a given shape_type. If shape_type is MESH_RESOURCE then the behaviour is similar to getMarkerShapeFromUrdf(..).

Parameters
shape_typeThe type of the shape (visualization_marker types).
abs_posThe absolute position (from root frame) of the shape.
quat_posThe orientation (from root frame) of the shape.
link_of_interestThe name of the link of interest (e.g. link name if shape_type MESH_RESOURCE else only for id).
segment_of_interest_marker_shapeThe pointer for that a marker shape shall be created.
Returns
State of success.

Definition at line 240 of file link_to_collision.cpp.

bool LinkToCollision::getMarkerShapeFromType ( const uint32_t &  shape_type,
const geometry_msgs::Pose pose,
const std::string &  link_of_interest,
const Eigen::Vector3d &  dimension,
PtrIMarkerShape_t segment_of_interest_marker_shape 
)

Tries to create a MarkerShape by a given shape_type (similar to above but with pose).

Parameters
shape_typeThe type of the shape (visualization_marker types).
poseThe pose of the shape (with respect to the root_frame).
link_of_interestThe name of the link of interest (e.g. link name if shape_type MESH_RESOURCE else only for id).
segment_of_interest_marker_shapeThe pointer for that a marker shape shall be created.
Returns
State of success.

Definition at line 258 of file link_to_collision.cpp.

bool LinkToCollision::getMarkerShapeFromUrdf ( const Eigen::Vector3d &  abs_pos,
const Eigen::Quaterniond &  quat_pos,
const std::string &  link_of_interest,
PtrIMarkerShape_t segment_of_interest_marker_shape 
)

Tries to find the given link_of_interest in the links parsed from URDF. According to the data there a MarkerShape is created and will be assigned to the pointer.

Parameters
abs_posThe absolute position (from root frame) of the shape.
quat_posThe orientation (from root frame) of the shape.
link_of_interestThe name of the link of interest.
segment_of_interest_marker_shapeThe pointer for that a marker shape shall be created.
Returns
State of success.

Definition at line 120 of file link_to_collision.cpp.

MapSelfCollisions_t::iterator LinkToCollision::getSelfCollisionsIterBegin ( )
inline

Definition at line 94 of file link_to_collision.hpp.

MapSelfCollisions_t::iterator LinkToCollision::getSelfCollisionsIterEnd ( )
inline

Definition at line 99 of file link_to_collision.hpp.

bool LinkToCollision::ignoreSelfCollisionPart ( const std::string &  link_of_interest,
const std::string &  self_collision_obstacle_link 
)

Definition at line 49 of file link_to_collision.cpp.

bool LinkToCollision::initFile ( const std::string &  root_frame_id,
const std::string &  urdf_file_name 
)

Initialize the FrameToCollision model by an URDF file.

Parameters
root_frame_idThe id of the root frame as base for further transformations.
urdf_file_nameThe URDF file name (containing path).
Returns
State of success.

Definition at line 63 of file link_to_collision.cpp.

bool LinkToCollision::initParameter ( const std::string &  root_frame_id,
const std::string &  urdf_param 
)

Initialize the FrameToCollision model by an ROS parameter containting the URDF description.

Parameters
root_frame_idThe id of the root frame as base for further transformations.
urdf_paramThe ROS parameter containing the URDF description.
Returns
State of success.

Definition at line 71 of file link_to_collision.cpp.

bool LinkToCollision::initSelfCollision ( XmlRpc::XmlRpcValue self_collision_params,
boost::scoped_ptr< ShapesManager > &  sm 
)

From the parameters self collision dictionary the keys are extracted as the self-collision "obstacles". While the values are the parts to be ignored for self-collision checking. Additionally the parts to be ignored are extended by the parent and child elements of the link corresponding to the key.

Parameters
self_collision_paramsA XML RPC data structure representing the self_collision params (from YAML or parameter server)
smThe shapes manager that will by extended by self-collision "obstacles"
Returns
State of success.

Definition at line 79 of file link_to_collision.cpp.

void LinkToCollision::poseURDFToMsg ( const urdf::Pose urdf_pose,
geometry_msgs::Pose msg_pose 
)
private

Convert a pose object from URDF into a pose msg object.

Parameters
urdf_posePose from URDF.
msg_posePose expressed as message.

Definition at line 36 of file link_to_collision.cpp.

Member Data Documentation

urdf::Model LinkToCollision::model_
private

Definition at line 61 of file link_to_collision.hpp.

std::string LinkToCollision::root_frame_id_
private

Definition at line 63 of file link_to_collision.hpp.

std::unordered_map<std::string, std::vector<std::string> > LinkToCollision::self_collision_map_
private

Definition at line 64 of file link_to_collision.hpp.

bool LinkToCollision::success_
private

Definition at line 62 of file link_to_collision.hpp.


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


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47