diff_drive_multiple_cmd_vel_publishers_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 // TEST CASES
33 TEST_F(DiffDriveControllerTest, breakWithMultiplePublishers)
34 {
35  // wait for ROS
36  waitForController();
37  waitForOdomMsgs();
38 
39  nav_msgs::Odometry old_odom = getLastOdom();
40  //TODO: we should be programatically publish from 2 different nodes
41  // not the current hacky solution with the launch files
42  ros::Duration(1.0).sleep();
43  nav_msgs::Odometry new_odom = getLastOdom();
44 
45  const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
46  const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
47  const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
48  EXPECT_NEAR(sqrt(dx*dx + dy*dy), 0.0, POSITION_TOLERANCE);
49  EXPECT_LT(fabs(dz), EPS);
50 
51  // convert to rpy and test that way
52  double roll_old, pitch_old, yaw_old;
53  double roll_new, pitch_new, yaw_new;
54  tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
55  tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
56  EXPECT_LT(fabs(roll_new - roll_old), EPS);
57  EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
58  EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
59 }
60 
61 int main(int argc, char** argv)
62 {
63  testing::InitGoogleTest(&argc, argv);
64  ros::init(argc, argv, "diff_drive_multiple_publishers_test");
65 
67  spinner.start();
68  int ret = RUN_ALL_TESTS();
69  spinner.stop();
70  ros::shutdown();
71  return ret;
72 }
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
const double EPS
Definition: test_common.h:43
void spinner()
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:140
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
int main(int argc, char **argv)
TEST_F(DiffDriveControllerTest, breakWithMultiplePublishers)
ROSCPP_DECL void shutdown()
const double POSITION_TOLERANCE
Definition: test_common.h:44


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