urdf_geometry_parser_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Irstea
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Irstea nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ros/ros.h>
37 
38 #include <gtest/gtest.h>
39 
40 class UrdfGeometryParserTest : public ::testing::Test{
41 public:
43  ugp_(nh_, "base_link")
44  {}
45 
48 };
49 
50 TEST_F(UrdfGeometryParserTest, testTransformVector)
51 {
52  urdf::Vector3 transform_vector;
53 
54  bool result = ugp_.getTransformVector("front_left_wheel", "base_link", transform_vector);
55  EXPECT_TRUE(result);
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);
59 }
60 
62 {
63  double track, wheel_base;
64 
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);
68 
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);
72 }
73 
75 {
76  double wheel_radius;
77  bool result = ugp_.getJointRadius("front_left_wheel", wheel_radius);
78  EXPECT_TRUE(result);
79  EXPECT_DOUBLE_EQ(wheel_radius, 0.28);
80 }
81 
82 TEST_F(UrdfGeometryParserTest, testJointSteeringLimits)
83 {
84  double steering_limit;
85  bool result = ugp_.getJointSteeringLimits("rear_left_steering_joint", steering_limit);
86  EXPECT_TRUE(result);
87  EXPECT_NEAR(steering_limit, M_PI/6, 0.001);
88 }
89 
90 int main(int argc, char** argv)
91 {
92  testing::InitGoogleTest(&argc, argv);
93  ros::init(argc, argv, "UrdfGeometryParserTestNode");
94  return RUN_ALL_TESTS();
95 }
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.


urdf_geometry_parser
Author(s): Vincent Rousseau
autogenerated on Thu Feb 4 2021 03:11:52