mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_WPNav: Add nav velocity gain scaler to interfaces
Allows gains to be adjusted to compensate for optical flow noise
This commit is contained in:
parent
9e7709fa09
commit
11fb51ceba
@ -159,7 +159,7 @@ void AC_Circle::update()
|
||||
}
|
||||
|
||||
// run loiter's position to velocity step
|
||||
_pos_control.update_xy_controller(false);
|
||||
_pos_control.update_xy_controller(false, 1.0f);
|
||||
}
|
||||
|
||||
// get_closest_point_on_circle - returns closest point on the circle
|
||||
|
@ -297,7 +297,7 @@ int32_t AC_WPNav::get_loiter_bearing_to_target() const
|
||||
}
|
||||
|
||||
/// update_loiter - run the loiter controller - should be called at 100hz
|
||||
void AC_WPNav::update_loiter(float ekfGndSpdLimit)
|
||||
void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler)
|
||||
{
|
||||
// calculate dt
|
||||
uint32_t now = hal.scheduler->millis();
|
||||
@ -317,7 +317,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit)
|
||||
_pos_control.trigger_xy();
|
||||
}else{
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(true);
|
||||
_pos_control.update_xy_controller(true, ekfNavVelGainScaler);
|
||||
}
|
||||
}
|
||||
|
||||
@ -627,7 +627,7 @@ void AC_WPNav::update_wpnav()
|
||||
_pos_control.freeze_ff_z();
|
||||
}else{
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(false);
|
||||
_pos_control.update_xy_controller(false, 1.0f);
|
||||
|
||||
// check if leash lengths need updating
|
||||
check_wp_leash_length();
|
||||
@ -892,7 +892,7 @@ void AC_WPNav::update_spline()
|
||||
_pos_control.freeze_ff_z();
|
||||
}else{
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(false);
|
||||
_pos_control.update_xy_controller(false, 1.0f);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -95,7 +95,7 @@ public:
|
||||
int32_t get_loiter_bearing_to_target() const;
|
||||
|
||||
/// update_loiter - run the loiter controller - should be called at 10hz
|
||||
void update_loiter(float ekfGndSpdLimit);
|
||||
void update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler);
|
||||
|
||||
///
|
||||
/// waypoint controller
|
||||
|
Loading…
Reference in New Issue
Block a user