56 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision description. Add collision description for link to urdf.");
60 if (!link->collision->geometry)
62 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have collision geometry description. Add collision geometry description for link to urdf.");
66 if (link->collision->geometry->type != urdf::Geometry::CYLINDER)
68 ROS_ERROR_STREAM(
"Link " << link->name <<
" does not have cylinder geometry");
81 static bool getWheelRadius(urdf::LinkConstSharedPtr wheel_link,
double& wheel_radius)
85 ROS_ERROR_STREAM(
"Wheel link " << wheel_link->name <<
" is NOT modeled as a cylinder!");
89 wheel_radius = (
static_cast<urdf::Cylinder*
>(wheel_link->collision->geometry.get()))->radius;
98 const std::string model_param_name =
"robot_description";
99 bool res = root_nh.
hasParam(model_param_name);
100 std::string robot_model_str=
"";
101 if (!res || !root_nh.
getParam(model_param_name,robot_model_str))
103 ROS_ERROR(
"Robot descripion couldn't be retrieved from param server.");
107 model_ = urdf::parseURDF(robot_model_str);
109 ROS_ERROR_STREAM(
"Could not parse the urdf robot model "<<model_param_name);
114 , urdf::Vector3 &transform_vector)
118 urdf::JointConstSharedPtr joint(
model_->getJoint(joint_name));
122 <<
" couldn't be retrieved from model description");
126 transform_vector = joint->parent_to_joint_origin_transform.position;
127 while(joint->parent_link_name != parent_link_name)
129 urdf::LinkConstSharedPtr link_parent(
model_->getLink(joint->parent_link_name));
130 if (!link_parent || !link_parent->parent_joint)
133 <<
" couldn't be retrieved from model description or his parent joint");
136 joint = link_parent->parent_joint;
137 transform_vector = transform_vector + joint->parent_to_joint_origin_transform.position;
146 const std::string& second_joint_name,
149 urdf::Vector3 first_transform;
153 urdf::Vector3 second_transform;
158 distance = std::sqrt(std::pow(first_transform.x - second_transform.x, 2)
159 + std::pow(first_transform.y - second_transform.y, 2));
168 urdf::JointConstSharedPtr joint(
model_->getJoint(joint_name));
182 double& steering_limit)
186 urdf::JointConstSharedPtr joint(
model_->getJoint(joint_name));
187 if(joint->type == urdf::Joint::REVOLUTE)
189 const double lower_steering_limit = fabs(joint->limits->lower);
190 const double upper_steering_limit = fabs(joint->limits->upper);
191 if(lower_steering_limit > upper_steering_limit)
192 steering_limit = upper_steering_limit;
194 steering_limit = lower_steering_limit;
195 ROS_DEBUG_STREAM(
"Joint "<<joint_name<<
" steering limit is "<<steering_limit*180.0/M_PI<<
" in degrees");
198 ROS_ERROR_STREAM(
"Couldn't get joint "<<joint_name<<
" steering limit, is it of type REVOLUTE ?");
static bool getWheelRadius(urdf::LinkConstSharedPtr wheel_link, double &wheel_radius)
static bool isCylinder(urdf::LinkConstSharedPtr &link)
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.
urdf::ModelInterfaceSharedPtr model_
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...
#define ROS_DEBUG_STREAM(args)
UrdfGeometryParser(ros::NodeHandle &root_nh, const std::string &base_link)
bool getJointRadius(const std::string &joint_name, double &radius)
Get joint radius from the URDF.
bool getParam(const std::string &key, std::string &s) const
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 hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)