four_wheel_steering_twist_cmd_test.cpp
Go to the documentation of this file.
1 #include "test_common.h"
3 
4 // TEST CASES
6 {
7  // wait for ROS
8  waitForController();
9 
10  // zero everything before test
11  geometry_msgs::Twist cmd_vel;
12  cmd_vel.linear.x = 0.0;
13  cmd_vel.angular.z = 0.0;
14  publish(cmd_vel);
15  ros::Duration(0.1).sleep();
16  // get initial odom
17  nav_msgs::Odometry old_odom = getLastOdom();
18  // send a velocity command of 0.1 m/s
19  cmd_vel.linear.x = 0.1;
20  publish(cmd_vel);
21  // wait for Xs
22  double travel_time = 5.0;
23  ros::Duration(travel_time).sleep();
24 
25  nav_msgs::Odometry new_odom = getLastOdom();
26 
27  const ros::Duration actual_elapsed_time = new_odom.header.stamp - old_odom.header.stamp;
28 
29  const double expected_distance = cmd_vel.linear.x * actual_elapsed_time.toSec();
30 
31  // check if the robot traveled 1 meter in XY plane, changes in z should be ~~0
32  const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
33  const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
34  const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
35  EXPECT_NEAR(sqrt(dx*dx + dy*dy), expected_distance, POSITION_TOLERANCE);
36  EXPECT_LT(fabs(dz), EPS);
37 
38  // convert to rpy and test that way
39  double roll_old, pitch_old, yaw_old;
40  double roll_new, pitch_new, yaw_new;
41  tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
42  tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
43  EXPECT_LT(fabs(roll_new - roll_old), EPS);
44  EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
45  EXPECT_LT(fabs(yaw_new - yaw_old), EPS);
46  EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS);
47  EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
48  EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
49 
50  EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
51  EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
52  EXPECT_LT(fabs(new_odom.twist.twist.angular.z), EPS);
53 }
54 
56 {
57  // wait for ROS
58  waitForController();
59 
60  // zero everything before test
61  geometry_msgs::Twist cmd_vel;
62  cmd_vel.linear.x = 0.0;
63  cmd_vel.angular.z = 0.0;
64  publish(cmd_vel);
65  ros::Duration(0.1).sleep();
66  // get initial odom
67  nav_msgs::Odometry old_odom = getLastOdom();
68  // send a velocity command
69  cmd_vel.linear.x = M_PI/2.0;
70  cmd_vel.angular.z = M_PI/10.0;
71  publish(cmd_vel);
72  // wait for 10s to make a half turn
73  ros::Duration(10.0).sleep();
74 
75  nav_msgs::Odometry new_odom = getLastOdom();
76 
77  // check if the robot traveled 20 meter in XY plane, changes in z should be ~~0
78  const double dx = new_odom.pose.pose.position.x - old_odom.pose.pose.position.x;
79  const double dy = new_odom.pose.pose.position.y - old_odom.pose.pose.position.y;
80  const double dz = new_odom.pose.pose.position.z - old_odom.pose.pose.position.z;
81  EXPECT_NEAR(sqrt(dx*dx + dy*dy), 2*cmd_vel.linear.x/cmd_vel.angular.z, POSITION_TOLERANCE);
82  EXPECT_LT(fabs(dz), EPS);
83 
84  // convert to rpy and test that way
85  double roll_old, pitch_old, yaw_old;
86  double roll_new, pitch_new, yaw_new;
87  tf::Matrix3x3(tfQuatFromGeomQuat(old_odom.pose.pose.orientation)).getRPY(roll_old, pitch_old, yaw_old);
88  tf::Matrix3x3(tfQuatFromGeomQuat(new_odom.pose.pose.orientation)).getRPY(roll_new, pitch_new, yaw_new);
89  EXPECT_LT(fabs(roll_new - roll_old), EPS);
90  EXPECT_LT(fabs(pitch_new - pitch_old), EPS);
91  EXPECT_NEAR(fabs(yaw_new - yaw_old), M_PI, ORIENTATION_TOLERANCE);
92 
93  EXPECT_NEAR(fabs(new_odom.twist.twist.linear.x), cmd_vel.linear.x, EPS);
94  EXPECT_LT(fabs(new_odom.twist.twist.linear.y), EPS);
95  EXPECT_LT(fabs(new_odom.twist.twist.linear.z), EPS);
96 
97  EXPECT_LT(fabs(new_odom.twist.twist.angular.x), EPS);
98  EXPECT_LT(fabs(new_odom.twist.twist.angular.y), EPS);
99  EXPECT_NEAR(fabs(new_odom.twist.twist.angular.z), cmd_vel.angular.z, EPS);
100 }
101 
103 {
104  // wait for ROS
105  waitForController();
106 
107  // set up tf listener
108  tf::TransformListener listener;
109  ros::Duration(2.0).sleep();
110  // check the odom frame exist
111  EXPECT_TRUE(listener.frameExists("odom"));
112 }
113 
114 int main(int argc, char** argv)
115 {
116  testing::InitGoogleTest(&argc, argv);
117  ros::init(argc, argv, "four_wheel_steering_twist_cmd_test");
118 
120  spinner.start();
121  //ros::Duration(0.5).sleep();
122  int ret = RUN_ALL_TESTS();
123  spinner.stop();
124  ros::shutdown();
125  return ret;
126 }
int main(int argc, char **argv)
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:44
void spinner()
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:130
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
ROSCPP_DECL void shutdown()
TEST_F(FourWheelSteeringControllerTest, testForward)
const double ORIENTATION_TOLERANCE
Definition: test_common.h:49
bool frameExists(const std::string &frame_id_str) const
const double POSITION_TOLERANCE
Definition: test_common.h:45


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Thu Apr 11 2019 03:08:25