diff_drive_limits_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 
32 // TEST CASES
33 TEST_F(DiffDriveControllerTest, testLinearJerkLimits)
34 {
35  // wait for ROS
36  waitForController();
37 
38  // zero everything before test
39  geometry_msgs::Twist cmd_vel;
40  cmd_vel.linear.x = 0.0;
41  cmd_vel.angular.z = 0.0;
42  publish(cmd_vel);
43  ros::Duration(2.0).sleep();
44  // get initial odom
45  nav_msgs::Odometry old_odom = getLastOdom();
46  // send a big command
47  cmd_vel.linear.x = 10.0;
48  publish(cmd_vel);
49  // wait for a while
50  ros::Duration(0.5).sleep();
51 
52  nav_msgs::Odometry new_odom = getLastOdom();
53 
54  // check if the robot speed is now 0.37m.s-1
55  EXPECT_NEAR(new_odom.twist.twist.linear.x, 0.37, JERK_LINEAR_VELOCITY_TOLERANCE);
56  EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
57 
58  cmd_vel.linear.x = 0.0;
59  publish(cmd_vel);
60 }
61 
62 TEST_F(DiffDriveControllerTest, testLinearAccelerationLimits)
63 {
64  // wait for ROS
65  while(!isControllerAlive())
66  {
67  ros::Duration(0.1).sleep();
68  }
69  // zero everything before test
70  geometry_msgs::Twist cmd_vel;
71  cmd_vel.linear.x = 0.0;
72  cmd_vel.angular.z = 0.0;
73  publish(cmd_vel);
74  ros::Duration(2.0).sleep();
75  // get initial odom
76  nav_msgs::Odometry old_odom = getLastOdom();
77  // send a big command
78  cmd_vel.linear.x = 10.0;
79  publish(cmd_vel);
80  // wait for a while
81  ros::Duration(0.5).sleep();
82 
83  nav_msgs::Odometry new_odom = getLastOdom();
84 
85  // check if the robot speed is now 0.5 m.s-1, which is 1.0m.s-2 * 0.5s
86  EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 0.5 + VELOCITY_TOLERANCE);
87  EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
88 
89  cmd_vel.linear.x = 0.0;
90  publish(cmd_vel);
91 }
92 
93 TEST_F(DiffDriveControllerTest, testLinearVelocityLimits)
94 {
95  // wait for ROS
96  while(!isControllerAlive())
97  {
98  ros::Duration(0.1).sleep();
99  }
100  // zero everything before test
101  geometry_msgs::Twist cmd_vel;
102  cmd_vel.linear.x = 0.0;
103  cmd_vel.angular.z = 0.0;
104  publish(cmd_vel);
105  ros::Duration(2.0).sleep();
106  // get initial odom
107  nav_msgs::Odometry old_odom = getLastOdom();
108  // send a big command
109  cmd_vel.linear.x = 10.0;
110  publish(cmd_vel);
111  // wait for a while
112  ros::Duration(5.0).sleep();
113 
114  nav_msgs::Odometry new_odom = getLastOdom();
115 
116  // check if the robot speed is now 1.0 m.s-1, the limit
117  EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), 1.0 + VELOCITY_TOLERANCE);
118  EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), EPS);
119 
120  cmd_vel.linear.x = 0.0;
121  publish(cmd_vel);
122 }
123 
124 /* This test has been failing on Travis for a long time due to timing issues however it works well when ran manually
125 TEST_F(DiffDriveControllerTest, testAngularJerkLimits)
126 {
127  // wait for ROS
128  while(!isControllerAlive())
129  {
130  ros::Duration(0.1).sleep();
131  }
132  // zero everything before test
133  geometry_msgs::Twist cmd_vel;
134  cmd_vel.linear.x = 0.0;
135  cmd_vel.angular.z = 0.0;
136  publish(cmd_vel);
137  ros::Duration(2.0).sleep();
138  // get initial odom
139  nav_msgs::Odometry old_odom = getLastOdom();
140  // send a big command
141  cmd_vel.angular.z = 10.0;
142  publish(cmd_vel);
143  // wait for a while
144  ros::Duration(0.5).sleep();
145 
146  nav_msgs::Odometry new_odom = getLastOdom();
147 
148  // check if the robot speed is now 0.7rad.s-1
149  EXPECT_NEAR(new_odom.twist.twist.angular.z, 0.7, JERK_ANGULAR_VELOCITY_TOLERANCE);
150  EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
151 
152  cmd_vel.angular.z = 0.0;
153  publish(cmd_vel);
154 }
155 */
156 
157 TEST_F(DiffDriveControllerTest, testAngularAccelerationLimits)
158 {
159  // wait for ROS
160  while(!isControllerAlive())
161  {
162  ros::Duration(0.1).sleep();
163  }
164  // zero everything before test
165  geometry_msgs::Twist cmd_vel;
166  cmd_vel.linear.x = 0.0;
167  cmd_vel.angular.z = 0.0;
168  publish(cmd_vel);
169  ros::Duration(2.0).sleep();
170  // get initial odom
171  nav_msgs::Odometry old_odom = getLastOdom();
172  // send a big command
173  cmd_vel.angular.z = 10.0;
174  publish(cmd_vel);
175  // wait for a while
176  ros::Duration(0.5).sleep();
177 
178  nav_msgs::Odometry new_odom = getLastOdom();
179 
180  // check if the robot speed is now 1.0rad.s-1, which is 2.0rad.s-2 * 0.5s
181  EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 1.0 + VELOCITY_TOLERANCE);
182  EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
183 
184  cmd_vel.angular.z = 0.0;
185  publish(cmd_vel);
186 }
187 
188 TEST_F(DiffDriveControllerTest, testAngularVelocityLimits)
189 {
190  // wait for ROS
191  while(!isControllerAlive())
192  {
193  ros::Duration(0.1).sleep();
194  }
195  // zero everything before test
196  geometry_msgs::Twist cmd_vel;
197  cmd_vel.linear.x = 0.0;
198  cmd_vel.angular.z = 0.0;
199  publish(cmd_vel);
200  ros::Duration(2.0).sleep();
201  // get initial odom
202  nav_msgs::Odometry old_odom = getLastOdom();
203  // send a big command
204  cmd_vel.angular.z = 10.0;
205  publish(cmd_vel);
206  // wait for a while
207  ros::Duration(5.0).sleep();
208 
209  nav_msgs::Odometry new_odom = getLastOdom();
210 
211  // check if the robot speed is now 2.0rad.s-1, the limit
212  EXPECT_LT(fabs(new_odom.twist.twist.angular.z - old_odom.twist.twist.angular.z), 2.0 + VELOCITY_TOLERANCE);
213  EXPECT_LT(fabs(new_odom.twist.twist.linear.x - old_odom.twist.twist.linear.x), EPS);
214 
215  cmd_vel.angular.z = 0.0;
216  publish(cmd_vel);
217 }
218 
219 int main(int argc, char** argv)
220 {
221  testing::InitGoogleTest(&argc, argv);
222  ros::init(argc, argv, "diff_drive_limits_test");
223 
225  spinner.start();
226  //ros::Duration(0.5).sleep();
227  int ret = RUN_ALL_TESTS();
228  spinner.stop();
229  ros::shutdown();
230  return ret;
231 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TEST_F
TEST_F(DiffDriveControllerTest, testLinearJerkLimits)
Definition: diff_drive_limits_test.cpp:33
test_common.h
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
main
int main(int argc, char **argv)
Definition: diff_drive_limits_test.cpp:219
spinner
void spinner()
EPS
const double EPS
Definition: test_common.h:47
DiffDriveControllerTest
Definition: test_common.h:54
ros::Duration::sleep
bool sleep() const
ros::Duration
JERK_LINEAR_VELOCITY_TOLERANCE
const double JERK_LINEAR_VELOCITY_TOLERANCE
Definition: test_common.h:50
VELOCITY_TOLERANCE
const double VELOCITY_TOLERANCE
Definition: test_common.h:49


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:04