Go to the documentation of this file.00001 #ifndef URDF_VEHICLE_KINEMATIC_H
00002 #define URDF_VEHICLE_KINEMATIC_H
00003
00004 #include <ros/ros.h>
00005
00006 #include <urdf_parser/urdf_parser.h>
00007
00008 namespace urdf_vehicle_kinematic {
00009
00010 class UrdfVehicleKinematic {
00011
00012 public:
00013 UrdfVehicleKinematic(ros::NodeHandle& root_nh, const std::string &base_link);
00014
00022 bool getTransformVector(const std::string& joint_name,
00023 const std::string& parent_link_name,
00024 urdf::Vector3& transform_vector);
00025
00032 bool getDistanceBetweenJoints(const std::string& first_joint_name,
00033 const std::string& second_joint_name,
00034 double& distance);
00035
00041 bool getJointRadius(const std::string& joint_name,
00042 double& radius);
00043
00050 bool getJointSteeringLimits(const std::string& joint_name,
00051 double& steering_limit);
00052 private:
00053 std::string base_link_;
00054
00055 boost::shared_ptr<urdf::ModelInterface> model_;
00056 };
00057
00058 }
00059
00060 #endif