43 #include <gtest/gtest.h> 67 bool testAffine3d(
const std::string&
id,
const Eigen::Affine3d& expect,
const Eigen::Affine3d& actual)
69 static const double EPSILON = 0.000001;
70 EXPECT_GT(EPSILON, fabs(expect.translation().x() - actual.translation().x()))
71 <<
id <<
" Translation x - expect: " << expect.translation().x() <<
" actual: " << actual.translation().x();
72 EXPECT_GT(EPSILON, fabs(expect.translation().y() - actual.translation().y()))
73 <<
id <<
" Translation y - expect: " << expect.translation().y() <<
" actual: " << actual.translation().y();
74 EXPECT_GT(EPSILON, fabs(expect.translation().z() - actual.translation().z()))
75 <<
id <<
" Translation z - expect: " << expect.translation().z() <<
" actual: " << actual.translation().z();
77 Eigen::Quaterniond q1(expect.rotation());
78 Eigen::Quaterniond q2(actual.rotation());
79 EXPECT_GT(EPSILON, fabs(q1.x() - q2.x())) <<
id <<
" Quaternion x - expect: " << q1.x() <<
" actual: " << q2.x();
80 EXPECT_GT(EPSILON, fabs(q1.y() - q2.y())) <<
id <<
" Quaternion y - expect: " << q1.y() <<
" actual: " << q2.y();
81 EXPECT_GT(EPSILON, fabs(q1.z() - q2.z())) <<
id <<
" Quaternion z - expect: " << q1.z() <<
" actual: " << q2.z();
82 EXPECT_GT(EPSILON, fabs(q1.w() - q2.w())) <<
id <<
" Quaternion w - expect: " << q1.w() <<
" actual: " << q2.w();
87 bool testVector(
const std::string&
id,
const std::vector<double>& expect,
const std::vector<double>& actual)
89 EXPECT_EQ(expect.size(), actual.size()) <<
id <<
" Unequal vector sizes";
91 static const double EPSILON = 0.000001;
92 for (std::size_t i = 0; i < expect.size(); ++i)
94 EXPECT_GT(EPSILON, fabs(expect[i] - actual[i])) <<
"Section " <<
id <<
", Element " << i
95 <<
", Expect: " << expect[i] <<
", Actual: " << actual[i];
115 Eigen::Affine3d expected_affine = Eigen::Affine3d::Identity();
116 std::vector<double> xyzrpy;
117 base.
visual_tools_->convertToXYZRPY(expected_affine, xyzrpy);
118 std::vector<double> expected_vector;
119 expected_vector.push_back(0);
120 expected_vector.push_back(0);
121 expected_vector.push_back(0);
122 expected_vector.push_back(0);
123 expected_vector.push_back(0);
124 expected_vector.push_back(0);
125 EXPECT_TRUE(base.
testVector(
"Identity: ", expected_vector, xyzrpy));
129 EXPECT_TRUE(base.
testAffine3d(
"Identity convert back", expected_affine, expected_affine2));
133 expected_affine.translation().x() = 1;
134 expected_affine.translation().y() = 2;
135 expected_affine.translation().z() = 3;
136 base.
visual_tools_->convertToXYZRPY(expected_affine, xyzrpy);
137 expected_vector[0] = 1;
138 expected_vector[1] = 2;
139 expected_vector[2] = 3;
140 EXPECT_TRUE(base.
testVector(
"123: ", expected_vector, xyzrpy));
144 EXPECT_TRUE(base.
testAffine3d(
"123 convert back", expected_affine, expected_affine2));
147 expected_affine2 = base.
visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4],
149 EXPECT_TRUE(base.
testAffine3d(
"123 convert back long", expected_affine, expected_affine2));
152 expected_affine2 = base.
visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4],
154 EXPECT_TRUE(base.
testAffine3d(
"123 convert back new long", expected_affine, expected_affine2));
158 expected_affine = expected_affine * Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitX()) *
159 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitZ()) *
160 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX());
161 base.
visual_tools_->convertToXYZRPY(expected_affine, xyzrpy);
165 EXPECT_TRUE(base.
testAffine3d(
"123 convert back", expected_affine, expected_affine2));
168 expected_affine2 = base.
visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4],
170 EXPECT_TRUE(base.
testAffine3d(
"123 convert back long", expected_affine, expected_affine2));
173 expected_affine2 = base.
visual_tools_->convertFromXYZRPY(xyzrpy[0], xyzrpy[1], xyzrpy[2], xyzrpy[3], xyzrpy[4],
175 EXPECT_TRUE(base.
testAffine3d(
"123 convert back new long", expected_affine, expected_affine2));
179 int main(
int argc,
char** argv)
181 testing::InitGoogleTest(&argc, argv);
182 ros::init(argc, argv,
"rviz_visual_tools_tests");
183 return RUN_ALL_TESTS();
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO_STREAM_NAMED(name, args)
rviz_visual_tools::RvizVisualToolsPtr visual_tools_
TEST(RVTTest, initialize)
bool testVector(const std::string &id, const std::vector< double > &expect, const std::vector< double > &actual)
bool testAffine3d(const std::string &id, const Eigen::Affine3d &expect, const Eigen::Affine3d &actual)