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"
@@ -133,7 +134,30 @@ class DriveOnHeading : public TimedBehavior<ActionT>
133
134
cmd_vel->header .frame_id = this ->robot_base_frame_ ;
134
135
cmd_vel->twist .linear .y = 0.0 ;
135
136
cmd_vel->twist .angular .z = 0.0 ;
136
- cmd_vel->twist .linear .x = command_speed_;
137
+
138
+ double current_speed = last_vel_ == std::numeric_limits<double >::max () ? 0.0 : last_vel_;
139
+ bool forward = command_speed_ > 0.0 ;
140
+ double min_feasible_speed, max_feasible_speed;
141
+ if (forward) {
142
+ min_feasible_speed = current_speed + deceleration_limit_ / this ->cycle_frequency_ ;
143
+ max_feasible_speed = current_speed + acceleration_limit_ / this ->cycle_frequency_ ;
144
+ } else {
145
+ min_feasible_speed = current_speed - acceleration_limit_ / this ->cycle_frequency_ ;
146
+ max_feasible_speed = current_speed - deceleration_limit_ / this ->cycle_frequency_ ;
147
+ }
148
+ cmd_vel->twist .linear .x = std::clamp (command_speed_, min_feasible_speed, max_feasible_speed);
149
+
150
+ // Check if we need to slow down to avoid overshooting
151
+ auto remaining_distance = std::fabs (command_x_) - distance;
152
+ double max_vel_to_stop = std::sqrt (-2.0 * deceleration_limit_ * remaining_distance);
153
+ if (max_vel_to_stop < std::abs (cmd_vel->twist .linear .x )) {
154
+ cmd_vel->twist .linear .x = forward ? max_vel_to_stop : -max_vel_to_stop;
155
+ }
156
+
157
+ // Ensure we don't go below minimum speed
158
+ if (std::fabs (cmd_vel->twist .linear .x ) < minimum_speed_) {
159
+ cmd_vel->twist .linear .x = forward ? minimum_speed_ : -minimum_speed_;
160
+ }
137
161
138
162
geometry_msgs::msg::Pose2D pose2d;
139
163
pose2d.x = current_pose.pose .position .x ;
@@ -146,6 +170,7 @@ class DriveOnHeading : public TimedBehavior<ActionT>
146
170
return ResultStatus{Status::FAILED, ActionT::Result::COLLISION_AHEAD};
147
171
}
148
172
173
+ last_vel_ = cmd_vel->twist .linear .x ;
149
174
this ->vel_pub_ ->publish (std::move (cmd_vel));
150
175
151
176
return ResultStatus{Status::RUNNING, ActionT::Result::NONE};
@@ -157,6 +182,14 @@ class DriveOnHeading : public TimedBehavior<ActionT>
157
182
*/
158
183
CostmapInfoType getResourceInfo () override {return CostmapInfoType::LOCAL;}
159
184
185
+ void onCleanup () override {last_vel_ = std::numeric_limits<double >::max ();}
186
+
187
+ void onActionCompletion (std::shared_ptr<typename ActionT::Result>/* result*/ )
188
+ override
189
+ {
190
+ last_vel_ = std::numeric_limits<double >::max ();
191
+ }
192
+
160
193
protected:
161
194
/* *
162
195
* @brief Check if pose is collision free
@@ -214,6 +247,26 @@ class DriveOnHeading : public TimedBehavior<ActionT>
214
247
node,
215
248
" simulate_ahead_time" , rclcpp::ParameterValue (2.0 ));
216
249
node->get_parameter (" simulate_ahead_time" , simulate_ahead_time_);
250
+
251
+ nav2_util::declare_parameter_if_not_declared (
252
+ node, this ->behavior_name_ + " .acceleration_limit" ,
253
+ rclcpp::ParameterValue (2.5 ));
254
+ nav2_util::declare_parameter_if_not_declared (
255
+ node, this ->behavior_name_ + " .deceleration_limit" ,
256
+ rclcpp::ParameterValue (-2.5 ));
257
+ nav2_util::declare_parameter_if_not_declared (
258
+ node, this ->behavior_name_ + " .minimum_speed" ,
259
+ rclcpp::ParameterValue (0.10 ));
260
+ node->get_parameter (this ->behavior_name_ + " .acceleration_limit" , acceleration_limit_);
261
+ node->get_parameter (this ->behavior_name_ + " .deceleration_limit" , deceleration_limit_);
262
+ node->get_parameter (this ->behavior_name_ + " .minimum_speed" , minimum_speed_);
263
+ if (acceleration_limit_ <= 0.0 || deceleration_limit_ >= 0.0 ) {
264
+ RCLCPP_ERROR (this ->logger_ ,
265
+ " DriveOnHeading: acceleration_limit and deceleration_limit must be "
266
+ " positive and negative respectively" );
267
+ acceleration_limit_ = std::abs (acceleration_limit_);
268
+ deceleration_limit_ = -std::abs (deceleration_limit_);
269
+ }
217
270
}
218
271
219
272
typename ActionT::Feedback::SharedPtr feedback_;
@@ -225,6 +278,10 @@ class DriveOnHeading : public TimedBehavior<ActionT>
225
278
rclcpp::Duration command_time_allowance_{0 , 0 };
226
279
rclcpp::Time end_time_;
227
280
double simulate_ahead_time_;
281
+ double acceleration_limit_;
282
+ double deceleration_limit_;
283
+ double minimum_speed_;
284
+ double last_vel_ = std::numeric_limits<double >::max();
228
285
};
229
286
230
287
} // namespace nav2_behaviors
0 commit comments