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 00030 00031 #include "../common/include/test_common.h" 00032 #include <tf/transform_listener.h> 00033 00034 // TEST CASES 00035 TEST_F(SteerDriveControllerTest, testOdomFrame) 00036 { 00037 // wait for ROS 00038 while(!isControllerAlive()) 00039 { 00040 ros::Duration(0.1).sleep(); 00041 } 00042 // set up tf listener 00043 tf::TransformListener listener; 00044 ros::Duration(2.0).sleep(); 00045 // check the original odom frame doesn't exist 00046 EXPECT_TRUE(listener.frameExists("odom")); 00047 } 00048 00049 TEST_F(SteerDriveControllerTest, testOdomTopic) 00050 { 00051 // wait for ROS 00052 while(!isControllerAlive()) 00053 { 00054 ros::Duration(0.1).sleep(); 00055 } 00056 00057 // get an odom message 00058 nav_msgs::Odometry odom_msg = getLastOdom(); 00059 // check its frame_id 00060 ASSERT_STREQ(odom_msg.header.frame_id.c_str(), "odom"); 00061 } 00062 00063 int main(int argc, char** argv) 00064 { 00065 testing::InitGoogleTest(&argc, argv); 00066 ros::init(argc, argv, "steer_drive_controller_default_odom_frame_test"); 00067 00068 ros::AsyncSpinner spinner(1); 00069 spinner.start(); 00070 int ret = RUN_ALL_TESTS(); 00071 spinner.stop(); 00072 ros::shutdown(); 00073 return ret; 00074 }