test_trajectory_tracker_overshoot.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2021, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <vector>
31 
33 #include <trajectory_tracker/TrajectoryTrackerConfig.h>
34 
35 #include <dynamic_reconfigure/client.h>
36 
38 {
39 protected:
40  void runTest(const double goal_tolerance_lin_vel, const double goal_tolerance_ang_vel,
41  const double linear_vel, const double rotation_vel, const int32_t expected_status)
42  {
43  initState(Eigen::Vector2d(0, 0), 0);
44 
45  std::vector<Eigen::Vector3d> poses;
46  for (double x = 0.0; x < 0.5; x += 0.01)
47  poses.push_back(Eigen::Vector3d(x, 0.0, 0.0));
48  poses.push_back(Eigen::Vector3d(0.5, 0.0, 0.0));
49  waitUntilStart(std::bind(&TrajectoryTrackerTest::publishPath, this, poses));
50 
52  ASSERT_TRUE(getConfig(param));
53  param.goal_tolerance_lin_vel = goal_tolerance_lin_vel;
54  param.goal_tolerance_ang_vel = goal_tolerance_ang_vel;
55  ASSERT_TRUE(setConfig(param));
56 
57  nav_msgs::Odometry odom;
58  odom.header.frame_id = "odom";
59  odom.child_frame_id = "base_link";
60  odom.pose.pose.position.x = 0.5;
61  odom.pose.pose.position.y = 0.0;
62  odom.pose.pose.position.z = 0.0;
63  odom.pose.pose.orientation.x = 0.0;
64  odom.pose.pose.orientation.y = 0.0;
65  odom.pose.pose.orientation.z = 0.0;
66  odom.pose.pose.orientation.w = 1.0;
67  odom.twist.twist.linear.x = linear_vel;
68  odom.twist.twist.linear.y = 0.0;
69  odom.twist.twist.linear.z = 0.0;
70  odom.twist.twist.angular.x = 0.0;
71  odom.twist.twist.angular.y = 0.0;
72  odom.twist.twist.angular.z = rotation_vel;
73 
74  ros::Rate rate(50);
75  const ros::Time initial_time = ros::Time::now();
76  const ros::Time time_limit = initial_time + ros::Duration(5.0);
77  while (ros::ok() && time_limit > ros::Time::now())
78  {
79  odom.header.stamp = ros::Time::now();
80  publishTransform(odom);
81  rate.sleep();
82  ros::spinOnce();
83  if ((status_->header.stamp > initial_time + ros::Duration(0.5)) && (status_->status == expected_status))
84  {
85  return;
86  }
87  }
88  FAIL() << "Expected status: " << expected_status << " Actual status: " << status_->status;
89  }
90 };
91 
92 TEST_F(TrajectoryTrackerOvershootTest, NoVelocityToleranceWithRemainingLinearVel)
93 {
94  SCOPED_TRACE("NoVelocityToleranceWithRemainingLinearVel");
95  runTest(0.0, 0.0, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
96 }
97 
98 TEST_F(TrajectoryTrackerOvershootTest, NoVelocityToleranceWithRemainingAngularVel)
99 {
100  SCOPED_TRACE("NoVelocityToleranceWithRemainingAngularVel");
101  runTest(0.0, 0.0, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
102 }
103 
104 TEST_F(TrajectoryTrackerOvershootTest, LinearVelocityToleranceWithRemainingLinearVel)
105 {
106  SCOPED_TRACE("LinearVelocityToleranceWithRemainingLinearVel");
107  runTest(0.05, 0.0, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
108 }
109 
110 TEST_F(TrajectoryTrackerOvershootTest, LinearVelocityToleranceWithRemainingAngularVel)
111 {
112  SCOPED_TRACE("LinearVelocityToleranceWithRemainingAngularVel");
113  runTest(0.05, 0.0, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
114 }
115 
116 TEST_F(TrajectoryTrackerOvershootTest, AngularrVelocityToleranceWithRemainingLinearVel)
117 {
118  SCOPED_TRACE("AngularrVelocityToleranceWithRemainingLinearVel");
119  runTest(0.0, 0.05, 0.1, 0.0, trajectory_tracker_msgs::TrajectoryTrackerStatus::GOAL);
120 }
121 
122 TEST_F(TrajectoryTrackerOvershootTest, AngularrVelocityToleranceWithRemainingAngularVel)
123 {
124  SCOPED_TRACE("AngularrVelocityToleranceWithRemainingAngularVel");
125  runTest(0.0, 0.05, 0.0, 0.1, trajectory_tracker_msgs::TrajectoryTrackerStatus::FOLLOWING);
126 }
127 
128 int main(int argc, char** argv)
129 {
130  testing::InitGoogleTest(&argc, argv);
131  ros::init(argc, argv, "test_trajectory_tracker_overshoot");
132 
133  return RUN_ALL_TESTS();
134 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TrajectoryTrackerTest::ParamType
trajectory_tracker::TrajectoryTrackerConfig ParamType
Definition: trajectory_tracker_test.h:86
TrajectoryTrackerOvershootTest
Definition: test_trajectory_tracker_overshoot.cpp:37
main
int main(int argc, char **argv)
Definition: test_trajectory_tracker_overshoot.cpp:128
TrajectoryTrackerTest::publishTransform
void publishTransform()
Definition: trajectory_tracker_test.h:257
ros::spinOnce
ROSCPP_DECL void spinOnce()
trajectory_tracker_test.h
TrajectoryTrackerTest::setConfig
bool setConfig(const ParamType &config)
Definition: trajectory_tracker_test.h:327
ros::ok
ROSCPP_DECL bool ok()
TrajectoryTrackerTest::status_
trajectory_tracker_msgs::TrajectoryTrackerStatus::ConstPtr status_
Definition: trajectory_tracker_test.h:119
TrajectoryTrackerTest::initState
void initState(const tf2::Transform &pose)
Definition: trajectory_tracker_test.h:153
ros::Rate::sleep
bool sleep()
ros::Time
TrajectoryTrackerTest::getConfig
bool getConfig(ParamType &config) const
Definition: trajectory_tracker_test.h:313
TrajectoryTrackerOvershootTest::runTest
void runTest(const double goal_tolerance_lin_vel, const double goal_tolerance_ang_vel, const double linear_vel, const double rotation_vel, const int32_t expected_status)
Definition: test_trajectory_tracker_overshoot.cpp:40
param
T param(const std::string &param_name, const T &default_val)
ros::Rate
TrajectoryTrackerTest
Definition: trajectory_tracker_test.h:62
TrajectoryTrackerTest::waitUntilStart
void waitUntilStart(const std::function< void()> func=nullptr)
Definition: trajectory_tracker_test.h:184
ros::Duration
TEST_F
TEST_F(TrajectoryTrackerOvershootTest, NoVelocityToleranceWithRemainingLinearVel)
Definition: test_trajectory_tracker_overshoot.cpp:92
TrajectoryTrackerTest::publishPath
void publishPath(const std::vector< Eigen::Vector3d > &poses)
Definition: trajectory_tracker_test.h:206
ros::Time::now
static Time now()


trajectory_tracker
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:20