#include <urdf_vehicle_kinematic.h>
| Public Member Functions | |
| bool | getDistanceBetweenJoints (const std::string &first_joint_name, const std::string &second_joint_name, double &distance) | 
| Get distance between two joints from the URDF. | |
| bool | getJointRadius (const std::string &joint_name, double &radius) | 
| Get joint radius from the URDF. | |
| 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. | |
| 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. | |
| UrdfVehicleKinematic (ros::NodeHandle &root_nh, const std::string &base_link) | |
| Private Attributes | |
| std::string | base_link_ | 
| boost::shared_ptr < urdf::ModelInterface > | model_ | 
Definition at line 10 of file urdf_vehicle_kinematic.h.
| urdf_vehicle_kinematic::UrdfVehicleKinematic::UrdfVehicleKinematic | ( | ros::NodeHandle & | root_nh, | 
| const std::string & | base_link | ||
| ) | 
Definition at line 64 of file urdf_vehicle_kinematic.cpp.
| bool urdf_vehicle_kinematic::UrdfVehicleKinematic::getDistanceBetweenJoints | ( | const std::string & | first_joint_name, | 
| const std::string & | second_joint_name, | ||
| double & | distance | ||
| ) | 
Get distance between two joints from the URDF.
| 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 | 
Definition at line 115 of file urdf_vehicle_kinematic.cpp.
| bool urdf_vehicle_kinematic::UrdfVehicleKinematic::getJointRadius | ( | const std::string & | joint_name, | 
| double & | radius | ||
| ) | 
Get joint radius from the URDF.
| joint_name | Name of the joint | 
| distance | Distance in meter between first and second joint | 
Definition at line 134 of file urdf_vehicle_kinematic.cpp.
| bool urdf_vehicle_kinematic::UrdfVehicleKinematic::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.
| joint_name | Name of the joint | 
| steering_limit | [rad] | 
Definition at line 152 of file urdf_vehicle_kinematic.cpp.
| bool urdf_vehicle_kinematic::UrdfVehicleKinematic::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.
| [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] | 
Definition at line 83 of file urdf_vehicle_kinematic.cpp.
| std::string urdf_vehicle_kinematic::UrdfVehicleKinematic::base_link_  [private] | 
Definition at line 53 of file urdf_vehicle_kinematic.h.
| boost::shared_ptr<urdf::ModelInterface> urdf_vehicle_kinematic::UrdfVehicleKinematic::model_  [private] | 
Definition at line 55 of file urdf_vehicle_kinematic.h.