test_tolerant_action.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2023, 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 <limits>
31 #include <memory>
32 #include <string>
33 
34 #include <gtest/gtest.h>
35 
37 #include <move_base_msgs/MoveBaseAction.h>
38 #include <planner_cspace_msgs/MoveWithToleranceAction.h>
39 #include <planner_cspace_msgs/PlannerStatus.h>
41 
42 #include <ros/ros.h>
43 
45 
47  : public ActionTestBase<planner_cspace_msgs::MoveWithToleranceAction, ACTION_TOPIC_TOLERANT_MOVE>
48 {
49 protected:
50  planner_cspace_msgs::MoveWithToleranceGoal createGoalInFree()
51  {
52  planner_cspace_msgs::MoveWithToleranceGoal goal;
53  goal.target_pose.header.stamp = ros::Time::now();
54  goal.target_pose.header.frame_id = "map";
55  goal.target_pose.pose.position.x = 2.1;
56  goal.target_pose.pose.position.y = 0.45;
57  goal.target_pose.pose.position.z = 0.0;
58  goal.target_pose.pose.orientation.x = 0.0;
59  goal.target_pose.pose.orientation.y = 0.0;
60  goal.target_pose.pose.orientation.z = 1.0;
61  goal.target_pose.pose.orientation.w = 0.0;
62  goal.continuous_movement_mode = true;
63  goal.goal_tolerance_ang = 0.1;
64  goal.goal_tolerance_ang_finish = 0.05;
65  goal.goal_tolerance_lin = 0.2;
66  return goal;
67  }
68 
69  double getDistBetweenRobotAndGoal(const planner_cspace_msgs::MoveWithToleranceGoal& goal)
70  {
71  try
72  {
73  const geometry_msgs::TransformStamped map_to_robot =
74  tfbuf_.lookupTransform("map", "base_link", ros::Time(), ros::Duration(0.1));
75  return std::hypot(map_to_robot.transform.translation.x - goal.target_pose.pose.position.x,
76  map_to_robot.transform.translation.y - goal.target_pose.pose.position.y);
77  }
78  catch (std::exception&)
79  {
80  return std::numeric_limits<double>::max();
81  }
82  }
83 };
84 
85 TEST_F(TolerantActionTest, GoalWithTolerance)
86 {
87  const ros::Time deadline = ros::Time::now() + ros::Duration(10);
88  const ros::Duration wait(1.0);
89 
90  // Assure that goal is received after map in planner_3d.
91  ros::Duration(0.5).sleep();
92  const planner_cspace_msgs::MoveWithToleranceGoal goal = createGoalInFree();
93  move_base_->sendGoal(goal);
94 
95  while (ros::ok() && move_base_->getState().state_ != actionlib::SimpleClientGoalState::ACTIVE)
96  {
97  ASSERT_LT(ros::Time::now(), deadline)
98  << "Action didn't get active: " << move_base_->getState().toString()
99  << " " << statusString();
100  ros::spinOnce();
101  }
102 
103  while (ros::ok() && move_base_->getState().state_ != actionlib::SimpleClientGoalState::SUCCEEDED)
104  {
105  ASSERT_LT(ros::Time::now(), deadline)
106  << "Action didn't succeeded: " << move_base_->getState().toString()
107  << " " << statusString();
108  ros::spinOnce();
109  }
110 
111  const double dist_to_goal = getDistBetweenRobotAndGoal(goal);
112  // distance_remains is less than updated goal_tolerance_lin (set in planner_cspace_msgs::MoveWithToleranceGoal).
113  EXPECT_LT(dist_to_goal, goal.goal_tolerance_lin);
114  // distance_remains is greater than default goal_tolerance_lin (set in actionlib_common_rostest.test).
115  EXPECT_GT(dist_to_goal, 0.05);
116  // Navigation still continues after ActionClient succeeded.
117  EXPECT_EQ(planner_status_->status, planner_cspace_msgs::PlannerStatus::DOING);
118 
119  while (ros::ok() && planner_status_->status != planner_cspace_msgs::PlannerStatus::DONE)
120  {
121  ASSERT_LT(ros::Time::now(), deadline)
122  << "Navigation didn't finished: " << move_base_->getState().toString()
123  << " " << statusString();
124  ros::spinOnce();
125  }
126  EXPECT_LT(getDistBetweenRobotAndGoal(goal), 0.05);
127 }
128 
129 int main(int argc, char** argv)
130 {
131  testing::InitGoogleTest(&argc, argv);
132  ros::init(argc, argv, "test_tolerant_action");
133  return RUN_ALL_TESTS();
134 }
TEST_F(TolerantActionTest, GoalWithTolerance)
planner_cspace_msgs::MoveWithToleranceGoal createGoalInFree()
void wait(int seconds)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double getDistBetweenRobotAndGoal(const planner_cspace_msgs::MoveWithToleranceGoal &goal)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL bool ok()
int main(int argc, char **argv)
static Time now()
bool sleep() const
ROSCPP_DECL void spinOnce()


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06