diff_drive_odom_frame_test.cpp
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2015, Locus Robotics Corp.
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 
00029 
00030 #include "test_common.h"
00031 #include <tf/transform_listener.h>
00032 
00033 // TEST CASES
00034 TEST_F(DiffDriveControllerTest, testNoOdomFrame)
00035 {
00036   // wait for ROS
00037   while(!isControllerAlive())
00038   {
00039     ros::Duration(0.1).sleep();
00040   }
00041   // set up tf listener
00042   tf::TransformListener listener;
00043   ros::Duration(2.0).sleep();
00044   // check the original odom frame doesn't exist
00045   EXPECT_FALSE(listener.frameExists("odom"));
00046 }
00047 
00048 TEST_F(DiffDriveControllerTest, testNewOdomFrame)
00049 {
00050   // wait for ROS
00051   while(!isControllerAlive())
00052   {
00053     ros::Duration(0.1).sleep();
00054   }
00055   // set up tf listener
00056   tf::TransformListener listener;
00057   ros::Duration(2.0).sleep();
00058   // check the new_odom frame does exist
00059   EXPECT_TRUE(listener.frameExists("new_odom"));
00060 }
00061 
00062 TEST_F(DiffDriveControllerTest, testOdomTopic)
00063 {
00064   // wait for ROS
00065   while(!isControllerAlive())
00066   {
00067     ros::Duration(0.1).sleep();
00068   }
00069 
00070   // get an odom message
00071   nav_msgs::Odometry odom_msg = getLastOdom();
00072   // check its frame_id
00073   ASSERT_STREQ(odom_msg.header.frame_id.c_str(), "new_odom");
00074 }
00075 
00076 int main(int argc, char** argv)
00077 {
00078   testing::InitGoogleTest(&argc, argv);
00079   ros::init(argc, argv, "diff_drive_odom_frame_test");
00080 
00081   ros::AsyncSpinner spinner(1);
00082   spinner.start();
00083   int ret = RUN_ALL_TESTS();
00084   spinner.stop();
00085   ros::shutdown();
00086   return ret;
00087 }


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Thu Jun 6 2019 18:58:48