32 #include <gtest/gtest.h> 38 int rand_num = rand()%100+1;
39 double result = min + (double)((max-min)*rand_num)/101.0;
43 TEST(TFKDLConversions, tf_kdl_vector)
53 ASSERT_NEAR(t[0],k[0],1e-6);
54 ASSERT_NEAR(t[1],k[1],1e-6);
55 ASSERT_NEAR(t[2],k[2],1e-6);
58 TEST(TFKDLConversions, tf_kdl_rotation)
73 ASSERT_NEAR(fabs(t[0]),fabs(x),1e-6);
74 ASSERT_NEAR(fabs(t[1]),fabs(y),1e-6);
75 ASSERT_NEAR(fabs(t[2]),fabs(z),1e-6);
76 ASSERT_NEAR(fabs(t[3]),fabs(w),1e-6);
77 ASSERT_NEAR(t[0]*t[1]*t[2]*t[3],x*y*z*w,1e-6);
82 TEST(TFKDLConversions, tf_kdl_transform)
98 for(
int i=0; i < 3; i++)
101 for(
int j=0; j < 3; j++)
103 ASSERT_NEAR(t.
getBasis()[i][j],k.
M(i,j),1e-6);
110 for(
int i=0; i< 3; i++)
112 ASSERT_NEAR(t.
getOrigin()[i],r.getOrigin()[i],1e-6);
113 for(
int j=0; j < 3; j++)
115 ASSERT_NEAR(t.
getBasis()[i][j],r.getBasis()[i][j],1e-6);
121 TEST(TFKDLConversions, tf_kdl_pose)
137 for(
int i=0; i < 3; i++)
140 for(
int j=0; j < 3; j++)
142 ASSERT_NEAR(t.
getBasis()[i][j],k.
M(i,j),1e-6);
150 for(
int i=0; i< 3; i++)
152 ASSERT_NEAR(t.
getOrigin()[i],r.getOrigin()[i],1e-6);
153 for(
int j=0; j < 3; j++)
155 ASSERT_NEAR(t.
getBasis()[i][j],r.getBasis()[i][j],1e-6);
161 TEST(TFKDLConversions, msg_kdl_twist)
163 geometry_msgs::Twist m;
175 ASSERT_NEAR(m.linear.x,t.
vel[0],1e-6);
176 ASSERT_NEAR(m.linear.y,t.
vel[1],1e-6);
177 ASSERT_NEAR(m.linear.z,t.
vel[2],1e-6);
178 ASSERT_NEAR(m.angular.x,t.
rot[0],1e-6);
179 ASSERT_NEAR(m.angular.y,t.
rot[1],1e-6);
180 ASSERT_NEAR(m.angular.z,t.
rot[2],1e-6);
184 geometry_msgs::Twist r;
187 ASSERT_NEAR(r.linear.x,t.
vel[0],1e-6);
188 ASSERT_NEAR(r.linear.y,t.
vel[1],1e-6);
189 ASSERT_NEAR(r.linear.z,t.
vel[2],1e-6);
190 ASSERT_NEAR(r.angular.x,t.
rot[0],1e-6);
191 ASSERT_NEAR(r.angular.y,t.
rot[1],1e-6);
192 ASSERT_NEAR(r.angular.z,t.
rot[2],1e-6);
198 int main(
int argc,
char **argv){
200 srand ( time(NULL) );
201 testing::InitGoogleTest(&argc, argv);
202 return RUN_ALL_TESTS();
void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) __attribute__((deprecated))
Converts a tf Transform into a KDL Frame.
TEST(TFKDLConversions, tf_kdl_vector)
void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) __attribute__((deprecated))
Converts a KDL Frame into a tf Transform.
void PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) __attribute__((deprecated))
Converts a KDL Frame into a tf Pose.
void VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) __attribute__((deprecated))
Converts a tf Vector3 into a KDL Vector.
void QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) __attribute__((deprecated))
Converts a tf Quaternion into a KDL Rotation.
TFSIMD_FORCE_INLINE const tfScalar & y() const
void PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) __attribute__((deprecated))
Converts a tf Pose into a KDL Frame.
void GetQuaternion(double &x, double &y, double &z, double &w) const
void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated))
TFSIMD_FORCE_INLINE const tfScalar & x() const
int main(int argc, char **argv)
TFSIMD_FORCE_INLINE const tfScalar & z() const
TFSIMD_FORCE_INLINE const tfScalar & w() const
double gen_rand(double min, double max)
void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated))