Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
assisted_teleop_behavior_tester.cpp
1 // Copyright (c) 2020 Sarthak Mittal
2 // Copyright (c) 2018 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License. Reserved.
15 
16 #include <string>
17 #include <random>
18 #include <tuple>
19 #include <memory>
20 #include <iostream>
21 #include <chrono>
22 #include <sstream>
23 #include <iomanip>
24 
25 #include "assisted_teleop_behavior_tester.hpp"
26 #include "nav2_util/geometry_utils.hpp"
27 
28 using namespace std::chrono_literals;
29 using namespace std::chrono; // NOLINT
30 
31 namespace nav2_system_tests
32 {
33 
34 AssistedTeleopBehaviorTester::AssistedTeleopBehaviorTester()
35 : is_active_(false),
36  initial_pose_received_(false)
37 {
38  node_ = rclcpp::Node::make_shared("assisted_teleop_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<AssistedTeleop>(
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  "assisted_teleop");
49 
50  initial_pose_pub_ =
51  node_->create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>("initialpose", 10);
52 
53  preempt_pub_ =
54  node_->create_publisher<std_msgs::msg::Empty>("preempt_teleop", 10);
55 
56  cmd_vel_pub_ =
57  node_->create_publisher<geometry_msgs::msg::TwistStamped>("cmd_vel_teleop", 10);
58 
59  subscription_ = node_->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
60  "amcl_pose", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(),
61  std::bind(&AssistedTeleopBehaviorTester::amclPoseCallback, this, std::placeholders::_1));
62 
63  filtered_vel_sub_ = node_->create_subscription<geometry_msgs::msg::TwistStamped>(
64  "cmd_vel",
65  rclcpp::SystemDefaultsQoS(),
66  std::bind(&AssistedTeleopBehaviorTester::filteredVelCallback, this, std::placeholders::_1));
67 
68  std::string costmap_topic = "/local_costmap/costmap_raw";
69  std::string footprint_topic = "/local_costmap/published_footprint";
70 
71  costmap_sub_ = std::make_shared<nav2_costmap_2d::CostmapSubscriber>(
72  node_,
73  costmap_topic);
74 
75  footprint_sub_ = std::make_shared<nav2_costmap_2d::FootprintSubscriber>(
76  node_,
77  footprint_topic,
78  *tf_buffer_);
79 
80  collision_checker_ = std::make_unique<nav2_costmap_2d::CostmapTopicCollisionChecker>(
81  *costmap_sub_,
82  *footprint_sub_
83  );
84 
85  stamp_ = node_->now();
86 }
87 
88 AssistedTeleopBehaviorTester::~AssistedTeleopBehaviorTester()
89 {
90  if (is_active_) {
91  deactivate();
92  }
93 }
94 
95 void AssistedTeleopBehaviorTester::activate()
96 {
97  if (is_active_) {
98  throw std::runtime_error("Trying to activate while already active");
99  return;
100  }
101 
102  while (!initial_pose_received_) {
103  RCLCPP_WARN(node_->get_logger(), "Initial pose not received");
104  sendInitialPose();
105  std::this_thread::sleep_for(100ms);
106  rclcpp::spin_some(node_);
107  }
108 
109  // Wait for lifecycle_manager_navigation to activate behavior_server
110  std::this_thread::sleep_for(10s);
111 
112  if (!client_ptr_) {
113  RCLCPP_ERROR(node_->get_logger(), "Action client not initialized");
114  is_active_ = false;
115  return;
116  }
117 
118  if (!client_ptr_->wait_for_action_server(10s)) {
119  RCLCPP_ERROR(node_->get_logger(), "Action server not available after waiting");
120  is_active_ = false;
121  return;
122  }
123 
124  RCLCPP_INFO(this->node_->get_logger(), "Assisted Teleop action server is ready");
125  is_active_ = true;
126 }
127 
128 void AssistedTeleopBehaviorTester::deactivate()
129 {
130  if (!is_active_) {
131  throw std::runtime_error("Trying to deactivate while already inactive");
132  }
133  is_active_ = false;
134 }
135 
136 bool AssistedTeleopBehaviorTester::defaultAssistedTeleopTest(
137  const float lin_vel,
138  const float ang_vel)
139 {
140  if (!is_active_) {
141  RCLCPP_ERROR(node_->get_logger(), "Not activated");
142  return false;
143  }
144 
145  RCLCPP_INFO(node_->get_logger(), "Sending goal");
146 
147  auto goal_handle_future = client_ptr_->async_send_goal(nav2_msgs::action::AssistedTeleop::Goal());
148 
149  if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
150  rclcpp::FutureReturnCode::SUCCESS)
151  {
152  RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
153  return false;
154  }
155 
156  rclcpp_action::ClientGoalHandle<AssistedTeleop>::SharedPtr goal_handle = goal_handle_future.get();
157  if (!goal_handle) {
158  RCLCPP_ERROR(node_->get_logger(), "Goal was rejected by server");
159  return false;
160  }
161 
162  // Wait for the server to be done with the goal
163  auto result_future = client_ptr_->async_get_result(goal_handle);
164 
165  rclcpp::Rate r(1);
166 
167  counter_ = 0;
168  auto start_time = std::chrono::system_clock::now();
169  while (rclcpp::ok()) {
170  geometry_msgs::msg::TwistStamped cmd_vel = geometry_msgs::msg::TwistStamped();
171  cmd_vel.twist.linear.x = lin_vel;
172  cmd_vel.twist.angular.z = ang_vel;
173  cmd_vel_pub_->publish(cmd_vel);
174 
175  if (counter_ > 1) {
176  break;
177  }
178 
179  auto current_time = std::chrono::system_clock::now();
180  if (current_time - start_time > 25s) {
181  RCLCPP_ERROR(node_->get_logger(), "Exceeded Timeout");
182  return false;
183  }
184 
185  rclcpp::spin_some(node_);
186  r.sleep();
187  }
188 
189  auto preempt_msg = std_msgs::msg::Empty();
190  preempt_pub_->publish(preempt_msg);
191 
192  RCLCPP_INFO(node_->get_logger(), "Waiting for result");
193  if (rclcpp::spin_until_future_complete(node_, result_future) !=
194  rclcpp::FutureReturnCode::SUCCESS)
195  {
196  RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
197  return false;
198  }
199 
200  rclcpp_action::ClientGoalHandle<AssistedTeleop>::WrappedResult
201  wrapped_result = result_future.get();
202 
203  switch (wrapped_result.code) {
204  case rclcpp_action::ResultCode::SUCCEEDED: break;
205  case rclcpp_action::ResultCode::ABORTED: RCLCPP_ERROR(
206  node_->get_logger(),
207  "Goal was aborted");
208  return false;
209  case rclcpp_action::ResultCode::CANCELED: RCLCPP_ERROR(
210  node_->get_logger(),
211  "Goal was canceled");
212  return false;
213  default: RCLCPP_ERROR(node_->get_logger(), "Unknown result code");
214  return false;
215  }
216 
217  RCLCPP_INFO(node_->get_logger(), "result received");
218 
219  geometry_msgs::msg::PoseStamped current_pose;
220  if (!nav2_util::getCurrentPose(current_pose, *tf_buffer_, "odom")) {
221  RCLCPP_ERROR(node_->get_logger(), "Current robot pose is not available.");
222  return false;
223  }
224 
225  geometry_msgs::msg::Pose2D pose_2d;
226  pose_2d.x = current_pose.pose.position.x;
227  pose_2d.y = current_pose.pose.position.y;
228  pose_2d.theta = tf2::getYaw(current_pose.pose.orientation);
229 
230  if (!collision_checker_->isCollisionFree(pose_2d)) {
231  RCLCPP_ERROR(node_->get_logger(), "Ended in collision");
232  return false;
233  }
234 
235  return true;
236 }
237 
238 void AssistedTeleopBehaviorTester::sendInitialPose()
239 {
240  geometry_msgs::msg::PoseWithCovarianceStamped pose;
241  pose.header.frame_id = "map";
242  pose.header.stamp = stamp_;
243  pose.pose.pose.position.x = -2.0;
244  pose.pose.pose.position.y = -0.5;
245  pose.pose.pose.position.z = 0.0;
246  pose.pose.pose.orientation.x = 0.0;
247  pose.pose.pose.orientation.y = 0.0;
248  pose.pose.pose.orientation.z = 0.0;
249  pose.pose.pose.orientation.w = 1.0;
250  for (int i = 0; i < 35; i++) {
251  pose.pose.covariance[i] = 0.0;
252  }
253  pose.pose.covariance[0] = 0.08;
254  pose.pose.covariance[7] = 0.08;
255  pose.pose.covariance[35] = 0.05;
256 
257  initial_pose_pub_->publish(pose);
258  RCLCPP_INFO(node_->get_logger(), "Sent initial pose");
259 }
260 
261 void AssistedTeleopBehaviorTester::amclPoseCallback(
262  const geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr)
263 {
264  initial_pose_received_ = true;
265 }
266 
267 void AssistedTeleopBehaviorTester::filteredVelCallback(
268  geometry_msgs::msg::TwistStamped::SharedPtr msg)
269 {
270  if (msg->twist.linear.x == 0.0f) {
271  counter_++;
272  } else {
273  counter_ = 0;
274  }
275 }
276 
277 } // namespace nav2_system_tests