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"
26 using namespace std::chrono_literals;
28 namespace nav2_behaviors
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),
40 simulate_ahead_time_(0.0)
44 Spin::~Spin() =
default;
48 auto node = node_.lock();
50 throw std::runtime_error{
"Failed to lock node"};
53 nav2_util::declare_parameter_if_not_declared(
55 "simulate_ahead_time", rclcpp::ParameterValue(2.0));
56 node->get_parameter(
"simulate_ahead_time", simulate_ahead_time_);
58 nav2_util::declare_parameter_if_not_declared(
60 "max_rotational_vel", rclcpp::ParameterValue(1.0));
61 node->get_parameter(
"max_rotational_vel", max_rotational_vel_);
63 nav2_util::declare_parameter_if_not_declared(
65 "min_rotational_vel", rclcpp::ParameterValue(0.4));
66 node->get_parameter(
"min_rotational_vel", min_rotational_vel_);
68 nav2_util::declare_parameter_if_not_declared(
70 "rotational_acc_lim", rclcpp::ParameterValue(3.2));
71 node->get_parameter(
"rotational_acc_lim", rotational_acc_lim_);
76 geometry_msgs::msg::PoseStamped current_pose;
77 if (!nav2_util::getCurrentPose(
78 current_pose, *tf_, local_frame_, robot_base_frame_,
79 transform_tolerance_))
81 RCLCPP_ERROR(logger_,
"Current robot pose is not available.");
82 return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR};
85 prev_yaw_ = tf2::getYaw(current_pose.pose.orientation);
88 cmd_yaw_ = command->target_yaw;
90 logger_,
"Turning %0.2f for spin behavior.",
93 command_time_allowance_ = command->time_allowance;
94 end_time_ = this->clock_->now() + command_time_allowance_;
96 return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE};
101 rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
102 if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
106 "Exceeded time allowance before reaching the Spin goal - Exiting Spin");
107 return ResultStatus{Status::FAILED, SpinActionResult::TIMEOUT};
110 geometry_msgs::msg::PoseStamped current_pose;
111 if (!nav2_util::getCurrentPose(
112 current_pose, *tf_, local_frame_, robot_base_frame_,
113 transform_tolerance_))
115 RCLCPP_ERROR(logger_,
"Current robot pose is not available.");
116 return ResultStatus{Status::FAILED, SpinActionResult::TF_ERROR};
119 const double current_yaw = tf2::getYaw(current_pose.pose.orientation);
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_);
126 relative_yaw_ += delta_yaw;
127 prev_yaw_ = current_yaw;
129 feedback_->angular_distance_traveled =
static_cast<float>(relative_yaw_);
130 action_server_->publish_feedback(feedback_);
132 double remaining_yaw = abs(cmd_yaw_) - abs(relative_yaw_);
133 if (remaining_yaw < 1e-6) {
135 return ResultStatus{Status::SUCCEEDED, SpinActionResult::NONE};
138 double vel = sqrt(2 * rotational_acc_lim_ * remaining_yaw);
139 vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
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_);
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);
153 RCLCPP_WARN(logger_,
"Collision Ahead - Exiting Spin");
154 return ResultStatus{Status::FAILED, SpinActionResult::COLLISION_AHEAD};
157 vel_pub_->publish(std::move(cmd_vel));
159 return ResultStatus{Status::RUNNING, SpinActionResult::NONE};
163 const double & relative_yaw,
164 const geometry_msgs::msg::Twist & cmd_vel,
165 geometry_msgs::msg::Pose2D & pose2d)
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;
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;
179 if (abs(relative_yaw) - abs(sim_position_change) <= 0.) {
183 if (!local_collision_checker_->isCollisionFree(pose2d, fetch_data)) {
193 #include "pluginlib/class_list_macros.hpp"
An action server behavior for spinning in.
ResultStatus onRun(const std::shared_ptr< const SpinActionGoal > command) override
Initialization to run behavior.
ResultStatus onCycleUpdate() override
Loop function to run behavior.
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
void onConfigure() override
Configuration of behavior action.
Abstract interface for behaviors to adhere to with pluginlib.