construct kdl object directly from quaternion
This commit is contained in:
parent
89be14e58b
commit
3438a44a14
|
@ -53,9 +53,7 @@ Vector toKdl(urdf::Vector3 v)
|
||||||
// construct rotation
|
// construct rotation
|
||||||
Rotation toKdl(urdf::Rotation r)
|
Rotation toKdl(urdf::Rotation r)
|
||||||
{
|
{
|
||||||
double roll, pitch, yaw;
|
return Rotation::Quaternion(r.x, r.y, r.z, r.w);
|
||||||
r.getRPY(roll, pitch, yaw);
|
|
||||||
return Rotation::RPY(roll, pitch, yaw);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// construct pose
|
// construct pose
|
||||||
|
|
Loading…
Reference in New Issue