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 
30 
31 #pragma once
32 
33 
34 #include <algorithm>
35 #include <cmath>
36 #include <mutex>
37 #include <string>
38 
39 #include <gtest/gtest.h>
40 
41 #include <ros/ros.h>
42 
43 #include <geometry_msgs/Twist.h>
44 #include <nav_msgs/Odometry.h>
45 #include <tf/tf.h>
46 
47 #include <std_srvs/Empty.h>
48 #include <controller_manager_msgs/ListControllers.h>
49 
50 // Floating-point value comparison threshold
51 const double EPS = 0.01;
52 const double POSITION_TOLERANCE = 0.01; // 1 cm-s precision
53 const double VELOCITY_TOLERANCE = 0.02; // 2 cm-s-1 precision
54 const double ANGULAR_VELOCITY_TOLERANCE = 0.05; // 3 deg-s-1 precision
55 const double JERK_LINEAR_VELOCITY_TOLERANCE = 0.10; // 10 cm-s-1 precision
56 const double JERK_ANGULAR_VELOCITY_TOLERANCE = 0.05; // 3 deg-s-1 precision
57 const double ORIENTATION_TOLERANCE = 0.03; // 0.57 degree precision
58 
59 class AckermannSteeringControllerTest : public ::testing::Test
60 {
61 public:
62 
64  : cmd_pub(nh.advertise<geometry_msgs::Twist>("cmd_vel", 100))
66  , start_srv(nh.serviceClient<std_srvs::Empty>("start"))
67  , stop_srv(nh.serviceClient<std_srvs::Empty>("stop"))
68  , list_ctrls_srv(nh.serviceClient<controller_manager_msgs::ListControllers>("/controller_manager/list_controllers"))
69  , ctrl_name("ackermann_steering_bot_controller")
70  {
71  }
72 
74  {
76  }
77 
78  nav_msgs::Odometry getLastOdom()
79  {
80  std::lock_guard<std::mutex> lock(odom_mutex);
81  return last_odom;
82  }
83 
85  {
86  try
87  {
88  auto odom = getLastOdom();
89  tf::assertQuaternionValid(odom.pose.pose.orientation);
90  }
91  catch (const tf::InvalidArgument& exception)
92  {
93  return false;
94  }
95  return true;
96  }
97 
98  void publish(geometry_msgs::Twist cmd_vel){ cmd_pub.publish(cmd_vel); }
99 
101  {
102  controller_manager_msgs::ListControllers srv;
103  list_ctrls_srv.call(srv);
104 
105  auto ctrl_list = srv.response.controller;
106  auto is_running = [this](const controller_manager_msgs::ControllerState& ctrl)
107  {
108  return ctrl.name == ctrl_name && ctrl.state == "running";
109  };
110  bool running = std::any_of(ctrl_list.begin(), ctrl_list.end(), is_running);
111  bool subscribing = cmd_pub.getNumSubscribers() > 0;
112  return running && subscribing;
113  }
114 
115  void start(){ std_srvs::Empty srv; start_srv.call(srv); }
116  void stop(){ std_srvs::Empty srv; stop_srv.call(srv); }
117 
118 private:
122  nav_msgs::Odometry last_odom;
123 
126 
128  std::string ctrl_name;
129 
130  std::mutex odom_mutex;
131 
132  void odomCallback(const nav_msgs::Odometry& odom)
133  {
134  ROS_INFO_STREAM("Callback reveived: pos.x: " << odom.pose.pose.position.x
135  << ", orient.z: " << odom.pose.pose.orientation.z
136  << ", lin_est: " << odom.twist.twist.linear.x
137  << ", ang_est: " << odom.twist.twist.angular.z);
138  std::lock_guard<std::mutex> lock(odom_mutex);
139  last_odom = odom;
140  }
141 };
142 
143 inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat)
144 {
145  return tf::Quaternion(quat.x, quat.y, quat.z, quat.w);
146 }
void odomCallback(const nav_msgs::Odometry &odom)
Definition: test_common.h:132
void assertQuaternionValid(const tf::Quaternion &q)
nav_msgs::Odometry getLastOdom()
Definition: test_common.h:78
nav_msgs::Odometry last_odom
Definition: test_common.h:122
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
const double VELOCITY_TOLERANCE
Definition: test_common.h:53
bool call(MReq &req, MRes &res)
const double EPS
Definition: test_common.h:51
void publish(geometry_msgs::Twist cmd_vel)
Definition: test_common.h:98
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:143
ros::ServiceClient start_srv
Definition: test_common.h:124
ros::ServiceClient stop_srv
Definition: test_common.h:125
void subscribe()
const double JERK_ANGULAR_VELOCITY_TOLERANCE
Definition: test_common.h:56
void publish(const boost::shared_ptr< M > &message) const
const double JERK_LINEAR_VELOCITY_TOLERANCE
Definition: test_common.h:55
#define ROS_INFO_STREAM(args)
const double ANGULAR_VELOCITY_TOLERANCE
Definition: test_common.h:54
ros::ServiceClient list_ctrls_srv
Definition: test_common.h:127
const double ORIENTATION_TOLERANCE
Definition: test_common.h:57
uint32_t getNumSubscribers() const
const double POSITION_TOLERANCE
Definition: test_common.h:52


ackermann_steering_controller
Author(s): Masaru Morita
autogenerated on Fri Feb 3 2023 03:19:04