AP_GPS: updated examples for new API

removed old per-driver examples, and updates AUTO example
This commit is contained in:
Andrew Tridgell 2014-03-31 19:06:37 +11:00
parent 60ad429d13
commit c2486d8d6e
13 changed files with 18 additions and 359 deletions

View File

@ -1,74 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* Example of GPS 406 library.
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
*
* Works with Ardupilot Mega Hardware (GPS on hal.console->Port1)
*/
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Math.h>
#include <AP_Param.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
AP_GPS_406 gps;
#define T6 1000000
#define T7 10000000
void setup()
{
hal.console->println("GPS 406 library test");
hal.uartB->begin(57600, 128, 16);
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
hal.scheduler->delay(1000);
}
void loop()
{
hal.scheduler->delay(20);
gps.update();
if (gps.new_data) {
hal.console->print("gps:");
hal.console->print(" Lat:");
hal.console->print((float)gps.latitude / T7, BASE_DEC);
hal.console->print(" Lon:");
hal.console->print((float)gps.longitude / T7, BASE_DEC);
hal.console->print(" Alt:");
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, BASE_DEC);
hal.console->print(" SAT:");
hal.console->print(gps.num_sats, BASE_DEC);
hal.console->print(" FIX:");
hal.console->print(gps.fix, BASE_DEC);
hal.console->print(" WEEK:");
hal.console->print(gps.time_week, BASE_DEC);
hal.console->print(" TIM:");
hal.console->print(gps.time_week_ms, BASE_DEC);
hal.console->println();
gps.new_data = 0; // We have readed the data
}
}
AP_HAL_MAIN();

View File

@ -1,2 +0,0 @@
BOARD = mega
include ../../../../mk/apm.mk

View File

@ -36,19 +36,14 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// create board led object
AP_BoardLED board_led;
GPS *gps;
AP_GPS_Auto GPS(&gps);
AP_GPS gps;
#define T6 1000000
#define T7 10000000
void setup()
{
hal.uartB->begin(38400);
hal.console->println("GPS AUTO library test");
gps = &GPS;
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL);
// initialise the leds
board_led.init();
@ -56,25 +51,23 @@ void setup()
void loop()
{
gps->update();
if (gps->new_data) {
if (gps->fix) {
hal.console->print("Lat: ");
print_latlon(hal.console,gps->latitude);
hal.console->print(" Lon: ");
print_latlon(hal.console,gps->longitude);
hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %u/%lu STATUS: %u\n",
(float)gps->altitude_cm / 100.0,
(float)gps->ground_speed_cm / 100.0,
(int)gps->ground_course_cd / 100,
gps->num_sats,
gps->time_week,
gps->time_week_ms,
gps->status());
} else {
hal.console->println("No fix");
}
gps->new_data = false;
static uint32_t last_msg_ms;
gps.update();
if (last_msg_ms != gps.last_message_time_ms()) {
last_msg_ms = gps.last_message_time_ms();
const Location &loc = gps.location();
hal.console->print("Lat: ");
print_latlon(hal.console, loc.lat);
hal.console->print(" Lon: ");
print_latlon(hal.console, loc.lng);
hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %u/%lu STATUS: %u\n",
loc.alt * 0.01f,
gps.ground_speed(),
(int)gps.ground_course_cd() / 100,
gps.num_sats(),
gps.time_week(),
gps.time_week_ms(),
gps.status());
}
}

View File

@ -1,77 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* Example of GPS MTK library.
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
*
* Works with Ardupilot Mega Hardware (GPS on Serial Port1)
*/
#include <stdlib.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_Empty.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
AP_GPS_MTK19 gps;
#define T6 1000000
#define T7 10000000
void setup()
{
hal.uartB->begin(38400);
hal.console->println("GPS MTK library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
}
void loop()
{
hal.scheduler->delay(20);
gps.update();
if (gps.new_data) {
hal.console->print("gps:");
hal.console->print(" Lat:");
hal.console->print((float)gps.latitude / T7, BASE_DEC);
hal.console->print(" Lon:");
hal.console->print((float)gps.longitude / T7, BASE_DEC);
hal.console->print(" Alt:");
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, BASE_DEC);
hal.console->print(" SAT:");
hal.console->print(gps.num_sats, BASE_DEC);
hal.console->print(" FIX:");
hal.console->print(gps.fix, BASE_DEC);
hal.console->print(" WEEK:");
hal.console->print(gps.time_week, BASE_DEC);
hal.console->print(" TIM:");
hal.console->print(gps.time_week_ms, BASE_DEC);
hal.console->println();
gps.new_data = 0; // We have readed the data
}
}
AP_HAL_MAIN();

