#include <link_to_collision.hpp>
|
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 () |
|
Definition at line 47 of file link_to_collision.hpp.
LinkToCollision::LinkToCollision |
( |
| ) |
|
LinkToCollision::~LinkToCollision |
( |
| ) |
|
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_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(..).
- Parameters
-
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. |
- 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_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. |
- 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_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. |
- Returns
- State of success.
Definition at line 120 of file link_to_collision.cpp.
MapSelfCollisions_t::iterator LinkToCollision::getSelfCollisionsIterBegin |
( |
| ) |
|
|
inline |
MapSelfCollisions_t::iterator LinkToCollision::getSelfCollisionsIterEnd |
( |
| ) |
|
|
inline |
bool LinkToCollision::ignoreSelfCollisionPart |
( |
const std::string & |
link_of_interest, |
|
|
const std::string & |
self_collision_obstacle_link |
|
) |
| |
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_id | The id of the root frame as base for further transformations. |
urdf_file_name | The 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_id | The id of the root frame as base for further transformations. |
urdf_param | The ROS parameter containing the URDF description. |
- Returns
- State of success.
Definition at line 71 of file link_to_collision.cpp.
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_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" |
- Returns
- State of success.
Definition at line 79 of file link_to_collision.cpp.
Convert a pose object from URDF into a pose msg object.
- Parameters
-
urdf_pose | Pose from URDF. |
msg_pose | Pose expressed as message. |
Definition at line 36 of file link_to_collision.cpp.
std::string LinkToCollision::root_frame_id_ |
|
private |
std::unordered_map<std::string, std::vector<std::string> > LinkToCollision::self_collision_map_ |
|
private |
bool LinkToCollision::success_ |
|
private |
The documentation for this class was generated from the following files: