|
|
@ -30,9 +30,7 @@ |
|
|
|
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h> |
|
|
|
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h> |
|
|
|
#include <AP_HAL_ChibiOS/I2CDevice.h> |
|
|
|
#include <AP_HAL_ChibiOS/I2CDevice.h> |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
#ifndef HAL_PERIPH_ENABLE_GPS |
|
|
|
|
|
|
|
#define HAL_PERIPH_ENABLE_GPS 1 |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
extern const AP_HAL::HAL &hal; |
|
|
|
|
|
|
|
|
|
|
|
AP_Periph_FW periph; |
|
|
|
AP_Periph_FW periph; |
|
|
@ -148,7 +146,8 @@ void AP_Periph_FW::init() |
|
|
|
|
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS |
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS |
|
|
|
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) { |
|
|
|
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) { |
|
|
|
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD); |
|
|
|
hal.serial(3)->printf("gps port: %d\n", (uint8_t)g.gps_port); |
|
|
|
|
|
|
|
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, 115200); |
|
|
|
#if HAL_LOGGING_ENABLED |
|
|
|
#if HAL_LOGGING_ENABLED |
|
|
|
#define MASK_LOG_GPS (1<<2) |
|
|
|
#define MASK_LOG_GPS (1<<2) |
|
|
|
gps.set_log_gps_bit(MASK_LOG_GPS); |
|
|
|
gps.set_log_gps_bit(MASK_LOG_GPS); |
|
|
@ -209,9 +208,9 @@ void AP_Periph_FW::update() |
|
|
|
{ |
|
|
|
{ |
|
|
|
static uint32_t last_led_ms; |
|
|
|
static uint32_t last_led_ms; |
|
|
|
uint32_t now = AP_HAL::native_millis(); |
|
|
|
uint32_t now = AP_HAL::native_millis(); |
|
|
|
if (now - last_led_ms > 500) { |
|
|
|
if (now - last_led_ms > 1000) { |
|
|
|
last_led_ms = now; |
|
|
|
last_led_ms = now; |
|
|
|
hal.serial(1)->printf("update: %lu\n", now); |
|
|
|
hal.serial(3)->printf("update: %lu,status: %u,sat:%u\n\r", now,(unsigned)gps.status(),(unsigned)gps.num_sats()); |
|
|
|
|
|
|
|
|
|
|
|
#ifdef HAL_GPIO_PIN_LED |
|
|
|
#ifdef HAL_GPIO_PIN_LED |
|
|
|
if (!no_iface_finished_dna) { |
|
|
|
if (!no_iface_finished_dna) { |
|
|
@ -220,7 +219,7 @@ void AP_Periph_FW::update() |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
#if 1 |
|
|
|
#if 1 |
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS |
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS |
|
|
|
hal.serial(1)->printf("GPS status: %u\n", (unsigned)gps.status()); |
|
|
|
hal.serial(3)->printf("GPS status: %u\n", (unsigned)gps.status()); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
hal.scheduler->delay(1); |
|
|
|
hal.scheduler->delay(1); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|