steer_drive_controller_nan_test.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2014, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics, Inc. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00030 
00031 #include "../common/include/test_common.h"
00032 
00033 // NaN
00034 #include <limits>
00035 
00036 // TEST CASES
00037 TEST_F(SteerDriveControllerTest, testNaN)
00038 {
00039   // wait for ROS
00040   while(!isControllerAlive())
00041   {
00042     ros::Duration(0.1).sleep();
00043   }
00044   // zero everything before test
00045   geometry_msgs::Twist cmd_vel;
00046   cmd_vel.linear.x = 0.0;
00047   cmd_vel.angular.z = 0.0;
00048   publish(cmd_vel);
00049   ros::Duration(2.0).sleep();
00050 
00051   // send a command
00052   cmd_vel.linear.x = 0.1;
00053   ros::Duration(2.0).sleep();
00054 
00055   // stop robot (will generate NaN)
00056   stop();
00057   ros::Duration(2.0).sleep();
00058 
00059   nav_msgs::Odometry odom = getLastOdom();
00060 
00061   EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
00062   EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
00063   EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
00064   EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
00065   EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
00066   EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
00067 
00068   // start robot
00069   start();
00070   ros::Duration(2.0).sleep();
00071 
00072   odom = getLastOdom();
00073 
00074   EXPECT_NE(std::isnan(odom.twist.twist.linear.x), true);
00075   EXPECT_NE(std::isnan(odom.twist.twist.angular.z), true);
00076   EXPECT_NE(std::isnan(odom.pose.pose.position.x), true);
00077   EXPECT_NE(std::isnan(odom.pose.pose.position.y), true);
00078   EXPECT_NE(std::isnan(odom.pose.pose.orientation.z), true);
00079   EXPECT_NE(std::isnan(odom.pose.pose.orientation.w), true);
00080 }
00081 
00082 int main(int argc, char** argv)
00083 {
00084   testing::InitGoogleTest(&argc, argv);
00085   ros::init(argc, argv, "steer_drive_controller_nan_test");
00086 
00087   ros::AsyncSpinner spinner(1);
00088   spinner.start();
00089   int ret = RUN_ALL_TESTS();
00090   spinner.stop();
00091   ros::shutdown();
00092   return ret;
00093 }


steer_drive_controller
Author(s): CIR-KIT , Masaru Morita
autogenerated on Sat Jun 8 2019 19:20:25