mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
2e464a53c2
The switching between different AP_HAL was happening by giving different definitions of AP_HAL_BOARD_DRIVER, and the programs would use it to instantiate. A program or library code would have to explicitly include (and depend) on the concrete implementation of the HAL, even when using it only via interface. The proposed change move this dependency to be link time. There is a AP_HAL::get_HAL() function that is used by the client code. Each implementation of HAL provides its own definition of this function, returning the appropriate concrete instance. Since this replaces the job of AP_HAL_BOARD_DRIVER, the definition was removed. The static variables for PX4 and VRBRAIN were named differently to avoid shadowing the extern symbol 'hal'.
73 lines
1.8 KiB
C++
73 lines
1.8 KiB
C++
// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*-
|
|
|
|
//
|
|
// Example code for the AP_HAL AVRUARTDriver, based on FastSerial
|
|
//
|
|
// This code is placed into the public domain.
|
|
//
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
#include <AP_Progmem/AP_Progmem.h>
|
|
#include <AP_HAL/AP_HAL.h>
|
|
#include <AP_HAL_AVR/AP_HAL_AVR.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
#include <AP_Math/AP_Math.h>
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
#include <AP_Mission/AP_Mission.h>
|
|
#include <StorageManager/StorageManager.h>
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
#include <GCS_Console/GCS_Console.h>
|
|
|
|
#include "simplegcs.h"
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|
|
|
void flush_console_to_statustext() {
|
|
uint8_t data[50];
|
|
int n = hal.console->backend_read(data, 50);
|
|
if (n > 0) {
|
|
try_send_statustext(MAVLINK_COMM_0, (char*) data, n);
|
|
}
|
|
}
|
|
|
|
void console_loopback() {
|
|
int a = hal.console->available();
|
|
if (a > 0) {
|
|
hal.console->print("Console loopback:");
|
|
int r = hal.console->read();
|
|
while (r > 0) {
|
|
hal.console->write( (uint8_t) r );
|
|
r = hal.console->read();
|
|
}
|
|
hal.console->println();
|
|
}
|
|
}
|
|
|
|
void setup(void) {
|
|
/* Allocate large enough buffers on uartA to support mavlink */
|
|
hal.uartA->begin(115200, 128, 256);
|
|
|
|
/* Setup GCS_Mavlink library's comm 0 port. */
|
|
mavlink_comm_port[0] = hal.uartA;
|
|
|
|
char hello[] = "Hello statustext\r\n";
|
|
try_send_statustext(MAVLINK_COMM_0, hello, strlen(hello));
|
|
|
|
hal.console->backend_open();
|
|
hal.console->printf_P(PSTR("Hello hal.console\r\n"));
|
|
}
|
|
|
|
int i = 0;
|
|
void loop(void) {
|
|
try_send_message(MAVLINK_COMM_0, MAVLINK_MSG_ID_HEARTBEAT);
|
|
simplegcs_update(MAVLINK_COMM_0);
|
|
// flush_console_to_statustext();
|
|
gcs_console_send(MAVLINK_COMM_0);
|
|
|
|
console_loopback();
|
|
hal.scheduler->delay(100);
|
|
}
|
|
|
|
AP_HAL_MAIN();
|