diff --git a/include/urdf_geometry_parser/urdf_geometry_parser.h b/include/urdf_geometry_parser/urdf_geometry_parser.h index f4abb45..5291597 100644 --- a/include/urdf_geometry_parser/urdf_geometry_parser.h +++ b/include/urdf_geometry_parser/urdf_geometry_parser.h @@ -78,6 +78,24 @@ class UrdfGeometryParser { bool getJointRadius(const std::string& joint_name, double& radius); + /** + * \brief Get link collision geometry from the URDF + * \param link_name Name of the link + * \param geometry Geometry of the link + * \return true if the geometry was found; false otherwise + */ + bool getLinkCollisionGeometry(const std::string& link_name, + urdf::GeometrySharedPtr& geometry); + + /** + * \brief Get link visual geometry from the URDF + * \param link_name Name of the link + * \param geometry Geometry of the link + * \return true if the geometry was found; false otherwise + */ + bool getLinkVisualGeometry(const std::string& link_name, + urdf::GeometrySharedPtr& geometry); + /** * \brief Get joint steering limit from the URDF * considering the upper and lower limit is the same diff --git a/src/urdf_geometry_parser.cpp b/src/urdf_geometry_parser.cpp index c375673..e5bd9b0 100644 --- a/src/urdf_geometry_parser.cpp +++ b/src/urdf_geometry_parser.cpp @@ -53,19 +53,19 @@ namespace urdf_geometry_parser{ if (!link->collision) { - ROS_ERROR_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf."); + ROS_WARN_STREAM("Link " << link->name << " does not have collision description. Add collision description for link to urdf."); return false; } if (!link->collision->geometry) { - ROS_ERROR_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf."); + ROS_WARN_STREAM("Link " << link->name << " does not have collision geometry description. Add collision geometry description for link to urdf."); return false; } if (link->collision->geometry->type != urdf::Geometry::CYLINDER) { - ROS_ERROR_STREAM("Link " << link->name << " does not have cylinder geometry"); + ROS_WARN_STREAM("Link " << link->name << " does not have cylinder geometry"); return false; } @@ -82,7 +82,7 @@ namespace urdf_geometry_parser{ { if (!isCylinder(wheel_link)) { - ROS_ERROR_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!"); + ROS_WARN_STREAM("Wheel link " << wheel_link->name << " is NOT modeled as a cylinder!"); return false; } @@ -100,13 +100,13 @@ namespace urdf_geometry_parser{ std::string robot_model_str=""; if (!res || !root_nh.getParam(model_param_name,robot_model_str)) { - ROS_ERROR("Robot descripion couldn't be retrieved from param server."); + ROS_ERROR("Robot description couldn't be retrieved from param server."); } else { model_ = urdf::parseURDF(robot_model_str); if(!model_) - ROS_ERROR_STREAM("Could not parse the urdf robot model "<getLink(link_name)); + if (!link) + { + ROS_ERROR_STREAM(link_name << " couldn't be retrieved from model description"); + return false; + } + if (!link->collision) + { + ROS_WARN_STREAM("Link " << link_name << " does not have collision description"); + return false; + } + if (!link->collision->geometry) + { + ROS_WARN_STREAM("Link " << link_name << " does not have collision geometry description"); + return false; + } + geometry = link->collision->geometry; + return true; + } + else + return false; + } + + bool UrdfGeometryParser::getLinkVisualGeometry(const std::string& link_name, + urdf::GeometrySharedPtr& geometry) + { + if(model_) + { + urdf::LinkConstSharedPtr link(model_->getLink(link_name)); + if (!link) + { + ROS_ERROR_STREAM(link_name << " couldn't be retrieved from model description"); + return false; + } + if (!link->visual) + { + ROS_WARN_STREAM("Link " << link_name << " does not have visual description"); + return false; + } + if (!link->visual->geometry) + { + ROS_WARN_STREAM("Link " << link_name << " does not have visual geometry description"); + return false; + } + geometry = link->visual->geometry; + return true; + } + else + return false; + } + bool UrdfGeometryParser::getJointSteeringLimits(const std::string& joint_name, double& steering_limit) {