mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed examples build
This commit is contained in:
parent
1b200b30f4
commit
448167e958
|
@ -37,21 +37,21 @@ void loop()
|
|||
if (gps.new_data) {
|
||||
hal.console->print("gps:");
|
||||
hal.console->print(" Lat:");
|
||||
hal.console->print((float)gps.latitude / T7, DEC);
|
||||
hal.console->print((float)gps.latitude / T7, BASE_DEC);
|
||||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print((float)gps.longitude / T7, BASE_DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course_cd / 100, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100, BASE_DEC);
|
||||
hal.console->print(" SAT:");
|
||||
hal.console->print(gps.num_sats, DEC);
|
||||
hal.console->print(gps.num_sats, BASE_DEC);
|
||||
hal.console->print(" FIX:");
|
||||
hal.console->print(gps.fix, DEC);
|
||||
hal.console->print(gps.fix, BASE_DEC);
|
||||
hal.console->print(" TIM:");
|
||||
hal.console->print(gps.time, DEC);
|
||||
hal.console->print(gps.time, BASE_DEC);
|
||||
hal.console->println();
|
||||
gps.new_data = 0; // We have readed the data
|
||||
}
|
||||
|
|
|
@ -40,21 +40,21 @@ void loop()
|
|||
if (gps.new_data) {
|
||||
hal.console->print("gps:");
|
||||
hal.console->print(" Lat:");
|
||||
hal.console->print((float)gps.latitude / T7, DEC);
|
||||
hal.console->print((float)gps.latitude / T7, BASE_DEC);
|
||||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print((float)gps.longitude / T7, BASE_DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course_cd / 100.0, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100.0, BASE_DEC);
|
||||
hal.console->print(" SAT:");
|
||||
hal.console->print(gps.num_sats, DEC);
|
||||
hal.console->print(gps.num_sats, BASE_DEC);
|
||||
hal.console->print(" FIX:");
|
||||
hal.console->print(gps.fix, DEC);
|
||||
hal.console->print(gps.fix, BASE_DEC);
|
||||
hal.console->print(" TIM:");
|
||||
hal.console->print(gps.time, DEC);
|
||||
hal.console->print(gps.time, BASE_DEC);
|
||||
hal.console->println();
|
||||
gps.new_data = 0; // We have readed the data
|
||||
}
|
||||
|
|
|
@ -40,26 +40,26 @@ void loop()
|
|||
if (gps.new_data) {
|
||||
hal.console->print("gps:");
|
||||
hal.console->print(" Lat:");
|
||||
hal.console->print((float)gps.latitude / T7, DEC);
|
||||
hal.console->print((float)gps.latitude / T7, BASE_DEC);
|
||||
hal.console->print(" Lon:");
|
||||
hal.console->print((float)gps.longitude / T7, DEC);
|
||||
hal.console->print((float)gps.longitude / T7, BASE_DEC);
|
||||
hal.console->print(" Alt:");
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, DEC);
|
||||
hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC);
|
||||
hal.console->print(" GSP:");
|
||||
hal.console->print(gps.ground_speed_cm / 100.0);
|
||||
hal.console->print(" COG:");
|
||||
hal.console->print(gps.ground_course_cd / 100.0, DEC);
|
||||
hal.console->print(gps.ground_course_cd / 100.0, BASE_DEC);
|
||||
Vector2f vel = Vector2f(gps.velocity_north(), gps.velocity_east());
|
||||
hal.console->printf(" VEL: %.2f %.2f %.2f",
|
||||
vel.x,
|
||||
vel.y,
|
||||
vel.length());
|
||||
hal.console->print(" SAT:");
|
||||
hal.console->print(gps.num_sats, DEC);
|
||||
hal.console->print(gps.num_sats, BASE_DEC);
|
||||
hal.console->print(" FIX:");
|
||||
hal.console->print(gps.fix, DEC);
|
||||
hal.console->print(gps.fix, BASE_DEC);
|
||||
hal.console->print(" TIM:");
|
||||
hal.console->print(gps.time, DEC);
|
||||
hal.console->print(gps.time, BASE_DEC);
|
||||
hal.console->println();
|
||||
gps.new_data = 0; // We have readed the data
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue