Public Member Functions | Private Attributes
urdf_vehicle_kinematic::UrdfVehicleKinematic Class Reference

#include <urdf_vehicle_kinematic.h>

List of all members.

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_

Detailed Description

Definition at line 10 of file urdf_vehicle_kinematic.h.


Constructor & Destructor Documentation

urdf_vehicle_kinematic::UrdfVehicleKinematic::UrdfVehicleKinematic ( ros::NodeHandle root_nh,
const std::string &  base_link 
)

Definition at line 64 of file urdf_vehicle_kinematic.cpp.


Member Function Documentation

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.

Parameters:
first_joint_nameName of the first joint
second_joint_nameName of the second joint
distanceDistance 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.

Parameters:
joint_nameName of the joint
distanceDistance 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.

Parameters:
joint_nameName 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.

Parameters:
[in]joint_nameChild joint_name from where to begin
[in]parent_link_nameName of link to find as parent of the joint
[out]transform_vectorDistance vector between joint and parent_link [m]
Returns:
true if the transform vector was found; false otherwise

Definition at line 83 of file urdf_vehicle_kinematic.cpp.


Member Data Documentation

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.


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


urdf_vehicle_kinematic
Author(s): Vincent Rousseau
autogenerated on Sat Jun 8 2019 20:06:17