18 #include <gtest/gtest.h>
20 #include <Eigen/Dense>
25 #define _USE_MATH_DEFINES
31 static constexpr
double L0{ 0.2604 };
32 static constexpr
double L1{ 0.3500 };
33 static constexpr
double L2{ 0.3070 };
34 static constexpr
double L3{ 0.0840 };
35 static constexpr
double DELTA{ 1.0e-10 };
39 typedef std::tuple<std::string, std::vector<double>, Eigen::Vector3d>
TestDataPoint;
43 return std::get<0>(tdp);
48 return std::get<1>(tdp);
53 return std::get<2>(tdp);
58 return std::string(vec.begin(), vec.end());
67 void SetUp()
override;
120 robot_state::RobotState rstate(robot_model_);
121 ASSERT_TRUE(rstate.knowsFrameTransform(tip_link_name_));
127 std::vector<double> joints =
getJoints(test_data);
128 Eigen::Vector3d pos_exp =
getPos(test_data);
131 rstate.setVariablePositions(joints);
133 Eigen::Affine3d
transform = rstate.getFrameTransform(tip_link_name_);
136 double error_norm = (
transform.translation() - pos_exp).norm();
139 << Eigen::VectorXd::Map(joints.data(),
static_cast<long>(joints.size()))
142 <<
"\t Expected position [" << pos_exp.transpose() <<
"]\n"
143 <<
"\t Real position [" <<
transform.translation().transpose() <<
"]";
147 int main(
int argc,
char** argv)
150 testing::InitGoogleTest(&argc, argv);
151 return RUN_ALL_TESTS();