Nav2 Navigation Stack - rolling  main
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 "nav2_ros_common/node_utils.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 
25 using namespace std::chrono_literals;
26 
27 namespace nav2_behaviors
28 {
29 
30 Spin::Spin()
31 : TimedBehavior<SpinAction>(),
32  feedback_(std::make_shared<SpinAction::Feedback>()),
33  min_rotational_vel_(0.0),
34  max_rotational_vel_(0.0),
35  rotational_acc_lim_(0.0),
36  cmd_yaw_(0.0),
37  prev_yaw_(0.0),
38  relative_yaw_(0.0),
39  simulate_ahead_time_(0.0)
40 {
41 }
42 
43 Spin::~Spin() = default;
44 
46 {
47  auto node = node_.lock();
48  if (!node) {
49  throw std::runtime_error{"Failed to lock node"};
50  }
51 
52  nav2::declare_parameter_if_not_declared(
53  node,
54  "simulate_ahead_time", rclcpp::ParameterValue(2.0));
55  node->get_parameter("simulate_ahead_time", simulate_ahead_time_);
56 
57  nav2::declare_parameter_if_not_declared(
58  node,
59  "max_rotational_vel", rclcpp::ParameterValue(1.0));
60  node->get_parameter("max_rotational_vel", max_rotational_vel_);
61 
62  nav2::declare_parameter_if_not_declared(
63  node,
64  "min_rotational_vel", rclcpp::ParameterValue(0.4));
65  node->get_parameter("min_rotational_vel", min_rotational_vel_);
66 
67  nav2::declare_parameter_if_not_declared(
68  node,
69  "rotational_acc_lim", rclcpp::ParameterValue(3.2));
70  node->get_parameter("rotational_acc_lim", rotational_acc_lim_);
71 }
72 
73 ResultStatus Spin::onRun(const std::shared_ptr<const SpinActionGoal> command)
74 {
75  geometry_msgs::msg::PoseStamped current_pose;
76  if (!nav2_util::getCurrentPose(
77  current_pose, *tf_, local_frame_, robot_base_frame_,
78  transform_tolerance_))
79  {
80  std::string error_msg = "Current robot pose is not available.";
81  RCLCPP_ERROR(logger_, error_msg.c_str());
82  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR, error_msg};
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  cmd_disable_collision_checks_ = command->disable_collision_checks;
95  end_time_ = this->clock_->now() + command_time_allowance_;
96 
97  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE, ""};
98 }
99 
101 {
102  rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
103  if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
104  stopRobot();
105  std::string error_msg = "Exceeded time allowance before reaching the Spin goal - Exiting Spin";
106  RCLCPP_WARN(logger_, error_msg.c_str());
107  return ResultStatus{Status::FAILED, SpinActionResult::TIMEOUT, error_msg};
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  std::string error_msg = "Current robot pose is not available.";
116  RCLCPP_ERROR(logger_, error_msg.c_str());
117  return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR, error_msg};
118  }
119 
120  const double current_yaw = tf2::getYaw(current_pose.pose.orientation);
121 
122  double delta_yaw = current_yaw - prev_yaw_;
123  if (abs(delta_yaw) > M_PI) {
124  delta_yaw = copysign(2 * M_PI - abs(delta_yaw), prev_yaw_);
125  }
126 
127  relative_yaw_ += delta_yaw;
128  prev_yaw_ = current_yaw;
129 
130  feedback_->angular_distance_traveled = static_cast<float>(relative_yaw_);
131  action_server_->publish_feedback(feedback_);
132 
133  double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_);
134  if (remaining_yaw < 1e-6) {
135  stopRobot();
136  return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE, ""};
137  }
138 
139  double vel = sqrt(2 * rotational_acc_lim_ * remaining_yaw);
140  vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
141 
142  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
143  cmd_vel->header.frame_id = robot_base_frame_;
144  cmd_vel->header.stamp = clock_->now();
145  cmd_vel->twist.angular.z = copysign(vel, cmd_yaw_);
146 
147  geometry_msgs::msg::Pose pose = current_pose.pose;
148 
149  if (!isCollisionFree(relative_yaw_, cmd_vel->twist, pose)) {
150  stopRobot();
151  std::string error_msg = "Collision Ahead - Exiting Spin";
152  RCLCPP_WARN(logger_, error_msg.c_str());
153  return ResultStatus{Status::FAILED, SpinActionResult::COLLISION_AHEAD, error_msg};
154  }
155 
156  vel_pub_->publish(std::move(cmd_vel));
157 
158  return ResultStatus{Status::RUNNING, SpinActionResult::NONE, ""};
159 }
160 
162  const double & relative_yaw,
163  const geometry_msgs::msg::Twist & cmd_vel,
164  geometry_msgs::msg::Pose & pose)
165 {
166  if (cmd_disable_collision_checks_) {
167  return true;
168  }
169 
170  // Simulate ahead by simulate_ahead_time_ in cycle_frequency_ increments
171  int cycle_count = 0;
172  double sim_position_change;
173  const int max_cycle_count = static_cast<int>(cycle_frequency_ * simulate_ahead_time_);
174  geometry_msgs::msg::Pose init_pose = pose;
175  double init_theta = tf2::getYaw(init_pose.orientation);
176  bool fetch_data = true;
177 
178  while (cycle_count < max_cycle_count) {
179  sim_position_change = cmd_vel.angular.z * (cycle_count / cycle_frequency_);
180  double new_theta = init_theta + sim_position_change;
181  pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(new_theta);
182  cycle_count++;
183 
184  if (abs(relative_yaw) - abs(sim_position_change) <= 0.0) {
185  break;
186  }
187 
188  if (!local_collision_checker_->isCollisionFree(pose, fetch_data)) {
189  return false;
190  }
191  fetch_data = false;
192  }
193  return true;
194 }
195 
196 } // namespace nav2_behaviors
197 
198 #include "pluginlib/class_list_macros.hpp"
199 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:73
ResultStatus onCycleUpdate() override
Loop function to run behavior.
Definition: spin.cpp:100
void onConfigure() override
Configuration of behavior action.
Definition: spin.cpp:45
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose &pose)
Check if pose is collision free.
Definition: spin.cpp:161
Abstract interface for behaviors to adhere to with pluginlib.
Definition: behavior.hpp:42