19
19
#include < chrono>
20
20
#include < memory>
21
21
#include < utility>
22
+ #include < limits>
22
23
23
24
#include " nav2_behaviors/timed_behavior.hpp"
24
25
#include " nav2_msgs/action/drive_on_heading.hpp"
@@ -126,7 +127,35 @@ class DriveOnHeading : public TimedBehavior<ActionT>
126
127
auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
127
128
cmd_vel->linear .y = 0.0 ;
128
129
cmd_vel->angular .z = 0.0 ;
129
- cmd_vel->linear .x = command_speed_;
130
+
131
+ bool forward = command_speed_ > 0.0 ;
132
+ if (acceleration_limit_ == 0.0 || deceleration_limit_ == 0.0 ) {
133
+ RCLCPP_INFO_ONCE (this ->logger_ , " DriveOnHeading: no acceleration or deceleration limits set" );
134
+ cmd_vel->linear .x = command_speed_;
135
+ } else {
136
+ double current_speed = last_vel_ == std::numeric_limits<double >::max () ? 0.0 : last_vel_;
137
+ double min_feasible_speed, max_feasible_speed;
138
+ if (forward) {
139
+ min_feasible_speed = current_speed + deceleration_limit_ / this ->cycle_frequency_ ;
140
+ max_feasible_speed = current_speed + acceleration_limit_ / this ->cycle_frequency_ ;
141
+ } else {
142
+ min_feasible_speed = current_speed - acceleration_limit_ / this ->cycle_frequency_ ;
143
+ max_feasible_speed = current_speed - deceleration_limit_ / this ->cycle_frequency_ ;
144
+ }
145
+ cmd_vel->linear .x = std::clamp (command_speed_, min_feasible_speed, max_feasible_speed);
146
+
147
+ // Check if we need to slow down to avoid overshooting
148
+ auto remaining_distance = std::fabs (command_x_) - distance;
149
+ double max_vel_to_stop = std::sqrt (-2.0 * deceleration_limit_ * remaining_distance);
150
+ if (max_vel_to_stop < std::abs (cmd_vel->linear .x )) {
151
+ cmd_vel->linear .x = forward ? max_vel_to_stop : -max_vel_to_stop;
152
+ }
153
+ }
154
+
155
+ // Ensure we don't go below minimum speed
156
+ if (std::fabs (cmd_vel->linear .x ) < minimum_speed_) {
157
+ cmd_vel->linear .x = forward ? minimum_speed_ : -minimum_speed_;
158
+ }
130
159
131
160
geometry_msgs::msg::Pose2D pose2d;
132
161
pose2d.x = current_pose.pose .position .x ;
@@ -139,11 +168,19 @@ class DriveOnHeading : public TimedBehavior<ActionT>
139
168
return Status::FAILED;
140
169
}
141
170
171
+ last_vel_ = cmd_vel->linear .x ;
142
172
this ->vel_pub_ ->publish (std::move (cmd_vel));
143
173
144
174
return Status::RUNNING;
145
175
}
146
176
177
+ void onCleanup () override {last_vel_ = std::numeric_limits<double >::max ();}
178
+
179
+ void onActionCompletion () override
180
+ {
181
+ last_vel_ = std::numeric_limits<double >::max ();
182
+ }
183
+
147
184
protected:
148
185
/* *
149
186
* @brief Check if pose is collision free
@@ -197,6 +234,26 @@ class DriveOnHeading : public TimedBehavior<ActionT>
197
234
node,
198
235
" simulate_ahead_time" , rclcpp::ParameterValue (2.0 ));
199
236
node->get_parameter (" simulate_ahead_time" , simulate_ahead_time_);
237
+
238
+ nav2_util::declare_parameter_if_not_declared (
239
+ node, this ->behavior_name_ + " .acceleration_limit" ,
240
+ rclcpp::ParameterValue (0.0 ));
241
+ nav2_util::declare_parameter_if_not_declared (
242
+ node, this ->behavior_name_ + " .deceleration_limit" ,
243
+ rclcpp::ParameterValue (0.0 ));
244
+ nav2_util::declare_parameter_if_not_declared (
245
+ node, this ->behavior_name_ + " .minimum_speed" ,
246
+ rclcpp::ParameterValue (0.0 ));
247
+ node->get_parameter (this ->behavior_name_ + " .acceleration_limit" , acceleration_limit_);
248
+ node->get_parameter (this ->behavior_name_ + " .deceleration_limit" , deceleration_limit_);
249
+ node->get_parameter (this ->behavior_name_ + " .minimum_speed" , minimum_speed_);
250
+ if (acceleration_limit_ < 0.0 || deceleration_limit_ > 0.0 ) {
251
+ RCLCPP_ERROR (this ->logger_ ,
252
+ " DriveOnHeading: acceleration_limit and deceleration_limit must be "
253
+ " positive and negative respectively" );
254
+ acceleration_limit_ = std::abs (acceleration_limit_);
255
+ deceleration_limit_ = -std::abs (deceleration_limit_);
256
+ }
200
257
}
201
258
202
259
typename ActionT::Feedback::SharedPtr feedback_;
@@ -207,6 +264,10 @@ class DriveOnHeading : public TimedBehavior<ActionT>
207
264
rclcpp::Duration command_time_allowance_{0 , 0 };
208
265
rclcpp::Time end_time_;
209
266
double simulate_ahead_time_;
267
+ double acceleration_limit_;
268
+ double deceleration_limit_;
269
+ double minimum_speed_;
270
+ double last_vel_ = std::numeric_limits<double >::max();
210
271
};
211
272
212
273
} // namespace nav2_behaviors
0 commit comments