Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
wait_behavior_tester.cpp
1 // Copyright (c) 2020 Samsung Research
2 // Copyright (c) 2020 Sarthak Mittal
3 // Copyright (c) 2018 Intel Corporation
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License. Reserved.
16 
17 #include <string>
18 #include <random>
19 #include <tuple>
20 #include <memory>
21 #include <iostream>
22 #include <chrono>
23 #include <sstream>
24 #include <iomanip>
25 
26 #include "wait_behavior_tester.hpp"
27 
28 using namespace std::chrono_literals;
29 using namespace std::chrono; // NOLINT
30 
31 namespace nav2_system_tests
32 {
33 
34 WaitBehaviorTester::WaitBehaviorTester()
35 : is_active_(false),
36  initial_pose_received_(false)
37 {
38  node_ = rclcpp::Node::make_shared("wait_behavior_test");
39 
40  tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
41  tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
42 
43  client_ptr_ = rclcpp_action::create_client<Wait>(
44  node_->get_node_base_interface(),
45  node_->get_node_graph_interface(),
46  node_->get_node_logging_interface(),
47  node_->get_node_waitables_interface(),
48  "wait");
49 
50  publisher_ =
51  node_->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>("initialpose", 10);
52 
53  subscription_ = node_->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
54  "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
55  std::bind(&WaitBehaviorTester::amclPoseCallback, this, std::placeholders::_1));
56 }
57 
58 WaitBehaviorTester::~WaitBehaviorTester()
59 {
60  if (is_active_) {
61  deactivate();
62  }
63 }
64 
65 void WaitBehaviorTester::activate()
66 {
67  if (is_active_) {
68  throw std::runtime_error("Trying to activate while already active");
69  return;
70  }
71  rclcpp::executors::SingleThreadedExecutor executor;
72  executor.add_node(node_);
73  while (!initial_pose_received_) {
74  RCLCPP_WARN(node_->get_logger(), "Initial pose not received");
75  sendInitialPose();
76  std::this_thread::sleep_for(100ms);
77  executor.spin_some();
78  }
79 
80  // Wait for lifecycle_manager_navigation to activate behavior_server
81  std::this_thread::sleep_for(10s);
82 
83  if (!client_ptr_) {
84  RCLCPP_ERROR(node_->get_logger(), "Action client not initialized");
85  is_active_ = false;
86  return;
87  }
88 
89  if (!client_ptr_->wait_for_action_server(10s)) {
90  RCLCPP_ERROR(node_->get_logger(), "Action server not available after waiting");
91  is_active_ = false;
92  return;
93  }
94 
95  RCLCPP_INFO(this->node_->get_logger(), "Wait action server is ready");
96  is_active_ = true;
97 }
98 
99 void WaitBehaviorTester::deactivate()
100 {
101  if (!is_active_) {
102  throw std::runtime_error("Trying to deactivate while already inactive");
103  }
104  is_active_ = false;
105 }
106 
107 bool WaitBehaviorTester::behaviorTest(
108  const float wait_time)
109 {
110  if (!is_active_) {
111  RCLCPP_ERROR(node_->get_logger(), "Not activated");
112  return false;
113  }
114 
115  // Sleep to let behavior server be ready for serving in multiple runs
116  std::this_thread::sleep_for(5s);
117 
118  auto start_time = node_->now();
119  auto goal_msg = Wait::Goal();
120  goal_msg.time = rclcpp::Duration(wait_time, 0.0);
121 
122  RCLCPP_INFO(this->node_->get_logger(), "Sending goal");
123 
124  auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
125 
126  if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
127  rclcpp::FutureReturnCode::SUCCESS)
128  {
129  RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
130  return false;
131  }
132 
133  rclcpp_action::ClientGoalHandle<Wait>::SharedPtr goal_handle = goal_handle_future.get();
134  if (!goal_handle) {
135  RCLCPP_ERROR(node_->get_logger(), "Goal was rejected by server");
136  return false;
137  }
138 
139  // Wait for the server to be done with the goal
140  auto result_future = client_ptr_->async_get_result(goal_handle);
141 
142  RCLCPP_INFO(node_->get_logger(), "Waiting for result");
143  if (rclcpp::spin_until_future_complete(node_, result_future) !=
144  rclcpp::FutureReturnCode::SUCCESS)
145  {
146  RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
147  return false;
148  }
149 
150  rclcpp_action::ClientGoalHandle<Wait>::WrappedResult wrapped_result = result_future.get();
151 
152  switch (wrapped_result.code) {
153  case rclcpp_action::ResultCode::SUCCEEDED: break;
154  case rclcpp_action::ResultCode::ABORTED: RCLCPP_ERROR(
155  node_->get_logger(),
156  "Goal was aborted");
157  return false;
158  case rclcpp_action::ResultCode::CANCELED: RCLCPP_ERROR(
159  node_->get_logger(),
160  "Goal was canceled");
161  return false;
162  default: RCLCPP_ERROR(node_->get_logger(), "Unknown result code");
163  return false;
164  }
165 
166  RCLCPP_INFO(node_->get_logger(), "result received");
167 
168  if ((node_->now() - start_time).seconds() < static_cast<double>(wait_time)) {
169  return false;
170  }
171 
172  return true;
173 }
174 
175 bool WaitBehaviorTester::behaviorTestCancel(
176  const float wait_time)
177 {
178  if (!is_active_) {
179  RCLCPP_ERROR(node_->get_logger(), "Not activated");
180  return false;
181  }
182 
183  // Sleep to let behavior server be ready for serving in multiple runs
184  std::this_thread::sleep_for(5s);
185 
186  auto start_time = node_->now();
187  auto goal_msg = Wait::Goal();
188  goal_msg.time = rclcpp::Duration(wait_time, 0.0);
189 
190  RCLCPP_INFO(this->node_->get_logger(), "Sending goal");
191 
192  auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
193 
194  if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
195  rclcpp::FutureReturnCode::SUCCESS)
196  {
197  RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
198  return false;
199  }
200 
201  rclcpp_action::ClientGoalHandle<Wait>::SharedPtr goal_handle = goal_handle_future.get();
202  if (!goal_handle) {
203  RCLCPP_ERROR(node_->get_logger(), "Goal was rejected by server");
204  return false;
205  }
206 
207  // Wait for the server to be done with the goal
208  auto result_future = client_ptr_->async_cancel_all_goals();
209 
210  RCLCPP_INFO(node_->get_logger(), "Waiting for cancellation");
211  if (rclcpp::spin_until_future_complete(node_, result_future) !=
212  rclcpp::FutureReturnCode::SUCCESS)
213  {
214  RCLCPP_ERROR(node_->get_logger(), "get cancel result call failed :(");
215  return false;
216  }
217 
218  auto status = goal_handle_future.get()->get_status();
219 
220  switch (status) {
221  case rclcpp_action::GoalStatus::STATUS_SUCCEEDED: RCLCPP_ERROR(
222  node_->get_logger(),
223  "Goal succeeded");
224  return false;
225  case rclcpp_action::GoalStatus::STATUS_ABORTED: RCLCPP_ERROR(
226  node_->get_logger(),
227  "Goal was aborted");
228  return false;
229  case rclcpp_action::GoalStatus::STATUS_CANCELED: RCLCPP_INFO(
230  node_->get_logger(),
231  "Goal was canceled");
232  return true;
233  case rclcpp_action::GoalStatus::STATUS_CANCELING: RCLCPP_INFO(
234  node_->get_logger(),
235  "Goal is cancelling");
236  return true;
237  case rclcpp_action::GoalStatus::STATUS_EXECUTING: RCLCPP_ERROR(
238  node_->get_logger(),
239  "Goal is executing");
240  return false;
241  case rclcpp_action::GoalStatus::STATUS_ACCEPTED: RCLCPP_ERROR(
242  node_->get_logger(),
243  "Goal is processing");
244  return false;
245  default: RCLCPP_ERROR(node_->get_logger(), "Unknown result code");
246  return false;
247  }
248 
249  return false;
250 }
251 
252 void WaitBehaviorTester::sendInitialPose()
253 {
254  geometry_msgs::msg::PoseWithCovarianceStamped pose;
255  pose.header.frame_id = "map";
256  pose.header.stamp = rclcpp::Time();
257  pose.pose.pose.position.x = -2.0;
258  pose.pose.pose.position.y = -0.5;
259  pose.pose.pose.position.z = 0.0;
260  pose.pose.pose.orientation.x = 0.0;
261  pose.pose.pose.orientation.y = 0.0;
262  pose.pose.pose.orientation.z = 0.0;
263  pose.pose.pose.orientation.w = 1.0;
264  for (int i = 0; i < 35; i++) {
265  pose.pose.covariance[i] = 0.0;
266  }
267  pose.pose.covariance[0] = 0.08;
268  pose.pose.covariance[7] = 0.08;
269  pose.pose.covariance[35] = 0.05;
270 
271  publisher_->publish(pose);
272  RCLCPP_INFO(node_->get_logger(), "Sent initial pose");
273 }
274 
275 void WaitBehaviorTester::amclPoseCallback(
276  const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr)
277 {
278  initial_pose_received_ = true;
279 }
280 
281 } // namespace nav2_system_tests