mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-07 05:23:06 +08:00
this fixes several places that set the alt field directly. The only one that is a real bug is in CIRCLE where if we were terrain following and change into CIRCLE mode we would climb to current alt + home alt
24 lines
576 B
C++
24 lines
576 B
C++
#include "mode.h"
|
|
#include "Plane.h"
|
|
|
|
bool ModeCircle::_enter()
|
|
{
|
|
// the altitude to circle at is taken from the current altitude
|
|
plane.next_WP_loc = plane.current_loc;
|
|
|
|
return true;
|
|
}
|
|
|
|
void ModeCircle::update()
|
|
{
|
|
// we have no GPS installed and have lost radio contact
|
|
// or we just want to fly around in a gentle circle w/o GPS,
|
|
// holding altitude at the altitude we set when we
|
|
// switched into the mode
|
|
plane.nav_roll_cd = plane.roll_limit_cd / 3;
|
|
plane.update_load_factor();
|
|
plane.calc_nav_pitch();
|
|
plane.calc_throttle();
|
|
}
|
|
|