use angles::to_degrees() to make the angles conversion from radians to degrees

This commit is contained in:
hsu 2010-03-09 22:24:25 +00:00
parent 2faa8ca082
commit 6369746caf
3 changed files with 7 additions and 4 deletions

View File

@ -11,4 +11,5 @@
<depend package="colladadom" />
<depend package="assimp" />
<depend package="resource_retriever" />
<depend package="angles" />
</package>

View File

@ -56,6 +56,8 @@
#include <urdf/model.h>
#include <urdf/pose.h>
#include <angles/angles.h>
#include "STLLoader.h"
using namespace std;
@ -533,8 +535,8 @@ public:
// <limits>
domJoint_limitsRef limits = daeSafeCast<domJoint_limits>(revolute->createAndPlace(COLLADA_TYPE_LIMITS));
{
daeSafeCast<domMinmax>(limits->createAndPlace(COLLADA_ELEMENT_MIN))->getValue() = urdf_joint->limits->lower * (180.0 / M_PI);
daeSafeCast<domMinmax>(limits->createAndPlace(COLLADA_ELEMENT_MAX))->getValue() = urdf_joint->limits->upper * (180.0 / M_PI);
daeSafeCast<domMinmax>(limits->createAndPlace(COLLADA_ELEMENT_MIN))->getValue() = angles::to_degrees(urdf_joint->limits->lower);
daeSafeCast<domMinmax>(limits->createAndPlace(COLLADA_ELEMENT_MAX))->getValue() = angles::to_degrees(urdf_joint->limits->upper);
}
// </limits>
}
@ -916,7 +918,7 @@ public:
rot->getValue()[0] = ax;
rot->getValue()[1] = ay;
rot->getValue()[2] = az;
rot->getValue()[3] = aa * (180.0 / M_PI);
rot->getValue()[3] = angles::to_degrees(aa);
return rot;
}
};

View File

@ -12,7 +12,7 @@
<url>http://ros.org/wiki/robot_model</url>
<depend stack="common" /> <!-- tinyxml -->
<depend stack="common_msgs" /> <!-- sensor_msgs -->
<depend stack="geometry" /> <!-- tf, kdl, tf_conversions -->
<depend stack="geometry" /> <!-- angles, tf, kdl, tf_conversions -->
<depend stack="ros" /> <!-- rosconsole, roslib, roscpp -->
</stack>