Skip to content

Commit

Permalink
Parse URDF continuous joint effort/velocity limits
Browse files Browse the repository at this point in the history
Fixes gazebosim#683.

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters committed Sep 2, 2021
1 parent 75e4226 commit 33e4b4d
Showing 1 changed file with 4 additions and 8 deletions.
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

0 comments on commit 33e4b4d

Please sign in to comment.