test_common.h
Go to the documentation of this file.
1 // Copyright (C) 2013, 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 #pragma once
31 
32 
33 #include <cmath>
34 
35 #include <gtest/gtest.h>
36 
37 #include <ros/ros.h>
38 
39 #include <geometry_msgs/Twist.h>
40 #include <four_wheel_steering_msgs/FourWheelSteering.h>
41 #include <nav_msgs/Odometry.h>
42 #include <tf/tf.h>
43 
44 #include <std_srvs/Empty.h>
45 
46 // Floating-point value comparison threshold
47 const double EPS = 0.01;
48 const double POSITION_TOLERANCE = 0.02; // 2 cm-s precision
49 const double VELOCITY_TOLERANCE = 0.02; // 2 cm-s-1 precision
50 const double JERK_LINEAR_VELOCITY_TOLERANCE = 0.10; // 10 cm-s-1 precision
51 const double JERK_ANGULAR_VELOCITY_TOLERANCE = 0.05; // 3 deg-s-1 precision
52 const double ORIENTATION_TOLERANCE = 0.08; // 4.58 degree precision
53 
54 class FourWheelSteeringControllerTest : public ::testing::Test
55 {
56 public:
57 
59  : received_first_odom(false)
60  , cmd_twist_pub(nh.advertise<geometry_msgs::Twist>("cmd_vel", 100))
61  , cmd_4ws_pub(nh.advertise<four_wheel_steering_msgs::FourWheelSteering>("cmd_four_wheel_steering", 100))
63  , start_srv(nh.serviceClient<std_srvs::Empty>("start"))
64  , stop_srv(nh.serviceClient<std_srvs::Empty>("stop"))
65  {
66  }
67 
69  {
71  }
72 
73  nav_msgs::Odometry getLastOdom(){ return last_odom; }
74  void publish(geometry_msgs::Twist cmd_vel)
75  {
76  cmd_twist_pub.publish(cmd_vel);
77  }
78  void publish_4ws(four_wheel_steering_msgs::FourWheelSteering cmd_vel)
79  {
80  cmd_4ws_pub.publish(cmd_vel);
81  }
82  bool isControllerAlive()const{ return (odom_sub.getNumPublishers() > 0)
84 
86 
87  void start(){ std_srvs::Empty srv; start_srv.call(srv); }
88  void stop(){ std_srvs::Empty srv; stop_srv.call(srv); }
89 
90  void waitForController() const
91  {
92  while(!isControllerAlive() && ros::ok())
93  {
94  ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for controller.");
95  ros::Duration(0.1).sleep();
96  }
97  if (!ros::ok())
98  FAIL() << "Something went wrong while executing test.";
99  }
100 
101  void waitForOdomMsgs() const
102  {
103  while(!hasReceivedFirstOdom() && ros::ok())
104  {
105  ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for odom messages to be published.");
106  ros::Duration(0.01).sleep();
107  }
108  if (!ros::ok())
109  FAIL() << "Something went wrong while executing test.";
110  }
111 
112 private:
117  nav_msgs::Odometry last_odom;
118 
121 
122  void odomCallback(const nav_msgs::Odometry& odom)
123  {
124  ROS_INFO_STREAM("Callback reveived: pos.x: " << odom.pose.pose.position.x
125  << ", orient.z: " << odom.pose.pose.orientation.z
126  << ", lin_est: " << odom.twist.twist.linear.x
127  << ", ang_est: " << odom.twist.twist.angular.z);
128  last_odom = odom;
129  received_first_odom = true;
130  }
131 };
132 
133 inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat)
134 {
135  return tf::Quaternion(quat.x, quat.y, quat.z, quat.w);
136 }
FourWheelSteeringControllerTest::cmd_4ws_pub
ros::Publisher cmd_4ws_pub
Definition: test_common.h:115
FourWheelSteeringControllerTest::stop_srv
ros::ServiceClient stop_srv
Definition: test_common.h:120
FourWheelSteeringControllerTest::getLastOdom
nav_msgs::Odometry getLastOdom()
Definition: test_common.h:73
ros::Publisher
ros.h
serviceClient
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
FourWheelSteeringControllerTest::cmd_twist_pub
ros::Publisher cmd_twist_pub
Definition: test_common.h:115
geometry_msgs
ros::Subscriber::shutdown
void shutdown()
FourWheelSteeringControllerTest::last_odom
nav_msgs::Odometry last_odom
Definition: test_common.h:117
FourWheelSteeringControllerTest::waitForOdomMsgs
void waitForOdomMsgs() const
Definition: test_common.h:101
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::ok
ROSCPP_DECL bool ok()
ros::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
FourWheelSteeringControllerTest::publish
void publish(geometry_msgs::Twist cmd_vel)
Definition: test_common.h:74
tfQuatFromGeomQuat
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:133
EPS
const double EPS
Definition: test_common.h:47
JERK_ANGULAR_VELOCITY_TOLERANCE
const double JERK_ANGULAR_VELOCITY_TOLERANCE
Definition: test_common.h:51
FourWheelSteeringControllerTest
Definition: test_common.h:54
FourWheelSteeringControllerTest::received_first_odom
bool received_first_odom
Definition: test_common.h:113
FourWheelSteeringControllerTest::odom_sub
ros::Subscriber odom_sub
Definition: test_common.h:116
ros::ServiceClient
subscribe
void subscribe()
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
FourWheelSteering
Definition: four_wheel_steering.h:24
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
tf.h
FourWheelSteeringControllerTest::publish_4ws
void publish_4ws(four_wheel_steering_msgs::FourWheelSteering cmd_vel)
Definition: test_common.h:78
FourWheelSteeringControllerTest::FourWheelSteeringControllerTest
FourWheelSteeringControllerTest()
Definition: test_common.h:58
FourWheelSteeringControllerTest::odomCallback
void odomCallback(const nav_msgs::Odometry &odom)
Definition: test_common.h:122
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
FourWheelSteeringControllerTest::start_srv
ros::ServiceClient start_srv
Definition: test_common.h:119
FourWheelSteeringControllerTest::nh
ros::NodeHandle nh
Definition: test_common.h:114
ros::Duration::sleep
bool sleep() const
FourWheelSteeringControllerTest::~FourWheelSteeringControllerTest
~FourWheelSteeringControllerTest()
Definition: test_common.h:68
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
FourWheelSteeringControllerTest::hasReceivedFirstOdom
bool hasReceivedFirstOdom() const
Definition: test_common.h:85
FourWheelSteeringControllerTest::start
void start()
Definition: test_common.h:87
FourWheelSteeringControllerTest::isControllerAlive
bool isControllerAlive() const
Definition: test_common.h:82
ros::Duration
JERK_LINEAR_VELOCITY_TOLERANCE
const double JERK_LINEAR_VELOCITY_TOLERANCE
Definition: test_common.h:50
tf::Quaternion
FourWheelSteeringControllerTest::waitForController
void waitForController() const
Definition: test_common.h:90
ros::NodeHandle
ros::Subscriber
VELOCITY_TOLERANCE
const double VELOCITY_TOLERANCE
Definition: test_common.h:49
ORIENTATION_TOLERANCE
const double ORIENTATION_TOLERANCE
Definition: test_common.h:52
POSITION_TOLERANCE
const double POSITION_TOLERANCE
Definition: test_common.h:48
FourWheelSteeringControllerTest::stop
void stop()
Definition: test_common.h:88


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15