#include <urdf_geometry_parser.h>
|
bool | getDistanceBetweenJoints (const std::string &first_joint_name, const std::string &second_joint_name, double &distance) |
| Get distance between two joints from the URDF. More...
|
|
bool | getJointRadius (const std::string &joint_name, double &radius) |
| Get joint radius from the URDF. More...
|
|
bool | getJointSteeringLimits (const std::string &joint_name, double &steering_limit) |
| Get joint steering limit from the URDF considering the upper and lower limit is the same. More...
|
|
bool | getTransformVector (const std::string &joint_name, const std::string &parent_link_name, urdf::Vector3 &transform_vector) |
| Get transform vector between the joint and parent_link. More...
|
|
| UrdfGeometryParser (ros::NodeHandle &root_nh, const std::string &base_link) |
|
Definition at line 45 of file urdf_geometry_parser.h.
urdf_geometry_parser::UrdfGeometryParser::UrdfGeometryParser |
( |
ros::NodeHandle & |
root_nh, |
|
|
const std::string & |
base_link |
|
) |
| |
bool urdf_geometry_parser::UrdfGeometryParser::getDistanceBetweenJoints |
( |
const std::string & |
first_joint_name, |
|
|
const std::string & |
second_joint_name, |
|
|
double & |
distance |
|
) |
| |
Get distance between two joints from the URDF.
- Parameters
-
first_joint_name | Name of the first joint |
second_joint_name | Name of the second joint |
distance | Distance in meter between first and second joint |
- Returns
- true if the distance was found; false otherwise
Definition at line 145 of file urdf_geometry_parser.cpp.
bool urdf_geometry_parser::UrdfGeometryParser::getJointRadius |
( |
const std::string & |
joint_name, |
|
|
double & |
radius |
|
) |
| |
Get joint radius from the URDF.
- Parameters
-
joint_name | Name of the joint |
distance | Distance in meter between first and second joint |
- Returns
- true if the radius was found; false otherwise
Definition at line 163 of file urdf_geometry_parser.cpp.
bool urdf_geometry_parser::UrdfGeometryParser::getJointSteeringLimits |
( |
const std::string & |
joint_name, |
|
|
double & |
steering_limit |
|
) |
| |
Get joint steering limit from the URDF considering the upper and lower limit is the same.
- Parameters
-
joint_name | Name of the joint |
steering_limit | [rad] |
- Returns
- true if the steering limit was found; false otherwise
Definition at line 181 of file urdf_geometry_parser.cpp.
bool urdf_geometry_parser::UrdfGeometryParser::getTransformVector |
( |
const std::string & |
joint_name, |
|
|
const std::string & |
parent_link_name, |
|
|
urdf::Vector3 & |
transform_vector |
|
) |
| |
Get transform vector between the joint and parent_link.
- Parameters
-
[in] | joint_name | Child joint_name from where to begin |
[in] | parent_link_name | Name of link to find as parent of the joint |
[out] | transform_vector | Distance vector between joint and parent_link [m] |
- Returns
- true if the transform vector was found; false otherwise
Definition at line 113 of file urdf_geometry_parser.cpp.
std::string urdf_geometry_parser::UrdfGeometryParser::base_link_ |
|
private |
urdf::ModelInterfaceSharedPtr urdf_geometry_parser::UrdfGeometryParser::model_ |
|
private |
The documentation for this class was generated from the following files: