42 #include <urdf_model/model.h>
43 #include <urdf_parser/urdf_parser.h>
45 #include <kdl/frames_io.hpp>
51 #define ROS_DEBUG(...) fprintf(stdout, __VA_ARGS__);
52 #define ROS_ERROR(...) fprintf(stderr, __VA_ARGS__);
53 #define ROS_WARN(...) fprintf(stderr, __VA_ARGS__);
58 #include <urdf/urdfdom_compatibility.h>
64 KDL::Vector
toKdl(urdf::Vector3 v)
66 return KDL::Vector(v.x, v.y, v.z);
70 KDL::Rotation
toKdl(urdf::Rotation r)
72 return KDL::Rotation::Quaternion(r.x, r.y, r.z, r.w);
78 return KDL::Frame(
toKdl(p.rotation),
toKdl(p.position));
82 KDL::Joint
toKdl(urdf::JointSharedPtr jnt)
84 KDL::Frame F_parent_jnt =
toKdl(jnt->parent_to_joint_origin_transform);
87 case urdf::Joint::FIXED: {
88 return KDL::Joint(jnt->name, KDL::Joint::None);
90 case urdf::Joint::REVOLUTE: {
91 KDL::Vector axis =
toKdl(jnt->axis);
92 return KDL::Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, KDL::Joint::RotAxis);
94 case urdf::Joint::CONTINUOUS: {
95 KDL::Vector axis =
toKdl(jnt->axis);
96 return KDL::Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, KDL::Joint::RotAxis);
98 case urdf::Joint::PRISMATIC: {
99 KDL::Vector axis =
toKdl(jnt->axis);
100 return KDL::Joint(jnt->name, F_parent_jnt.p, F_parent_jnt.M * axis, KDL::Joint::TransAxis);
103 ROS_WARN(
"Converting unknown joint type of joint '%s' into a fixed joint", jnt->name.c_str());
104 return KDL::Joint(jnt->name, KDL::Joint::None);
111 KDL::RigidBodyInertia
toKdl(urdf::InertialSharedPtr i)
113 KDL::Frame origin =
toKdl(i->origin);
116 double kdl_mass = i->mass;
119 KDL::Vector kdl_com = origin.p;
123 KDL::RotationalInertia urdf_inertia =
124 KDL::RotationalInertia(i->ixx, i->iyy, i->izz, i->ixy, i->ixz, i->iyz);
128 KDL::RigidBodyInertia kdl_inertia_wrt_com_workaround =
129 origin.M * KDL::RigidBodyInertia(0, KDL::Vector::Zero(), urdf_inertia);
134 KDL::RotationalInertia kdl_inertia_wrt_com =
135 kdl_inertia_wrt_com_workaround.getRotationalInertia();
137 return KDL::RigidBodyInertia(kdl_mass, kdl_com, kdl_inertia_wrt_com);
144 std::vector<urdf::LinkSharedPtr> children = root->child_links;
145 ROS_DEBUG(
"Link %s had %zu children", root->name.c_str(), children.size());
148 KDL::RigidBodyInertia inert(0);
149 if (root->inertial) {
150 inert =
toKdl(root->inertial);
154 KDL::Joint jnt =
toKdl(root->parent_joint);
157 KDL::Segment sgm(root->name, jnt,
toKdl(
158 root->parent_joint->parent_to_joint_origin_transform), inert);
161 tree.addSegment(sgm, root->parent_joint->parent_link_name);
164 for (
size_t i = 0; i < children.size(); i++) {
174 const urdf::ModelInterfaceSharedPtr robot_model = urdf::parseURDFFile(file);
181 #if defined(HAS_ROS) && defined(HAS_URDF)
184 ROS_ERROR(
"Could not generate robot model");
196 const urdf::ModelInterfaceSharedPtr robot_model = urdf::parseURDF(xml);
198 ROS_ERROR(
"Could not generate robot model");
204 bool treeFromXml(
const tinyxml2::XMLDocument * xml_doc, KDL::Tree & tree)
207 ROS_ERROR(
"Could not parse the xml document");
211 tinyxml2::XMLPrinter printer;
212 xml_doc->Print(&printer);
220 ROS_ERROR(
"Could not parse the xml document");
224 std::stringstream ss;
232 if (!robot_model.getRoot()) {
236 tree = KDL::Tree(robot_model.getRoot()->name);
239 if (robot_model.getRoot()->inertial) {
240 ROS_WARN(
"The root link %s has an inertia specified in the URDF, but KDL does not "
241 "support a root link with an inertia. As a workaround, you can add an extra "
242 "dummy link to your URDF.", robot_model.getRoot()->name.c_str());
246 for (
size_t i = 0; i < robot_model.getRoot()->child_links.size(); i++) {