mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: GPS_406_test ported to AP_HAL
This commit is contained in:
parent
4c5aaef245
commit
f1869d1aa6
|
@ -3,59 +3,61 @@
|
||||||
* Example of GPS 406 library.
|
* Example of GPS 406 library.
|
||||||
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
|
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
|
||||||
*
|
*
|
||||||
* Works with Ardupilot Mega Hardware (GPS on Serial Port1)
|
* Works with Ardupilot Mega Hardware (GPS on hal.console->Port1)
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <FastSerial.h>
|
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Progmem.h>
|
||||||
#include <AP_Math.h>
|
#include <AP_Math.h>
|
||||||
#include <AP_Param.h>
|
#include <AP_Param.h>
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#include <AP_HAL_AVR.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
|
|
||||||
FastSerialPort0(Serial);
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
FastSerialPort1(Serial1);
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM1;
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
|
||||||
|
#endif
|
||||||
|
|
||||||
AP_GPS_406 gps(&Serial1);
|
AP_GPS_406 gps(hal.uartB);
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
#define T7 10000000
|
#define T7 10000000
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
tone(A6, 1000, 200);
|
hal.console->println("GPS 406 library test");
|
||||||
|
hal.uartB->begin(57600, 128, 16);
|
||||||
Serial.begin(38400, 16, 128);
|
|
||||||
Serial1.begin(57600, 128, 16);
|
|
||||||
stderr = stdout;
|
|
||||||
gps.print_errors = true;
|
gps.print_errors = true;
|
||||||
|
|
||||||
Serial.println("GPS 406 library test");
|
|
||||||
gps.init(); // GPS Initialization
|
gps.init(); // GPS Initialization
|
||||||
delay(1000);
|
hal.scheduler->delay(1000);
|
||||||
}
|
}
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
delay(20);
|
hal.scheduler->delay(20);
|
||||||
gps.update();
|
gps.update();
|
||||||
if (gps.new_data) {
|
if (gps.new_data) {
|
||||||
Serial.print("gps:");
|
hal.console->print("gps:");
|
||||||
Serial.print(" Lat:");
|
hal.console->print(" Lat:");
|
||||||
Serial.print((float)gps.latitude / T7, DEC);
|
hal.console->print((float)gps.latitude / T7, DEC);
|
||||||
Serial.print(" Lon:");
|
hal.console->print(" Lon:");
|
||||||
Serial.print((float)gps.longitude / T7, DEC);
|
hal.console->print((float)gps.longitude / T7, DEC);
|
||||||
Serial.print(" Alt:");
|
hal.console->print(" Alt:");
|
||||||
Serial.print((float)gps.altitude / 100.0, DEC);
|
hal.console->print((float)gps.altitude / 100.0, DEC);
|
||||||
Serial.print(" GSP:");
|
hal.console->print(" GSP:");
|
||||||
Serial.print(gps.ground_speed / 100.0);
|
hal.console->print(gps.ground_speed / 100.0);
|
||||||
Serial.print(" COG:");
|
hal.console->print(" COG:");
|
||||||
Serial.print(gps.ground_course / 100, DEC);
|
hal.console->print(gps.ground_course / 100, DEC);
|
||||||
Serial.print(" SAT:");
|
hal.console->print(" SAT:");
|
||||||
Serial.print(gps.num_sats, DEC);
|
hal.console->print(gps.num_sats, DEC);
|
||||||
Serial.print(" FIX:");
|
hal.console->print(" FIX:");
|
||||||
Serial.print(gps.fix, DEC);
|
hal.console->print(gps.fix, DEC);
|
||||||
Serial.print(" TIM:");
|
hal.console->print(" TIM:");
|
||||||
Serial.print(gps.time, DEC);
|
hal.console->print(gps.time, DEC);
|
||||||
Serial.println();
|
hal.console->println();
|
||||||
gps.new_data = 0; // We have readed the data
|
gps.new_data = 0; // We have readed the data
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
AP_HAL_MAIN();
|
||||||
|
|
Loading…
Reference in New Issue