38 #include <gtest/gtest.h> 52 urdf::Vector3 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;
66 EXPECT_TRUE(result_track);
67 EXPECT_DOUBLE_EQ(track, 1.1);
70 EXPECT_TRUE(result_wb);
71 EXPECT_DOUBLE_EQ(wheel_base, 1.9);
79 EXPECT_DOUBLE_EQ(wheel_radius, 0.28);
84 double 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();
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool getTransformVector(const std::string &joint_name, const std::string &parent_link_name, urdf::Vector3 &transform_vector)
Get transform vector between the joint and parent_link.
bool getJointSteeringLimits(const std::string &joint_name, double &steering_limit)
Get joint steering limit from the URDF considering the upper and lower limit is the same...
urdf_geometry_parser::UrdfGeometryParser ugp_
int main(int argc, char **argv)
TEST_F(UrdfGeometryParserTest, testTransformVector)
bool getJointRadius(const std::string &joint_name, double &radius)
Get joint radius from the URDF.
bool getDistanceBetweenJoints(const std::string &first_joint_name, const std::string &second_joint_name, double &distance)
Get distance between two joints from the URDF.