View File

@ -1,2 +0,0 @@
BOARD = mega
include ../../../../mk/apm.mk

View File

@ -1,93 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
// Test for AP_GPS_NMEA
//
#include <AP_Common.h>
#include <AP_Param.h>
#include <AP_Progmem.h>
#include <AP_Math.h>
#include <AP_HAL.h>
#include <AP_GPS.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_AVR_SITL.h>
#include <AP_HAL_Empty.h>
#include <AP_Notify.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
AP_GPS_NMEA NMEA_gps;
GPS *gps = &NMEA_gps;
#define T6 1000000
#define T7 10000000
const uint8_t sirf_to_nmea[] = { 0xa0, 0xa2, // preamble
0x00, 0x18, // message length
0x81, 0x02, // switch to NMEA
0x01, 0x01, // GGA on with checksum
0x00, 0x01, // GLL off
0x00, 0x01, // GSA off
0x00, 0x01, // GSV off
0x01, 0x01, // RMC on with checksum
0x01, 0x01, // VTG on with checksum
0x00, 0x01, // MSS off
0x00, 0x01, // EPE off
0x00, 0x01, // ZPA off
0x00, 0x00, // pad
0x96, 0x00, // 38400
0x01, 0x25, // checksum TBD
0xb0, 0xb3}; // postamble
void setup()
{
hal.console->println_P(PSTR("GPS_NMEA library test"));
hal.uartB->begin(38400);
// try to coerce a SiRF unit that's been traumatized by
// AP_GPS_AUTO back into NMEA mode so that we can test
// it.
for (uint8_t i = 0; i < sizeof(sirf_to_nmea); i++)
hal.uartB->write(sirf_to_nmea[i]);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL);
}
void loop()
{
gps->update();
if (gps->new_data) {
if (gps->fix) {
hal.console->printf_P(
PSTR("Lat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s "
"CoG: %d SAT: %d TIM: %u/%lu\r\n"),
(float)gps->latitude / T7,
(float)gps->longitude / T7,
(float)gps->altitude_cm / 100.0,
(float)gps->ground_speed_cm / 100.0,
(int)gps->ground_course_cd / 100,
gps->num_sats,
gps->time_week,
gps->time_week_ms);
} else {
hal.console->println_P(PSTR("No fix"));
}
gps->new_data = false;
}
}
AP_HAL_MAIN();

View File

@ -1,2 +0,0 @@
BOARD = mega
include ../../../../mk/apm.mk

View File

@ -1,82 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* Example of GPS UBlox library.
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
*
* Works with Ardupilot Mega Hardware (GPS on Serial Port1)
*/
#include <stdlib.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_HAL.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_Empty.h>
#include <AP_HAL_PX4.h>
#include <AP_GPS.h>
#include <DataFlash.h>
#include <AP_InertialSensor.h>
#include <AP_ADC.h>
#include <GCS_MAVLink.h>
#include <AP_Baro.h>
#include <Filter.h>
#include <AP_AHRS.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_Vehicle.h>
#include <AP_ADC_AnalogSource.h>
#include <AP_Mission.h>
#include <AP_Math.h>
#include <AP_Notify.h>
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
AP_GPS_UBLOX gps;
#define T6 1000000
#define T7 10000000
void setup()
{
hal.uartB->begin(38400);
hal.console->println("GPS UBLOX library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
}
void loop()
{
hal.scheduler->delay(20);
gps.update();
if (gps.new_data) {
hal.console->print("gps:");
hal.console->print(" Lat:");
hal.console->print((float)gps.latitude / T7, BASE_DEC);
hal.console->print(" Lon:");
hal.console->print((float)gps.longitude / T7, BASE_DEC);
hal.console->print(" Alt:");
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, 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, BASE_DEC);
hal.console->print(" FIX:");
hal.console->print(gps.fix, BASE_DEC);
hal.console->print(" WEEK:");
hal.console->print(gps.time_week, BASE_DEC);
hal.console->print(" TIM:");
hal.console->print(gps.time_week_ms, BASE_DEC);
hal.console->println();
gps.new_data = 0; // We have readed the data
}
}
AP_HAL_MAIN();

View File

@ -1,2 +0,0 @@
BOARD = mega
include ../../../../mk/apm.mk