38 #include <gtest/gtest.h>
52 urdf::Vector3 transform_vector;
54 bool result = ugp_.getTransformVector(
"front_left_wheel",
"base_link", transform_vector);
56 EXPECT_DOUBLE_EQ(transform_vector.x, ( 1.90 / 2));
57 EXPECT_DOUBLE_EQ(transform_vector.y, ( 1.10 / 2));
58 EXPECT_DOUBLE_EQ(transform_vector.z, (-0.66 / 2) + 0.28 - 0.19);
63 double track, wheel_base;
65 bool result_track = ugp_.getDistanceBetweenJoints(
"front_left_wheel",
"front_right_wheel", track);
66 EXPECT_TRUE(result_track);
67 EXPECT_DOUBLE_EQ(track, 1.1);
69 bool result_wb = ugp_.getDistanceBetweenJoints(
"front_right_wheel",
"rear_right_wheel", wheel_base);
70 EXPECT_TRUE(result_wb);
71 EXPECT_DOUBLE_EQ(wheel_base, 1.9);
77 bool result = ugp_.getJointRadius(
"front_left_wheel", wheel_radius);
79 EXPECT_DOUBLE_EQ(wheel_radius, 0.28);
84 double steering_limit;
85 bool result = ugp_.getJointSteeringLimits(
"rear_left_steering_joint", steering_limit);
87 EXPECT_NEAR(steering_limit, M_PI/6, 0.001);
90 int main(
int argc,
char** argv)
92 testing::InitGoogleTest(&argc, argv);
93 ros::init(argc, argv,
"UrdfGeometryParserTestNode");
94 return RUN_ALL_TESTS();