diff_drive_nan_test.cpp
Go to the documentation of this file.
1 // Copyright (C) 2014, 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 // NaN
33 #include <limits>
34 
35 // TEST CASES
37  // wait for ROS
38  waitForController();
39 
40  // zero everything before test
41  geometry_msgs::Twist cmd_vel;
42  cmd_vel.linear.x = 0.0;
43  cmd_vel.angular.z = 0.0;
44  publish(cmd_vel);
45  ros::Duration(2.0).sleep();
46 
47  // send a command
48  cmd_vel.linear.x = 0.1;
49  ros::Duration(2.0).sleep();
50 
51  // stop robot (will generate NaN)
52  stop();
53  ros::Duration(2.0).sleep();
54 
55  nav_msgs::Odometry odom = getLastOdom();
56 
57  EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x));
58  EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z));
59  EXPECT_FALSE(std::isnan(odom.pose.pose.position.x));
60  EXPECT_FALSE(std::isnan(odom.pose.pose.position.y));
61  EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z));
62  EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w));
63 
64  // start robot
65  start();
66  ros::Duration(2.0).sleep();
67 
68  odom = getLastOdom();
69 
70  EXPECT_FALSE(std::isnan(odom.twist.twist.linear.x));
71  EXPECT_FALSE(std::isnan(odom.twist.twist.angular.z));
72  EXPECT_FALSE(std::isnan(odom.pose.pose.position.x));
73  EXPECT_FALSE(std::isnan(odom.pose.pose.position.y));
74  EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.z));
75  EXPECT_FALSE(std::isnan(odom.pose.pose.orientation.w));
76 }
77 
79  // wait for ROS
80  while (!isControllerAlive()) {
81  ros::Duration(0.1).sleep();
82  }
83  // zero everything before test
84  geometry_msgs::Twist cmd_vel;
85  cmd_vel.linear.x = 0.0;
86  cmd_vel.angular.z = 0.0;
87  publish(cmd_vel);
88  ros::Duration(0.1).sleep();
89 
90  // send NaN
91  for (int i = 0; i < 10; ++i) {
92  geometry_msgs::Twist cmd_vel;
93  cmd_vel.linear.x = NAN;
94  cmd_vel.angular.z = 0.0;
95  publish(cmd_vel);
96  geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
97  EXPECT_FALSE(std::isnan(odom_msg.twist.linear.x));
98  EXPECT_FALSE(std::isnan(odom_msg.twist.angular.z));
99  ros::Duration(0.1).sleep();
100  }
101  for (int i = 0; i < 10; ++i) {
102  geometry_msgs::Twist cmd_vel;
103  cmd_vel.linear.x = 0.0;
104  cmd_vel.angular.z = NAN;
105  publish(cmd_vel);
106  geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
107  EXPECT_FALSE(std::isnan(odom_msg.twist.linear.x));
108  EXPECT_FALSE(std::isnan(odom_msg.twist.angular.z));
109  ros::Duration(0.1).sleep();
110  }
111 
112  nav_msgs::Odometry odom = getLastOdom();
113  EXPECT_DOUBLE_EQ(odom.twist.twist.linear.x, 0.0);
114  EXPECT_DOUBLE_EQ(odom.pose.pose.position.x, 0.0);
115  EXPECT_DOUBLE_EQ(odom.pose.pose.position.y, 0.0);
116 
117  geometry_msgs::TwistStamped odom_msg = getLastCmdVelOut();
118  EXPECT_DOUBLE_EQ(odom_msg.twist.linear.x, 0.0);
119 }
120 
121 int main(int argc, char **argv) {
122  testing::InitGoogleTest(&argc, argv);
123  ros::init(argc, argv, "diff_drive_nan_test");
124 
126  spinner.start();
127  int ret = RUN_ALL_TESTS();
128  spinner.stop();
129  ros::shutdown();
130  return ret;
131 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
test_common.h
ros::AsyncSpinner
ros::shutdown
ROSCPP_DECL void shutdown()
spinner
void spinner()
main
int main(int argc, char **argv)
Definition: diff_drive_nan_test.cpp:121
DiffDriveControllerTest
Definition: test_common.h:54
start
ROSCPP_DECL void start()
TEST_F
TEST_F(DiffDriveControllerTest, testNaN)
Definition: diff_drive_nan_test.cpp:36
ros::Duration::sleep
bool sleep() const
ros::Duration


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