#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 boost::shared_ptr < urdf::Box > | PtrBox_t |
| typedef boost::shared_ptr < urdf::Collision > | PtrCollision_t |
| typedef boost::shared_ptr < const urdf::Link > | PtrConstLink_t |
| typedef boost::shared_ptr < urdf::Cylinder > | PtrCylinder_t |
| typedef boost::shared_ptr < urdf::Geometry > | PtrGeometry_t |
| typedef boost::shared_ptr < urdf::Link > | PtrLink_t |
| typedef boost::shared_ptr < urdf::Mesh > | PtrMesh_t |
| typedef boost::shared_ptr < urdf::Sphere > | PtrSphere_t |
| typedef std::vector < boost::shared_ptr < urdf::Link > > | VecPtrLink_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 | |
| 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_ |
Definition at line 47 of file link_to_collision.hpp.
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 boost::shared_ptr<urdf::Box> LinkToCollision::PtrBox_t [private] |
Definition at line 56 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Collision> LinkToCollision::PtrCollision_t [private] |
Definition at line 53 of file link_to_collision.hpp.
typedef boost::shared_ptr<const urdf::Link> LinkToCollision::PtrConstLink_t [private] |
Definition at line 50 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Cylinder> LinkToCollision::PtrCylinder_t [private] |
Definition at line 58 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Geometry> LinkToCollision::PtrGeometry_t [private] |
Definition at line 54 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Link> LinkToCollision::PtrLink_t [private] |
Definition at line 51 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Mesh> LinkToCollision::PtrMesh_t [private] |
Definition at line 55 of file link_to_collision.hpp.
typedef boost::shared_ptr<urdf::Sphere> LinkToCollision::PtrSphere_t [private] |
Definition at line 57 of file link_to_collision.hpp.
typedef std::vector<boost::shared_ptr<urdf::Link> > LinkToCollision::VecPtrLink_t [private] |
Definition at line 52 of file link_to_collision.hpp.
Definition at line 26 of file link_to_collision.cpp.
Definition at line 31 of file link_to_collision.cpp.
| 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.
| link_of_interest | The name of the link of interest. |
| pose | The pose of the frame (root of the frame). |
| col | The color. |
| geometry | A pointer to a URDF geometry object. |
| segment_of_interest_marker_shape | The 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(..).
| shape_type | The type of the shape (visualization_marker types). |
| abs_pos | The absolute position (from root frame) of the shape. |
| quat_pos | The orientation (from root frame) of the shape. |
| link_of_interest | The name of the link of interest (e.g. link name if shape_type MESH_RESOURCE else only for id). |
| segment_of_interest_marker_shape | The pointer for that a marker shape shall be created. |
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).
| shape_type | The type of the shape (visualization_marker types). |
| pose | The pose of the shape (with respect to the root_frame). |
| link_of_interest | The name of the link of interest (e.g. link name if shape_type MESH_RESOURCE else only for id). |
| segment_of_interest_marker_shape | The pointer for that a marker shape shall be created. |
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.
| abs_pos | The absolute position (from root frame) of the shape. |
| quat_pos | The orientation (from root frame) of the shape. |
| link_of_interest | The name of the link of interest. |
| segment_of_interest_marker_shape | The pointer for that a marker shape shall be created. |
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.
| root_frame_id | The id of the root frame as base for further transformations. |
| urdf_file_name | The URDF file name (containing path). |
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.
| root_frame_id | The id of the root frame as base for further transformations. |
| urdf_param | The ROS parameter containing the URDF description. |
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.
| self_collision_params | A XML RPC data structure representing the self_collision params (from YAML or parameter server) |
| sm | The shapes manager that will by extended by self-collision "obstacles" |
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.
| urdf_pose | Pose from URDF. |
| msg_pose | Pose expressed as message. |
Definition at line 36 of file link_to_collision.cpp.
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.