Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
spin.cpp
1 // Copyright (c) 2018 Intel Corporation, 2019 Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <cmath>
16 #include <thread>
17 #include <algorithm>
18 #include <memory>
19 #include <utility>
20 
21 #include "nav2_behaviors/plugins/spin.hpp"
22 #include "tf2/utils.hpp"
23 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
24 #include "nav2_util/node_utils.hpp"
25 
26 using namespace std::chrono_literals;
27 
28 namespace nav2_behaviors
29 {
30 
31 Spin::Spin()
32 : TimedBehavior<SpinAction>(),
33  feedback_(std::make_shared<SpinAction::Feedback>()),
34  min_rotational_vel_(0.0),
35  max_rotational_vel_(0.0),
36  rotational_acc_lim_(0.0),
37  cmd_yaw_(0.0),
38  prev_yaw_(0.0),
39  relative_yaw_(0.0),
40  simulate_ahead_time_(0.0)
41 {
42 }
43 
44 Spin::~Spin() = default;
45 
47 {
48  auto node = node_.lock();
49  if (!node) {
50  throw std::runtime_error{"Failed to lock node"};
51  }
52 
53  nav2_util::declare_parameter_if_not_declared(
54  node,
55  "simulate_ahead_time", rclcpp::ParameterValue(2.0));
56  node->get_parameter("simulate_ahead_time", simulate_ahead_time_);
57 
58  nav2_util::declare_parameter_if_not_declared(
59  node,
60  "max_rotational_vel", rclcpp::ParameterValue(1.0));
61  node->get_parameter("max_rotational_vel", max_rotational_vel_);
62 
63  nav2_util::declare_parameter_if_not_declared(
64  node,
65  "min_rotational_vel", rclcpp::ParameterValue(0.4));
66  node->get_parameter("min_rotational_vel", min_rotational_vel_);
67 
68  nav2_util::declare_parameter_if_not_declared(
69  node,
70  "rotational_acc_lim", rclcpp::ParameterValue(3.2));
71  node->get_parameter("rotational_acc_lim", rotational_acc_lim_);
72 }
73 
74 ResultStatus Spin::onRun(const std::shared_ptr<const SpinActionGoal> command)
75 {
76  geometry_msgs::msg::PoseStamped current_pose;
77  if (!nav2_util::getCurrentPose(
78  current_pose, *tf_, local_frame_, robot_base_frame_,
79  transform_tolerance_))
80  {
81  std::string error_msg = "Current robot pose is not available.";
82  RCLCPP_ERROR(logger_, error_msg.c_str());
83  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR, error_msg};
84  }
85 
86  prev_yaw_ = tf2::getYaw(current_pose.pose.orientation);
87  relative_yaw_ = 0.0;
88 
89  cmd_yaw_ = command->target_yaw;
90  RCLCPP_INFO(
91  logger_, "Turning %0.2f for spin behavior.",
92  cmd_yaw_);
93 
94  command_time_allowance_ = command->time_allowance;
95  cmd_disable_collision_checks_ = command->disable_collision_checks;
96  end_time_ = this->clock_->now() + command_time_allowance_;
97 
98  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE, ""};
99 }
100 
102 {
103  rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
104  if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
105  stopRobot();
106  std::string error_msg = "Exceeded time allowance before reaching the Spin goal - Exiting Spin";
107  RCLCPP_WARN(logger_, error_msg.c_str());
108  return ResultStatus{Status::FAILED, SpinActionResult::TIMEOUT, error_msg};
109  }
110 
111  geometry_msgs::msg::PoseStamped current_pose;
112  if (!nav2_util::getCurrentPose(
113  current_pose, *tf_, local_frame_, robot_base_frame_,
114  transform_tolerance_))
115  {
116  std::string error_msg = "Current robot pose is not available.";
117  RCLCPP_ERROR(logger_, error_msg.c_str());
118  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR, error_msg};
119  }
120 
121  const double current_yaw = tf2::getYaw(current_pose.pose.orientation);
122 
123  double delta_yaw = current_yaw - prev_yaw_;
124  if (abs(delta_yaw) > M_PI) {
125  delta_yaw = copysign(2 * M_PI - abs(delta_yaw), prev_yaw_);
126  }
127 
128  relative_yaw_ += delta_yaw;
129  prev_yaw_ = current_yaw;
130 
131  feedback_->angular_distance_traveled = static_cast<float>(relative_yaw_);
132  action_server_->publish_feedback(feedback_);
133 
134  double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_);
135  if (remaining_yaw < 1e-6) {
136  stopRobot();
137  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE, ""};
138  }
139 
140  double vel = sqrt(2 * rotational_acc_lim_ * remaining_yaw);
141  vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
142 
143  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
144  cmd_vel->header.frame_id = robot_base_frame_;
145  cmd_vel->header.stamp = clock_->now();
146  cmd_vel->twist.angular.z = copysign(vel, cmd_yaw_);
147 
148  geometry_msgs::msg::Pose2D pose2d;
149  pose2d.x = current_pose.pose.position.x;
150  pose2d.y = current_pose.pose.position.y;
151  pose2d.theta = tf2::getYaw(current_pose.pose.orientation);
152 
153  if (!isCollisionFree(relative_yaw_, cmd_vel->twist, pose2d)) {
154  stopRobot();
155  std::string error_msg = "Collision Ahead - Exiting Spin";
156  RCLCPP_WARN(logger_, error_msg.c_str());
157  return ResultStatus{Status::FAILED, SpinActionResult::COLLISION_AHEAD, error_msg};
158  }
159 
160  vel_pub_->publish(std::move(cmd_vel));
161 
162  return ResultStatus{Status::RUNNING, SpinActionResult::NONE, ""};
163 }
164 
166  const double & relative_yaw,
167  const geometry_msgs::msg::Twist & cmd_vel,
168  geometry_msgs::msg::Pose2D & pose2d)
169 {
170  if (cmd_disable_collision_checks_) {
171  return true;
172  }
173 
174  // Simulate ahead by simulate_ahead_time_ in cycle_frequency_ increments
175  int cycle_count = 0;
176  double sim_position_change;
177  const int max_cycle_count = static_cast<int>(cycle_frequency_ * simulate_ahead_time_);
178  geometry_msgs::msg::Pose2D init_pose = pose2d;
179  bool fetch_data = true;
180 
181  while (cycle_count < max_cycle_count) {
182  sim_position_change = cmd_vel.angular.z * (cycle_count / cycle_frequency_);
183  pose2d.theta = init_pose.theta + sim_position_change;
184  cycle_count++;
185 
186  if (abs(relative_yaw) - abs(sim_position_change) <= 0.) {
187  break;
188  }
189 
190  if (!local_collision_checker_->isCollisionFree(pose2d, fetch_data)) {
191  return false;
192  }
193  fetch_data = false;
194  }
195  return true;
196 }
197 
198 } // namespace nav2_behaviors
199 
200 #include "pluginlib/class_list_macros.hpp"
201 PLUGINLIB_EXPORT_CLASS(nav2_behaviors::Spin, nav2_core::Behavior)
An action server behavior for spinning in.
Definition: spin.hpp:36
ResultStatus onRun(const std::shared_ptr< const SpinActionGoal > command) override
Initialization to run behavior.
Definition: spin.cpp:74
ResultStatus onCycleUpdate() override
Loop function to run behavior.
Definition: spin.cpp:101
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
Definition: spin.cpp:165
void onConfigure() override
Configuration of behavior action.
Definition: spin.cpp:46
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:42