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/TwistStamped.h>
40 #include <nav_msgs/Odometry.h>
41 #include <control_msgs/JointTrajectoryControllerState.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.01; // 1 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.03; // 0.57 degree precision
53 
54 class DiffDriveControllerTest : public ::testing::Test
55 {
56 public:
57 
59  : received_first_odom(false)
60  , cmd_pub(nh.advertise<geometry_msgs::Twist>("cmd_vel", 100))
62  , vel_out_sub(nh.subscribe("cmd_vel_out", 100, &DiffDriveControllerTest::cmdVelOutCallback, this))
64  , start_srv(nh.serviceClient<std_srvs::Empty>("start"))
65  , stop_srv(nh.serviceClient<std_srvs::Empty>("stop"))
66  {
67  }
68 
70  {
73  }
74 
75  nav_msgs::Odometry getLastOdom(){ return last_odom; }
76  geometry_msgs::TwistStamped getLastCmdVelOut(){ return last_cmd_vel_out; }
77  control_msgs::JointTrajectoryControllerState getLastJointTrajectoryControllerState(){ return last_joint_traj_controller_state; }
78  void publish(geometry_msgs::Twist cmd_vel){ cmd_pub.publish(cmd_vel); }
79  bool isControllerAlive()const{ return (odom_sub.getNumPublishers() > 0); }
80  bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const
81  {
83  int get_num_publishers = vel_out_sub.getNumPublishers();
84  while ( (get_num_publishers == 0) && (ros::Time::now() < start + timeout) ) {
85  ros::Duration(0.1).sleep();
86  get_num_publishers = vel_out_sub.getNumPublishers();
87  }
88  return (get_num_publishers > 0);
89  }
92 
93  void start(){ std_srvs::Empty srv; start_srv.call(srv); }
94  void stop(){ std_srvs::Empty srv; stop_srv.call(srv); }
95 
96  void waitForController() const
97  {
98  while(!isControllerAlive() && ros::ok())
99  {
100  ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for controller.");
101  ros::Duration(0.1).sleep();
102  }
103  if (!ros::ok())
104  FAIL() << "Something went wrong while executing test.";
105  }
106 
107  void waitForOdomMsgs() const
108  {
109  while(!hasReceivedFirstOdom() && ros::ok())
110  {
111  ROS_DEBUG_STREAM_THROTTLE(0.5, "Waiting for odom messages to be published.");
112  ros::Duration(0.01).sleep();
113  }
114  if (!ros::ok())
115  FAIL() << "Something went wrong while executing test.";
116  }
117 
118 private:
124  nav_msgs::Odometry last_odom;
125  geometry_msgs::TwistStamped last_cmd_vel_out;
127  control_msgs::JointTrajectoryControllerState last_joint_traj_controller_state;
128 
131 
132  void odomCallback(const nav_msgs::Odometry& odom)
133  {
134  ROS_INFO_STREAM("Callback received: 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  last_odom = odom;
139  received_first_odom = true;
140  }
141 
142  void jointTrajectoryControllerStateCallback(const control_msgs::JointTrajectoryControllerState& joint_traj_controller_state)
143  {
144  ROS_INFO_STREAM("Joint trajectory controller state callback.");
145  ROS_DEBUG_STREAM("Joint trajectory controller state callback received:\n" <<
146  joint_traj_controller_state);
147 
148  last_joint_traj_controller_state = joint_traj_controller_state;
149  }
150 
151  void cmdVelOutCallback(const geometry_msgs::TwistStamped& cmd_vel_out)
152  {
153  ROS_INFO_STREAM("Callback received: lin: " << cmd_vel_out.twist.linear.x
154  << ", ang: " << cmd_vel_out.twist.angular.z);
155  last_cmd_vel_out = cmd_vel_out;
156  }
157 };
158 
159 inline tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion& quat)
160 {
161  return tf::Quaternion(quat.x, quat.y, quat.z, quat.w);
162 }
DiffDriveControllerTest::cmdVelOutCallback
void cmdVelOutCallback(const geometry_msgs::TwistStamped &cmd_vel_out)
Definition: test_common.h:151
ros::Publisher
DiffDriveControllerTest::cmd_pub
ros::Publisher cmd_pub
Definition: test_common.h:121
DiffDriveControllerTest::~DiffDriveControllerTest
~DiffDriveControllerTest()
Definition: test_common.h:69
DiffDriveControllerTest::odomCallback
void odomCallback(const nav_msgs::Odometry &odom)
Definition: test_common.h:132
DiffDriveControllerTest::hasReceivedFirstOdom
bool hasReceivedFirstOdom() const
Definition: test_common.h:91
DiffDriveControllerTest::getLastCmdVelOut
geometry_msgs::TwistStamped getLastCmdVelOut()
Definition: test_common.h:76
ros.h
serviceClient
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
DiffDriveControllerTest::jointTrajectoryControllerStateCallback
void jointTrajectoryControllerStateCallback(const control_msgs::JointTrajectoryControllerState &joint_traj_controller_state)
Definition: test_common.h:142
DiffDriveControllerTest::nh
ros::NodeHandle nh
Definition: test_common.h:120
DiffDriveControllerTest::vel_out_sub
ros::Subscriber vel_out_sub
Definition: test_common.h:123
geometry_msgs
DiffDriveControllerTest::isPublishingCmdVelOut
bool isPublishingCmdVelOut(const ros::Duration &timeout=ros::Duration(1)) const
Definition: test_common.h:80
ros::Subscriber::shutdown
void shutdown()
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::ok
ROSCPP_DECL bool ok()
DiffDriveControllerTest::waitForController
void waitForController() const
Definition: test_common.h:96
DiffDriveControllerTest::stop
void stop()
Definition: test_common.h:94
ros::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
DiffDriveControllerTest::isPublishingJointTrajectoryControllerState
bool isPublishingJointTrajectoryControllerState()
Definition: test_common.h:90
DiffDriveControllerTest::DiffDriveControllerTest
DiffDriveControllerTest()
Definition: test_common.h:58
tfQuatFromGeomQuat
tf::Quaternion tfQuatFromGeomQuat(const geometry_msgs::Quaternion &quat)
Definition: test_common.h:159
EPS
const double EPS
Definition: test_common.h:47
DiffDriveControllerTest::getLastJointTrajectoryControllerState
control_msgs::JointTrajectoryControllerState getLastJointTrajectoryControllerState()
Definition: test_common.h:77
JERK_ANGULAR_VELOCITY_TOLERANCE
const double JERK_ANGULAR_VELOCITY_TOLERANCE
Definition: test_common.h:51
DiffDriveControllerTest::last_odom
nav_msgs::Odometry last_odom
Definition: test_common.h:124
DiffDriveControllerTest::publish
void publish(geometry_msgs::Twist cmd_vel)
Definition: test_common.h:78
DiffDriveControllerTest::isControllerAlive
bool isControllerAlive() const
Definition: test_common.h:79
DiffDriveControllerTest::received_first_odom
bool received_first_odom
Definition: test_common.h:119
ros::ServiceClient
subscribe
void subscribe()
ROS_DEBUG_STREAM_THROTTLE
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
DiffDriveControllerTest::stop_srv
ros::ServiceClient stop_srv
Definition: test_common.h:130
DiffDriveControllerTest::last_cmd_vel_out
geometry_msgs::TwistStamped last_cmd_vel_out
Definition: test_common.h:125
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
DiffDriveControllerTest
Definition: test_common.h:54
DiffDriveControllerTest::waitForOdomMsgs
void waitForOdomMsgs() const
Definition: test_common.h:107
tf.h
ros::Time
DiffDriveControllerTest::odom_sub
ros::Subscriber odom_sub
Definition: test_common.h:122
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
DiffDriveControllerTest::start
void start()
Definition: test_common.h:93
DiffDriveControllerTest::start_srv
ros::ServiceClient start_srv
Definition: test_common.h:129
ros::Duration::sleep
bool sleep() const
ros::Duration
JERK_LINEAR_VELOCITY_TOLERANCE
const double JERK_LINEAR_VELOCITY_TOLERANCE
Definition: test_common.h:50
DiffDriveControllerTest::last_joint_traj_controller_state
control_msgs::JointTrajectoryControllerState last_joint_traj_controller_state
Definition: test_common.h:127
tf::Quaternion
DiffDriveControllerTest::getLastOdom
nav_msgs::Odometry getLastOdom()
Definition: test_common.h:75
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
DiffDriveControllerTest::joint_traj_controller_state_sub
ros::Subscriber joint_traj_controller_state_sub
Definition: test_common.h:126
ros::Time::now
static Time now()


diff_drive_controller
Author(s): Bence Magyar
autogenerated on Fri May 24 2024 02:41:05