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:
priseborough 2014-11-16 12:53:16 +11:00 committed by Andrew Tridgell
parent 9e7709fa09
commit 11fb51ceba
3 changed files with 6 additions and 6 deletions

View File

@ -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

View File

@ -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);
}
}

View File

@ -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