Bugfix: URDF inertia was not added to KDL::Segment, which ended up

always having zero mass and inertia. (Yet another case of default ctor
args standing in the way of development).
This commit is contained in:
rphilippsen 2009-10-30 18:51:30 +00:00
parent 1711b830da
commit 848abcdd20
1 changed files with 1 additions and 1 deletions

View File

@ -115,7 +115,7 @@ bool addChildrenToTree(boost::shared_ptr<const urdf::Link> root, Tree& tree)
Joint jnt = toKdl(root->parent_joint);
// construct the kdl segment
Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform));
Segment sgm(root->name, jnt, toKdl(root->parent_joint->parent_to_joint_origin_transform), inert);
// add segment to tree
tree.addSegment(sgm, root->parent_joint->parent_link_name);