32 #include <gtest/gtest.h>
36 static const std::string
urdf_string_ =
"<robot name=\"test_robot\"><link name=\"base\"><visual><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></visual><collision><geometry><cylinder length=\"0.3\" radius=\"0.2\"/></geometry><origin xyz=\"0 0 0.15\"/></collision></link><link name=\"link1\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></visual><collision><geometry><cylinder length=\"0.15\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.075\"/></collision></link><link name=\"link2\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></visual><collision><geometry><cylinder length=\"0.35\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.175\"/></collision></link><link name=\"link3\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></visual><collision><geometry><cylinder length=\"0.45\" radius=\"0.05\"/></geometry><origin xyz=\"0 0 0.225\"/></collision></link><link name=\"endeff\"><inertial><mass value=\"0.2\"/><origin xyz=\"0 0 0.1\"/><inertia ixx=\"0.00381666666667\" ixy=\"0\" ixz=\"0\" iyy=\"0.0036\" iyz=\"0\" izz=\"0.00381666666667\"/></inertial><visual><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></visual><collision><geometry><cylinder length=\"0.05\" radius=\"0.1\"/></geometry><origin xyz=\"0 0 -0.025\"/></collision></link><joint name=\"joint1\" type=\"revolute\"><parent link=\"base\"/><child link=\"link1\"/><origin xyz=\"0 0 0.3\" rpy=\"0 0 0\" /><axis xyz=\"0 0 1\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint2\" type=\"revolute\"><parent link=\"link1\"/><child link=\"link2\"/><origin xyz=\"0 0 0.15\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint3\" type=\"revolute\"><parent link=\"link2\"/><child link=\"link3\"/><origin xyz=\"0 0 0.35\" rpy=\"0 0 0\" /><axis xyz=\"0 1 0\" /><limit effort=\"200\" velocity=\"1.0\" lower=\"-0.4\" upper=\"0.4\"/><safety_controller k_position=\"30\" k_velocity=\"30\" soft_lower_limit=\"-0.4\" soft_upper_limit=\"0.4\"/></joint><joint name=\"joint4\" type=\"fixed\"><parent link=\"link3\"/><child link=\"endeff\"/><origin xyz=\"0 0 0.45\" rpy=\"0 0 0\" /></joint></robot>";
37 static const std::string
srdf_string_ =
"<robot name=\"test_robot\"><group name=\"arm\"><chain base_link=\"base\" tip_link=\"endeff\" /></group><virtual_joint name=\"world_joint\" type=\"fixed\" parent_frame=\"world_frame\" child_link=\"base\" /><group_state name=\"zero\" group=\"arm\"><joint name=\"joint1\" value=\"0\" /><joint name=\"joint2\" value=\"0.3\" /><joint name=\"joint3\" value=\"0.55\" /></group_state><disable_collisions link1=\"base\" link2=\"link1\" reason=\"Adjacent\" /><disable_collisions link1=\"endeff\" link2=\"link3\" reason=\"Adjacent\" /><disable_collisions link1=\"link1\" link2=\"link2\" reason=\"Adjacent\" /><disable_collisions link1=\"link2\" link2=\"link3\" reason=\"Adjacent\" /></robot>";
56 scene.reset(
new Scene());
58 {
"Name", std::string(
"MyScene")},
59 {
"JointGroup", std::string(
"arm")},
60 {
"DoNotInstantiateCollisionScene", std::string(
"1")},
62 scene->InstantiateInternal(SceneInitializer(
init));
70 N = scene->GetKinematicTree().GetNumControlledJoints();
76 constexpr
double h = 1e-5;
78 TEST_COUT <<
"Testing Jacobian with h=" << h <<
", eps=" << eps;
81 Eigen::VectorXd x0(
test.N);
82 x0 =
test.scene->GetKinematicTree().GetRandomControlledState();
83 test.scene->Update(x0, 0.0);
84 KDL::Frame y0 =
test.solution.Phi(0);
85 KDL::Jacobian J0 =
test.solution.jacobian(0);
86 KDL::Jacobian jacobian(
test.N);
87 jacobian.data.setZero();
88 for (
int i = 0; i <
test.N; ++i)
90 Eigen::VectorXd
x(x0);
92 test.scene->Update(
x, 0.0);
93 KDL::Frame
y =
test.solution.Phi(0);
94 KDL::Twist diff = KDL::diff(y0,
y);
95 for (
int j = 0; j < 6; ++j)
96 jacobian.data(j, i) = diff[j] / h;
98 double errJ = (jacobian.data - J0.data).norm();
107 << (jacobian.data - J0.data);
108 ADD_FAILURE() <<
"Jacobian error out of bounds: " << errJ;
116 constexpr
double h = 1e-5;
118 TEST_COUT <<
"Testing Hessian with h=" << h <<
", eps=" << eps;
121 Eigen::VectorXd x0(
test.N);
122 x0 =
test.scene->GetKinematicTree().GetRandomControlledState();
123 test.scene->Update(x0, 0.0);
125 Hessian hessian = Hessian::Constant(6, Eigen::MatrixXd::Zero(
test.N,
test.N));
127 for (
int j = 0; j <
test.N; ++j)
131 test.scene->Update(
x, 0.0);
132 Eigen::MatrixXd J1 =
test.solution.jacobian(0).data;
135 test.scene->Update(
x, 0.0);
136 Eigen::MatrixXd J2 =
test.solution.jacobian(0).data;
137 for (
int i = 0; i <
test.N; ++i)
139 for (
int k = 0; k < 6; ++k)
141 hessian(k)(i, j) = (J1(k, i) - J2(k, i)) / (2.0 * h);
146 for (
int i = 0; i < hessian.rows(); ++i) errH += (hessian(i) - H0(i)).norm();
176 ADD_FAILURE() <<
"Hessian error out of bounds: " << errH;
182 TEST(ExoticaCore, testKinematicJacobian)
190 catch (
const std::exception& e)
192 ADD_FAILURE() <<
"Uncaught exception! " << e.what();
196 TEST(ExoticaCore, testKinematicHessian)
204 catch (
const std::exception& e)
206 ADD_FAILURE() <<
"Uncaught exception! " << e.what();
210 int main(
int argc,
char** argv)
212 testing::InitGoogleTest(&argc, argv);
213 int ret = RUN_ALL_TESTS();