Skip to content
Snippets Groups Projects
Commit d9ac8d76 authored by Fabian Reister's avatar Fabian Reister
Browse files

Merge branch 'fix/urdf-prismatic-joint-limits' into 'master'

fix: URDF model loading: limits of prismatic joints are in [m] instead of [mm]

See merge request Simox/simox!102
parents e99f8499 95c62eb7
No related branches found
No related tags found
No related merge requests found
......@@ -445,11 +445,13 @@ namespace VirtualRobot
break;
case urdf::Joint::PRISMATIC:
result = prismaticNodeFactory->createRobotNode(robo, name, rnVisu, rnCol, limitLo, limitHi, 0, preJointTransform, idVec3, axis, physics);
// here, we need to convert [m] to [mm] for joint limits
result = prismaticNodeFactory->createRobotNode(robo, name, rnVisu, rnCol, limitLo * 1000, limitHi * 1000, 0, preJointTransform, idVec3, axis, physics);
break;
case urdf::Joint::FIXED:
result = prismaticNodeFactory->createRobotNode(robo, name, rnVisu, rnCol, limitLo, limitHi, 0, preJointTransform, axis, idVec3, physics);
// here, we need to convert [m] to [mm] for joint limits
result = prismaticNodeFactory->createRobotNode(robo, name, rnVisu, rnCol, limitLo * 1000, limitHi * 1000, 0, preJointTransform, axis, idVec3, physics);
break;
default:
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment