APM:Libraries
GPS_UBLOX_passthrough.cpp
Go to the documentation of this file.
1 /*
2  * GPS UBlox passthrough sketch
3  * Code by DIYDrones.com
4  */
5 
6 #include <stdlib.h>
7 #include <AP_Common/AP_Common.h>
8 #include <AP_Param/AP_Param.h>
9 #include <AP_HAL/AP_HAL.h>
10 #include <AP_GPS/AP_GPS.h>
11 #include <DataFlash/DataFlash.h>
13 #include <AP_ADC/AP_ADC.h>
15 #include <AP_Baro/AP_Baro.h>
16 #include <Filter/Filter.h>
17 #include <AP_AHRS/AP_AHRS.h>
18 #include <AP_Compass/AP_Compass.h>
21 #include <AP_Vehicle/AP_Vehicle.h>
22 #include <AP_Mission/AP_Mission.h>
24 #include <AP_Terrain/AP_Terrain.h>
25 #include <AP_Math/AP_Math.h>
26 #include <AP_Notify/AP_Notify.h>
30 
31 void setup();
32 void loop();
33 
35 
36 void setup()
37 {
38  // initialise console uart to 38400 baud
39  hal.console->begin(38400);
40 
41  // initialise gps uart to 38400 baud
42  hal.uartB->begin(38400);
43 }
44 
45 void loop()
46 {
47  // send characters received from the console to the GPS
48  while (hal.console->available()) {
49  hal.uartB->write(hal.console->read());
50  }
51  // send GPS characters to the console
52  while (hal.uartB->available()) {
53  hal.console->write(hal.uartB->read());
54  }
55 }
56 
57 AP_HAL_MAIN();
AP_HAL_MAIN()
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual void begin(uint32_t baud)=0
AP_HAL::UARTDriver * uartB
Definition: HAL.h:101
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
A system for managing and storing variables that are of general interest to the system.
virtual size_t write(uint8_t)=0
void setup()
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
virtual int16_t read()=0
const HAL & get_HAL()
Common definitions and utility routines for the ArduPilot libraries.
virtual uint32_t available()=0
void loop()
Catch-all header that defines all supported RangeFinder classes.