mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed examples build
This commit is contained in:
parent
2802814a66
commit
c7141c4851
|
@ -40,11 +40,11 @@ void loop()
|
|||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed / 100.0);
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course / 100, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100, DEC);
|
||||
hal.console->print(" SAT:");
|
||||
hal.console->print(gps.num_sats, DEC);
|
||||
hal.console->print(" FIX:");
|
||||
|
|
|
@ -43,9 +43,9 @@ void loop()
|
|||
hal.console->print(" Lon: ");
|
||||
print_latlon(hal.console,gps->longitude);
|
||||
hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu STATUS: %u\n",
|
||||
(float)gps->altitude / 100.0,
|
||||
(float)gps->ground_speed / 100.0,
|
||||
(int)gps->ground_course / 100,
|
||||
(float)gps->altitude_cm / 100.0,
|
||||
(float)gps->ground_speed_cm / 100.0,
|
||||
(int)gps->ground_course_cd / 100,
|
||||
gps->num_sats,
|
||||
gps->time,
|
||||
gps->status());
|
||||
|
|
|
@ -43,11 +43,11 @@ void loop()
|
|||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed / 100.0);
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course / 100.0, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100.0, DEC);
|
||||
hal.console->print(" SAT:");
|
||||
hal.console->print(gps.num_sats, DEC);
|
||||
hal.console->print(" FIX:");
|
||||
|
|
|
@ -63,9 +63,9 @@ void loop()
|
|||
"CoG: %d SAT: %d TIM: %lu\r\n"),
|
||||
(float)gps->latitude / T7,
|
||||
(float)gps->longitude / T7,
|
||||
(float)gps->altitude / 100.0,
|
||||
(float)gps->ground_speed / 100.0,
|
||||
(int)gps->ground_course / 100,
|
||||
(float)gps->altitude_cm / 100.0,
|
||||
(float)gps->ground_speed_cm / 100.0,
|
||||
(int)gps->ground_course_cd / 100,
|
||||
gps->num_sats,
|
||||
gps->time);
|
||||
} else {
|
||||
|
|
|
@ -43,11 +43,11 @@ void loop()
|
|||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed / 100.0);
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course / 100.0, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100.0, DEC);
|
||||
Vector2f vel = Vector2f(gps.velocity_north(), gps.velocity_east());
|
||||
hal.console->printf(" VEL: %.2f %.2f %.2f",
|
||||
vel.x,
|
||||
|
|
Loading…
Reference in New Issue