Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Parse URDF continuous joint effort/velocity limits #684

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 4 additions & 8 deletions src/parser_urdf.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3016,10 +3016,6 @@ void CreateJoint(TiXmlElement *_root,
Values2str(1, &_link->parent_joint->limits->lower));
AddKeyValue(jointAxisLimit, "upper",
Values2str(1, &_link->parent_joint->limits->upper));
AddKeyValue(jointAxisLimit, "effort",
Values2str(1, &_link->parent_joint->limits->effort));
AddKeyValue(jointAxisLimit, "velocity",
Values2str(1, &_link->parent_joint->limits->velocity));
}
else if (_link->parent_joint->type != urdf::Joint::CONTINUOUS)
{
Expand All @@ -3041,11 +3037,11 @@ void CreateJoint(TiXmlElement *_root,
Values2str(1, &_link->parent_joint->limits->lower));
AddKeyValue(jointAxisLimit, "upper",
Values2str(1, &_link->parent_joint->limits->upper));
AddKeyValue(jointAxisLimit, "effort",
Values2str(1, &_link->parent_joint->limits->effort));
AddKeyValue(jointAxisLimit, "velocity",
Values2str(1, &_link->parent_joint->limits->velocity));
}
AddKeyValue(jointAxisLimit, "effort",
Values2str(1, &_link->parent_joint->limits->effort));
AddKeyValue(jointAxisLimit, "velocity",
Values2str(1, &_link->parent_joint->limits->velocity));
}
}

Expand Down
7 changes: 7 additions & 0 deletions test/integration/urdf_joint_parameters.cc
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,13 @@ TEST(SDFParser, JointAxisParameters)
ASSERT_TRUE(dynamics->HasElement("friction"));
EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("damping"));
EXPECT_DOUBLE_EQ(value, dynamics->Get<double>("friction"));

EXPECT_TRUE(axis->HasElement("limit"));
sdf::ElementPtr limit = axis->GetElement("limit");
EXPECT_TRUE(limit->HasElement("effort"));
EXPECT_TRUE(limit->HasElement("velocity"));
EXPECT_DOUBLE_EQ(value, limit->Get<double>("effort"));
EXPECT_DOUBLE_EQ(value, limit->Get<double>("velocity"));
}
EXPECT_EQ(bitmask, 0x3u);

Expand Down
2 changes: 2 additions & 0 deletions test/integration/urdf_joint_parameters.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<parent link="world"/>
<child link="link0"/>
<dynamics damping="0.0" friction="0.0" />
<limit effort="0.0" velocity="0.0" />
</joint>

<link name="link0">
Expand All @@ -31,6 +32,7 @@
<parent link="link0"/>
<child link="link1"/>
<dynamics damping="1.0" friction="1.0" />
<limit effort="1.0" velocity="1.0" />
</joint>

<link name="link1">
Expand Down