mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AR_WPNav: remove unused speed_min
This commit is contained in:
parent
537874c075
commit
a91025fa16
@ -53,16 +53,7 @@ const AP_Param::GroupInfo AR_WPNav::var_info[] = {
|
||||
|
||||
// 4 was PIVOT_ANGLE
|
||||
// 5 was PIVOT_RATE
|
||||
|
||||
// @Param: SPEED_MIN
|
||||
// @DisplayName: Waypoint speed minimum
|
||||
// @Description: Vehicle will not slow below this speed for corners. Should be set to boat's plane speed. Does not apply to pivot turns.
|
||||
// @Units: m/s
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("SPEED_MIN", 6, AR_WPNav, _speed_min, 0),
|
||||
|
||||
// 6 was SPEED_MIN
|
||||
// 7 was PIVOT_DELAY
|
||||
|
||||
// @Group: PIVOT_
|
||||
@ -493,18 +484,6 @@ void AR_WPNav::set_turn_params(float turn_radius, bool pivot_possible)
|
||||
_pivot.enable(pivot_possible);
|
||||
}
|
||||
|
||||
// adjust speed to ensure it does not fall below value held in SPEED_MIN
|
||||
// desired_speed should always be positive (or zero)
|
||||
void AR_WPNav::apply_speed_min(float &desired_speed) const
|
||||
{
|
||||
if (!is_positive(_speed_min) || (_speed_min > _speed_max)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// ensure speed does not fall below minimum
|
||||
desired_speed = MAX(desired_speed, _speed_min);
|
||||
}
|
||||
|
||||
// calculate the crosstrack error
|
||||
float AR_WPNav::calc_crosstrack_error(const Location& current_loc) const
|
||||
{
|
||||
|
@ -121,10 +121,6 @@ protected:
|
||||
// calculate steering and speed to drive along line from origin to destination waypoint
|
||||
void update_steering_and_speed(const Location ¤t_loc, float dt);
|
||||
|
||||
// adjust speed to ensure it does not fall below value held in SPEED_MIN
|
||||
// desired_speed should always be positive (or zero)
|
||||
void apply_speed_min(float &desired_speed) const;
|
||||
|
||||
// calculate the crosstrack error (does not rely on L1 controller)
|
||||
float calc_crosstrack_error(const Location& current_loc) const;
|
||||
|
||||
@ -138,7 +134,6 @@ protected:
|
||||
|
||||
// parameters
|
||||
AP_Float _speed_max; // target speed between waypoints in m/s
|
||||
AP_Float _speed_min; // target speed minimum in m/s. Vehicle will not slow below this speed for corners
|
||||
AP_Float _radius; // distance in meters from a waypoint when we consider the waypoint has been reached
|
||||
AR_PivotTurn _pivot; // pivot turn controller
|
||||
AP_Float _accel_max; // max acceleration. If zero then attitude controller's specified max accel is used
|
||||
|
Loading…
Reference in New Issue
Block a user