mirror of https://github.com/ArduPilot/ardupilot
Reinstate the ground course filter for the not-really-suppored SiRF GPS.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@448 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a610577701
commit
80bc831363
|
@ -170,6 +170,8 @@ AP_GPS_SIRF::_parse_gps(void)
|
||||||
longitude = _swapl(&_buffer.nav.longitude);
|
longitude = _swapl(&_buffer.nav.longitude);
|
||||||
altitude = _swapl(&_buffer.nav.altitude_msl);
|
altitude = _swapl(&_buffer.nav.altitude_msl);
|
||||||
ground_speed = _swapi(&_buffer.nav.ground_speed);
|
ground_speed = _swapi(&_buffer.nav.ground_speed);
|
||||||
|
// at low speeds, ground course wanders wildly; suppress changes if we are not moving
|
||||||
|
if (ground_speed > 50)
|
||||||
ground_course = _swapi(&_buffer.nav.ground_course);
|
ground_course = _swapi(&_buffer.nav.ground_course);
|
||||||
num_sats = _buffer.nav.satellites;
|
num_sats = _buffer.nav.satellites;
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -18,8 +18,10 @@ AP_GPS_406 gps(&Serial1);
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(38400);
|
tone(A6, 1000, 200);
|
||||||
Serial1.begin(57600);
|
|
||||||
|
Serial.begin(38400, 16, 128);
|
||||||
|
Serial1.begin(57600, 128, 16);
|
||||||
stderr = stdout;
|
stderr = stdout;
|
||||||
gps.print_errors = true;
|
gps.print_errors = true;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue