diff_drive_default_cmd_vel_out_test.cpp
Go to the documentation of this file.
1 // Copyright (C) 2017, PAL Robotics.
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 // TEST CASES
33 TEST_F(DiffDriveControllerTest, testDefaultCmdVelOutTopic)
34 {
35  // wait for ROS
36  waitForController();
37  // msgs are published in the same loop
38  // thus if odom is published cmd_vel_out
39  // should be as well (if enabled)
40  waitForOdomMsgs();
41 
42  EXPECT_FALSE(isPublishingCmdVelOut());
43 
44  // zero everything before test
45  geometry_msgs::Twist cmd_vel;
46  cmd_vel.linear.x = 0.0;
47  cmd_vel.angular.z = 0.0;
48  publish(cmd_vel);
49  ros::Duration(0.1).sleep();
50 
51  cmd_vel.linear.x = 0.1;
52  publish(cmd_vel);
53  ros::Duration(0.1).sleep();
54 
55  EXPECT_FALSE(isPublishingCmdVelOut());
56 }
57 
58 int main(int argc, char** argv)
59 {
60  testing::InitGoogleTest(&argc, argv);
61  ros::init(argc, argv, "diff_drive_default_cmd_vel_out_topic_test");
62 
64  spinner.start();
65  int ret = RUN_ALL_TESTS();
66  spinner.stop();
67  ros::shutdown();
68  return ret;
69 }
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TEST_F(DiffDriveControllerTest, testDefaultCmdVelOutTopic)
int main(int argc, char **argv)
void spinner()
ROSCPP_DECL void shutdown()


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