8 #include <mrpt/poses/CPosePDFGaussian.h>
9 #include <mrpt/poses/CPose3DPDFGaussian.h>
10 #include <mrpt/math/CQuaternion.h>
11 #include <geometry_msgs/PoseWithCovariance.h>
12 #include <geometry_msgs/Pose.h>
13 #include <geometry_msgs/Quaternion.h>
16 #include <gtest/gtest.h>
17 #include <Eigen/Dense>
21 #if MRPT_VERSION >= 0x199
22 #define getAsVectorVal asVectorVal
25 using mrpt::utils::DEG2RAD;
29 const double roll,
const double pitch,
const double yaw)
34 rotation.
setRPY(roll, pitch, yaw);
39 mrpt::poses::CPose3D mrpt_original_pose;
40 mrpt_original_pose.setYawPitchRoll(yaw, pitch, roll);
41 mrpt::math::CMatrixDouble33 mrpt_basis =
42 mrpt_original_pose.getRotationMatrix();
44 for (
int i = 0; i < 3; i++)
45 for (
int j = 0; j < 3; j++)
46 EXPECT_NEAR(basis[i][j], mrpt_basis(i, j), 0.01);
49 TEST(PoseConversions, copyMatrix3x3ToCMatrixDouble33)
52 mrpt::math::CMatrixDouble33 des;
54 for (
int r = 0; r < 3; r++)
55 for (
int c = 0; c < 3; c++) EXPECT_FLOAT_EQ(des(r, c), src[r][c]);
57 TEST(PoseConversions, copyCMatrixDouble33ToMatrix3x3)
59 mrpt::math::CMatrixDouble33 src;
60 for (
int r = 0; r < 3; r++)
61 for (
int c = 0; c < 3; c++) src(r, c) = 12.0 + r * 4 - c * 2 + r * c;
65 for (
int r = 0; r < 3; r++)
66 for (
int c = 0; c < 3; c++) EXPECT_FLOAT_EQ(des[r][c], src(r, c));
80 TEST(PoseConversions, reference_frame_change_with_rotations)
84 ros_msg_original_pose.pose.position.x = 1;
85 ros_msg_original_pose.pose.position.y = 0;
86 ros_msg_original_pose.pose.position.z = 0;
87 ros_msg_original_pose.pose.orientation.x = 0;
88 ros_msg_original_pose.pose.orientation.y = 0;
89 ros_msg_original_pose.pose.orientation.z = 0;
90 ros_msg_original_pose.pose.orientation.w = 1;
93 mrpt::poses::CPose3DPDFGaussian mrpt_original_pose;
96 ros_msg_original_pose.pose.position.x, mrpt_original_pose.mean[0]);
103 mrpt::poses::CPose3D rotation_mrpt;
104 double yaw = M_PI / 2.0;
105 rotation_mrpt.setFromValues(0, 0, 0, yaw, 0, 0);
106 mrpt::poses::CPose3D mrpt_result = rotation_mrpt + mrpt_original_pose.mean;
107 EXPECT_NEAR(mrpt_result[1], 1.0, 0.01);
111 rotation_tf.
setRPY(0, 0, yaw);
115 tf::Pose tf_result = rotation_pose_tf * tf_original_pose;
116 EXPECT_NEAR(tf_result.
getOrigin()[1], 1.0, 0.01);
121 EXPECT_NEAR(mrpt_ros_result.position.x, tf_result.
getOrigin()[0], 0.01);
122 EXPECT_NEAR(mrpt_ros_result.position.y, tf_result.
getOrigin()[1], 0.01);
123 EXPECT_NEAR(mrpt_ros_result.position.z, tf_result.
getOrigin()[2], 0.01);
127 double x,
double y,
double z,
double yaw,
double pitch,
double roll)
129 const mrpt::poses::CPose3D p3D(x, y, z, yaw, pitch, roll);
137 p3D.getAsQuaternion(q);
139 EXPECT_NEAR(ros_p3D.position.x, p3D.x(), 1e-4) <<
"p: " << p3D << endl;
140 EXPECT_NEAR(ros_p3D.position.y, p3D.y(), 1e-4) <<
"p: " << p3D << endl;
141 EXPECT_NEAR(ros_p3D.position.z, p3D.z(), 1e-4) <<
"p: " << p3D << endl;
143 EXPECT_NEAR(ros_p3D.orientation.x, q.x(), 1e-4) <<
"p: " << p3D << endl;
144 EXPECT_NEAR(ros_p3D.orientation.y, q.y(), 1e-4) <<
"p: " << p3D << endl;
145 EXPECT_NEAR(ros_p3D.orientation.z, q.z(), 1e-4) <<
"p: " << p3D << endl;
146 EXPECT_NEAR(ros_p3D.orientation.w, q.r(), 1e-4) <<
"p: " << p3D << endl;
149 mrpt::poses::CPose3D p_bis;
154 (p_bis.getAsVectorVal() - p3D.getAsVectorVal())
159 <<
"p_bis: " << p_bis << endl
160 <<
"p3D: " << p3D << endl;
180 TEST(PoseConversions, check_CPose2D_to_ROS)
182 const mrpt::poses::CPose2D p2D(1, 2, 0.56);
189 const mrpt::poses::CPose3D p3D = mrpt::poses::CPose3D(p2D);
190 mrpt::poses::CPose3D p3D_ros;
195 (p3D_ros.getAsVectorVal() - p3D.getAsVectorVal())
200 <<
"p3D_ros: " << p3D_ros << endl
201 <<
"p3D: " << p3D << endl;