AC_Loiter: Add method to change Loiter horizontal maximum speed

This commit is contained in:
Rishabh 2020-04-24 23:53:52 +05:30 committed by Randy Mackay
parent c7f32c2fb4
commit 5b3fe19916
2 changed files with 9 additions and 0 deletions

View File

@ -192,6 +192,12 @@ void AC_Loiter::update(bool avoidance_on)
_pos_control.update_xy_controller();
}
//set maximum horizontal speed
void AC_Loiter::set_max_xy_speed(float max_xy_speed)
{
_speed_cms.set(MAX(max_xy_speed, LOITER_SPEED_MIN));
}
// sanity check parameters
void AC_Loiter::sanity_check_params()
{

View File

@ -52,6 +52,9 @@ public:
/// run the loiter controller
void update(bool avoidance_on = true);
//set maximum horizontal speed
void set_max_xy_speed(float max_xy_speed);
/// get desired roll, pitch which should be fed into stabilize controllers
float get_roll() const { return _pos_control.get_roll_cd(); }
float get_pitch() const { return _pos_control.get_pitch_cd(); }