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 {
38  // wait for ROS
39  while(!isControllerAlive())
40  {
41  ros::Duration(0.1).sleep();
42  }
43  // zero everything before test
44  geometry_msgs::Twist cmd_vel;
45  cmd_vel.linear.x = 0.0;
46  cmd_vel.angular.z = 0.0;
47  publish(cmd_vel);
48  ros::Duration(2.0).sleep();
49 
50  // send a command
51  cmd_vel.linear.x = 0.1;
52  ros::Duration(2.0).sleep();
53 
54  // stop robot (will generate NaN)
55  stop();
56  ros::Duration(2.0).sleep();
57 
58  nav_msgs::Odometry odom = getLastOdom();
59 
60  EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
61  EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
62  EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
63  EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
64  EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
65  EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
66 
67  // start robot
68  start();
69  ros::Duration(2.0).sleep();
70 
71  odom = getLastOdom();
72 
73  EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
74  EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
75  EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
76  EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
77  EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
78  EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
79 }
80 
81 int main(int argc, char** argv)
82 {
83  testing::InitGoogleTest(&argc, argv);
84  ros::init(argc, argv, "diff_drive_nan_test");
85 
87  spinner.start();
88  int ret = RUN_ALL_TESTS();
89  spinner.stop();
90  ros::shutdown();
91  return ret;
92 }
TEST_F(DiffDriveControllerTest, testNaN)
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void spinner()
int main(int argc, char **argv)
ROSCPP_DECL void shutdown()


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