diff_drive_test.cpp
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #include "test_common.h"
31 #include <tf/transform_listener.h>
32 
33 // TEST CASES
35 {
36  // wait for ROS
37  waitForController();
38 
39  // zero everything before test
40  geometry_msgs::Twist cmd_vel;
41  cmd_vel.linear.x = 0.0;
42  cmd_vel.angular.z = 0.0;
43  publish(cmd_vel);
44  ros::Duration(0.1).sleep();
45  // get initial odom
46  nav_msgs::Odometry old_odom = getLastOdom();
47  // send a velocity command of 0.1 m/s
48  cmd_vel.linear.x = 0.1;
49  publish(cmd_vel);
50  // wait for 10s
51  ros::Duration(10.0).sleep();
52 
53  nav_msgs::Odometry new_odom = getLastOdom();
54 
55  const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp;
56 
57  const double expected_distance = cmd_vel.linear.x * actual_elapsed_time.toSec();
58 
59  // check if the robot traveled 1 meter in XY plane, changes in z should be ~~0
60  const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
61  const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
62  const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
63  EXPECT_NEAR(sqrt(dx*dx + dy*dy), expected_distance, POSITION_TOLERANCE);
64  EXPECT_LT(fabs(dz), EPS);
65 
66  // convert to rpy and test that way
67  double roll_old, pitch_old, yaw_old;
68  double roll_new, pitch_new, yaw_new;
69  tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
70  tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
71  EXPECT_LT(fabs(roll_new - roll_old), EPS);
72  EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
73  EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
74  EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS);
75  EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
76  EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
77 
78  EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
79  EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
80  EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS);
81 }
82 
84 {
85  // wait for ROS
86  waitForController();
87 
88  // zero everything before test
89  geometry_msgs::Twist cmd_vel;
90  cmd_vel.linear.x = 0.0;
91  cmd_vel.angular.z = 0.0;
92  publish(cmd_vel);
93  ros::Duration(0.1).sleep();
94  // get initial odom
95  nav_msgs::Odometry old_odom = getLastOdom();
96  // send a velocity command
97  cmd_vel.angular.z = M_PI/10.0;
98  publish(cmd_vel);
99  // wait for 10s
100  ros::Duration(10.0).sleep();
101 
102  nav_msgs::Odometry new_odom = getLastOdom();
103 
104  // check if the robot rotated PI around z, changes in the other fields should be ~~0
105  EXPECT_LT(fabs(new_odom.pose.pose.position.x - old_odom.pose.pose.position.x), EPS);
106  EXPECT_LT(fabs(new_odom.pose.pose.position.y - old_odom.pose.pose.position.y), EPS);
107  EXPECT_LT(fabs(new_odom.pose.pose.position.z - old_odom.pose.pose.position.z), EPS);
108 
109  const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp;
110  const double expected_rotation = cmd_vel.angular.z * actual_elapsed_time.toSec();
111 
112  // convert to rpy and test that way
113  double roll_old, pitch_old, yaw_old;
114  double roll_new, pitch_new, yaw_new;
115  tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
116  tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
117  EXPECT_LT(fabs(roll_new - roll_old), EPS);
118  EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
119  EXPECT_NEAR(fabs(yaw_new - yaw_old), expected_rotation, ORIENTATION_TOLERANCE);
120 
121  EXPECT_LT(fabs(new_odom.twist.twist.linear.x), EPS);
122  EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
123  EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
124 
125  EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
126  EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
127  EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), expected_rotation/actual_elapsed_time.toSec(), EPS);
128 }
129 
131 {
132  // wait for ROS
133  waitForController();
134 
135  // set up tf listener
136  tf::TransformListener listener;
137  ros::Duration(2.0).sleep();
138  // check the odom frame exist
139  EXPECT_TRUE(listener.frameExists("odom"));
140 }
141 
142 int main(int argc, char** argv)
143 {
144  testing::InitGoogleTest(&argc, argv);
145  ros::init(argc, argv, "diff_drive_test");
146 
148  spinner.start();
149  //ros::Duration(0.5).sleep();
150  int ret = RUN_ALL_TESTS();
151  spinner.stop();
152  ros::shutdown();
153  return ret;
154 }
int main(int argc, char **argv)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const double EPS
Definition: test_common.h:43
void spinner()
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:140
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
ROSCPP_DECL void shutdown()
const double ORIENTATION_TOLERANCE
Definition: test_common.h:48
bool frameExists(const std::string &frame_id_str) const
TEST_F(DiffDriveControllerTest, testForward)
const double POSITION_TOLERANCE
Definition: test_common.h:44


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Apr 11 2019 03:08:07