16 #ifndef NAV2_BEHAVIORS__PLUGINS__DRIVE_ON_HEADING_HPP_
17 #define NAV2_BEHAVIORS__PLUGINS__DRIVE_ON_HEADING_HPP_
25 #include "nav2_behaviors/timed_behavior.hpp"
26 #include "nav2_msgs/action/drive_on_heading.hpp"
27 #include "nav2_msgs/action/back_up.hpp"
28 #include "nav2_util/node_utils.hpp"
29 #include "geometry_msgs/msg/twist_stamped.hpp"
31 namespace nav2_behaviors
38 template<
typename ActionT = nav2_msgs::action::DriveOnHeading>
41 using CostmapInfoType = nav2_core::CostmapInfoType;
49 feedback_(std::make_shared<typename ActionT::Feedback>()),
52 command_disable_collision_checks_(false),
53 simulate_ahead_time_(0.0)
66 std::string error_msg;
67 if (command->target.y != 0.0 || command->target.z != 0.0) {
68 error_msg =
"DrivingOnHeading in Y and Z not supported, will only move in X.";
69 RCLCPP_INFO(this->logger_, error_msg.c_str());
70 return ResultStatus{Status::FAILED, ActionT::Result::INVALID_INPUT, error_msg};
74 if (!((command->target.x > 0.0) == (command->speed > 0.0)) ) {
75 error_msg =
"Speed and command sign did not match";
76 RCLCPP_ERROR(this->logger_, error_msg.c_str());
77 return ResultStatus{Status::FAILED, ActionT::Result::INVALID_INPUT, error_msg};
80 command_x_ = command->target.x;
81 command_speed_ = command->speed;
82 command_time_allowance_ = command->time_allowance;
83 command_disable_collision_checks_ = command->disable_collision_checks;
85 end_time_ = this->clock_->now() + command_time_allowance_;
87 if (!nav2_util::getCurrentPose(
88 initial_pose_, *this->tf_, this->local_frame_, this->robot_base_frame_,
89 this->transform_tolerance_))
91 error_msg =
"Initial robot pose is not available.";
92 RCLCPP_ERROR(this->logger_, error_msg.c_str());
93 return ResultStatus{Status::FAILED, ActionT::Result::TF_ERROR, error_msg};
96 return ResultStatus{Status::SUCCEEDED, ActionT::Result::NONE,
""};
105 rclcpp::Duration time_remaining = end_time_ - this->clock_->now();
106 if (time_remaining.seconds() < 0.0 && command_time_allowance_.seconds() > 0.0) {
108 std::string error_msg =
109 "Exceeded time allowance before reaching the DriveOnHeading goal - Exiting DriveOnHeading";
110 RCLCPP_WARN(this->logger_, error_msg.c_str());
111 return ResultStatus{Status::FAILED, ActionT::Result::TIMEOUT, error_msg};
114 geometry_msgs::msg::PoseStamped current_pose;
115 if (!nav2_util::getCurrentPose(
116 current_pose, *this->tf_, this->local_frame_, this->robot_base_frame_,
117 this->transform_tolerance_))
119 std::string error_msg =
"Current robot pose is not available.";
120 RCLCPP_ERROR(this->logger_, error_msg.c_str());
121 return ResultStatus{Status::FAILED, ActionT::Result::TF_ERROR, error_msg};
124 double diff_x = initial_pose_.pose.position.x - current_pose.pose.position.x;
125 double diff_y = initial_pose_.pose.position.y - current_pose.pose.position.y;
126 double distance = hypot(diff_x, diff_y);
128 feedback_->distance_traveled = distance;
129 this->action_server_->publish_feedback(feedback_);
131 if (distance >= std::fabs(command_x_)) {
133 return ResultStatus{Status::SUCCEEDED, ActionT::Result::NONE,
""};
136 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
137 cmd_vel->header.stamp = this->clock_->now();
138 cmd_vel->header.frame_id = this->robot_base_frame_;
139 cmd_vel->twist.linear.y = 0.0;
140 cmd_vel->twist.angular.z = 0.0;
142 double current_speed = last_vel_ == std::numeric_limits<double>::max() ? 0.0 : last_vel_;
143 bool forward = command_speed_ > 0.0;
144 double min_feasible_speed, max_feasible_speed;
146 min_feasible_speed = current_speed + deceleration_limit_ / this->cycle_frequency_;
147 max_feasible_speed = current_speed + acceleration_limit_ / this->cycle_frequency_;
149 min_feasible_speed = current_speed - acceleration_limit_ / this->cycle_frequency_;
150 max_feasible_speed = current_speed - deceleration_limit_ / this->cycle_frequency_;
152 cmd_vel->twist.linear.x = std::clamp(command_speed_, min_feasible_speed, max_feasible_speed);
155 auto remaining_distance = std::fabs(command_x_) - distance;
156 double max_vel_to_stop = std::sqrt(-2.0 * deceleration_limit_ * remaining_distance);
157 if (max_vel_to_stop < std::abs(cmd_vel->twist.linear.x)) {
158 cmd_vel->twist.linear.x = forward ? max_vel_to_stop : -max_vel_to_stop;
162 if (std::fabs(cmd_vel->twist.linear.x) < minimum_speed_) {
163 cmd_vel->twist.linear.x = forward ? minimum_speed_ : -minimum_speed_;
166 geometry_msgs::msg::Pose2D pose2d;
167 pose2d.x = current_pose.pose.position.x;
168 pose2d.y = current_pose.pose.position.y;
169 pose2d.theta = tf2::getYaw(current_pose.pose.orientation);
173 std::string error_msg =
"Collision Ahead - Exiting DriveOnHeading";
174 RCLCPP_WARN(this->logger_, error_msg.c_str());
175 return ResultStatus{Status::FAILED, ActionT::Result::COLLISION_AHEAD, error_msg};
178 last_vel_ = cmd_vel->twist.linear.x;
179 this->vel_pub_->publish(std::move(cmd_vel));
181 return ResultStatus{Status::RUNNING, ActionT::Result::NONE,
""};
190 void onCleanup()
override {last_vel_ = std::numeric_limits<double>::max();}
192 void onActionCompletion(std::shared_ptr<typename ActionT::Result>)
195 last_vel_ = std::numeric_limits<double>::max();
207 const double & distance,
208 const geometry_msgs::msg::Twist & cmd_vel,
209 geometry_msgs::msg::Pose2D & pose2d)
211 if (command_disable_collision_checks_) {
217 double sim_position_change;
218 const double diff_dist = abs(command_x_) - distance;
219 const int max_cycle_count =
static_cast<int>(this->cycle_frequency_ * simulate_ahead_time_);
220 geometry_msgs::msg::Pose2D init_pose = pose2d;
221 bool fetch_data =
true;
223 while (cycle_count < max_cycle_count) {
224 sim_position_change = cmd_vel.linear.x * (cycle_count / this->cycle_frequency_);
225 pose2d.x = init_pose.x + sim_position_change * cos(init_pose.theta);
226 pose2d.y = init_pose.y + sim_position_change * sin(init_pose.theta);
229 if (diff_dist - abs(sim_position_change) <= 0.) {
233 if (!this->local_collision_checker_->isCollisionFree(pose2d, fetch_data)) {
246 auto node = this->node_.lock();
248 throw std::runtime_error{
"Failed to lock node"};
251 nav2_util::declare_parameter_if_not_declared(
253 "simulate_ahead_time", rclcpp::ParameterValue(2.0));
254 node->get_parameter(
"simulate_ahead_time", simulate_ahead_time_);
256 nav2_util::declare_parameter_if_not_declared(
257 node, this->behavior_name_ +
".acceleration_limit",
258 rclcpp::ParameterValue(2.5));
259 nav2_util::declare_parameter_if_not_declared(
260 node, this->behavior_name_ +
".deceleration_limit",
261 rclcpp::ParameterValue(-2.5));
262 nav2_util::declare_parameter_if_not_declared(
263 node, this->behavior_name_ +
".minimum_speed",
264 rclcpp::ParameterValue(0.10));
265 node->get_parameter(this->behavior_name_ +
".acceleration_limit", acceleration_limit_);
266 node->get_parameter(this->behavior_name_ +
".deceleration_limit", deceleration_limit_);
267 node->get_parameter(this->behavior_name_ +
".minimum_speed", minimum_speed_);
268 if (acceleration_limit_ <= 0.0 || deceleration_limit_ >= 0.0) {
269 RCLCPP_ERROR(this->logger_,
270 "DriveOnHeading: acceleration_limit and deceleration_limit must be "
271 "positive and negative respectively");
272 acceleration_limit_ = std::abs(acceleration_limit_);
273 deceleration_limit_ = -std::abs(deceleration_limit_);
277 typename ActionT::Feedback::SharedPtr feedback_;
279 geometry_msgs::msg::PoseStamped initial_pose_;
281 double command_speed_;
282 bool command_disable_collision_checks_;
283 rclcpp::Duration command_time_allowance_{0, 0};
284 rclcpp::Time end_time_;
285 double simulate_ahead_time_;
286 double acceleration_limit_;
287 double deceleration_limit_;
288 double minimum_speed_;
289 double last_vel_ = std::numeric_limits<double>::max();
An action server Behavior for spinning in.
ResultStatus onCycleUpdate() override
Loop function to run behavior.
void onConfigure() override
Configuration of behavior action.
DriveOnHeading()
A constructor for nav2_behaviors::DriveOnHeading.
bool isCollisionFree(const double &distance, const geometry_msgs::msg::Twist &cmd_vel, geometry_msgs::msg::Pose2D &pose2d)
Check if pose is collision free.
ResultStatus onRun(const std::shared_ptr< const typename ActionT::Goal > command) override
Initialization to run behavior.
CostmapInfoType getResourceInfo() override
Method to determine the required costmap info.