Nav2 Navigation Stack - jazzy  jazzy
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.h"
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  RCLCPP_ERROR(logger_, "Current robot pose is not available.");
82  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR};
83  }
84 
85  prev_yaw_ = tf2::getYaw(current_pose.pose.orientation);
86  relative_yaw_ = 0.0;
87 
88  cmd_yaw_ = command->target_yaw;
89  RCLCPP_INFO(
90  logger_, "Turning %0.2f for spin behavior.",
91  cmd_yaw_);
92 
93  command_time_allowance_ = command->time_allowance;
94  end_time_ = this->clock_->now() + command_time_allowance_;
95 
96  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE};
97 }
98 
100 {
101  rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
102  if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
103  stopRobot();
104  RCLCPP_WARN(
105  logger_,
106  "Exceeded time allowance before reaching the Spin goal - Exiting Spin");
107  return ResultStatus{Status::FAILED, SpinActionResult::TIMEOUT};
108  }
109 
110  geometry_msgs::msg::PoseStamped current_pose;
111  if (!nav2_util::getCurrentPose(
112  current_pose, *tf_, local_frame_, robot_base_frame_,
113  transform_tolerance_))
114  {
115  RCLCPP_ERROR(logger_, "Current robot pose is not available.");
116  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR};
117  }
118 
119  const double current_yaw = tf2::getYaw(current_pose.pose.orientation);
120 
121  double delta_yaw = current_yaw - prev_yaw_;
122  if (abs(delta_yaw) > M_PI) {
123  delta_yaw = copysign(2 * M_PI - abs(delta_yaw), prev_yaw_);
124  }
125 
126  relative_yaw_ += delta_yaw;
127  prev_yaw_ = current_yaw;
128 
129  feedback_->angular_distance_traveled = static_cast<float>(relative_yaw_);
130  action_server_->publish_feedback(feedback_);
131 
132  double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_);
133  if (remaining_yaw < 1e-6) {
134  stopRobot();
135  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE};
136  }
137 
138  double vel = sqrt(2 * rotational_acc_lim_ * remaining_yaw);
139  vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
140 
141  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
142  cmd_vel->header.frame_id = robot_base_frame_;
143  cmd_vel->header.stamp = clock_->now();
144  cmd_vel->twist.angular.z = copysign(vel, cmd_yaw_);
145 
146  geometry_msgs::msg::Pose2D pose2d;
147  pose2d.x = current_pose.pose.position.x;
148  pose2d.y = current_pose.pose.position.y;
149  pose2d.theta = tf2::getYaw(current_pose.pose.orientation);
150 
151  if (!isCollisionFree(relative_yaw_, cmd_vel->twist, pose2d)) {
152  stopRobot();
153  RCLCPP_WARN(logger_, "Collision Ahead - Exiting Spin");
154  return ResultStatus{Status::FAILED, SpinActionResult::COLLISION_AHEAD};
155  }
156 
157  vel_pub_->publish(std::move(cmd_vel));
158 
159  return ResultStatus{Status::RUNNING, SpinActionResult::NONE};
160 }
161 
163  const double & relative_yaw,
164  const geometry_msgs::msg::Twist & cmd_vel,
165  geometry_msgs::msg::Pose2D & pose2d)
166 {
167  // Simulate ahead by simulate_ahead_time_ in cycle_frequency_ increments
168  int cycle_count = 0;
169  double sim_position_change;
170  const int max_cycle_count = static_cast<int>(cycle_frequency_ * simulate_ahead_time_);
171  geometry_msgs::msg::Pose2D init_pose = pose2d;
172  bool fetch_data = true;
173 
174  while (cycle_count < max_cycle_count) {
175  sim_position_change = cmd_vel.angular.z * (cycle_count / cycle_frequency_);
176  pose2d.theta = init_pose.theta + sim_position_change;
177  cycle_count++;
178 
179  if (abs(relative_yaw) - abs(sim_position_change) <= 0.) {
180  break;
181  }
182 
183  if (!local_collision_checker_->isCollisionFree(pose2d, fetch_data)) {
184  return false;
185  }
186  fetch_data = false;
187  }
188  return true;
189 }
190 
191 } // namespace nav2_behaviors
192 
193 #include "pluginlib/class_list_macros.hpp"
194 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:99
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:162
void onConfigure() override
Configuration of behavior action.
Definition: spin.cpp:46
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:42