2016-01-18 12:06:15 -04:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
//
|
|
|
|
// Emlid Reach Binary (ERB) GPS driver for ArduPilot.
|
|
|
|
// ERB protocol: http://files.emlid.com/ERB.pdf
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-04-13 14:20:05 -03:00
|
|
|
|
2016-01-18 12:06:15 -04:00
|
|
|
#include "AP_GPS.h"
|
2016-04-13 14:20:05 -03:00
|
|
|
#include "GPS_Backend.h"
|
2016-01-18 12:06:15 -04:00
|
|
|
|
|
|
|
class AP_GPS_ERB : public AP_GPS_Backend
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
|
|
|
|
|
|
|
// Methods
|
2018-11-07 06:58:08 -04:00
|
|
|
bool read() override;
|
2016-01-18 12:06:15 -04:00
|
|
|
|
2018-11-07 06:58:08 -04:00
|
|
|
AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
|
2016-01-18 12:06:15 -04:00
|
|
|
|
2018-11-07 06:58:08 -04:00
|
|
|
bool supports_mavlink_gps_rtk_message() override { return true; }
|
2017-09-24 18:48:52 -03:00
|
|
|
|
2016-01-18 12:06:15 -04:00
|
|
|
static bool _detect(struct ERB_detect_state &state, uint8_t data);
|
|
|
|
|
2016-08-01 08:58:23 -03:00
|
|
|
const char *name() const override { return "ERB"; }
|
|
|
|
|
2016-01-18 12:06:15 -04:00
|
|
|
private:
|
|
|
|
struct PACKED erb_header {
|
|
|
|
uint8_t preamble1;
|
|
|
|
uint8_t preamble2;
|
|
|
|
uint8_t msg_id;
|
|
|
|
uint16_t length;
|
|
|
|
};
|
|
|
|
struct PACKED erb_ver {
|
2017-07-01 15:17:24 -03:00
|
|
|
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
|
2016-01-18 12:06:15 -04:00
|
|
|
uint8_t ver_high;
|
|
|
|
uint8_t ver_medium;
|
|
|
|
uint8_t ver_low;
|
|
|
|
};
|
|
|
|
struct PACKED erb_pos {
|
2017-07-01 15:17:24 -03:00
|
|
|
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
|
2016-01-18 12:06:15 -04:00
|
|
|
double longitude;
|
|
|
|
double latitude;
|
2017-07-01 15:17:24 -03:00
|
|
|
double altitude_ellipsoid; ///< Height above ellipsoid [m]
|
|
|
|
double altitude_msl; ///< Height above mean sea level [m]
|
|
|
|
uint32_t horizontal_accuracy; ///< Horizontal accuracy estimate [mm]
|
|
|
|
uint32_t vertical_accuracy; ///< Vertical accuracy estimate [mm]
|
2016-01-18 12:06:15 -04:00
|
|
|
};
|
|
|
|
struct PACKED erb_stat {
|
2017-07-01 15:17:24 -03:00
|
|
|
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
|
2016-01-18 12:06:15 -04:00
|
|
|
uint16_t week;
|
2017-07-01 15:17:24 -03:00
|
|
|
uint8_t fix_type; ///< see erb_fix_type enum
|
2016-01-18 12:06:15 -04:00
|
|
|
uint8_t fix_status;
|
|
|
|
uint8_t satellites;
|
|
|
|
};
|
|
|
|
struct PACKED erb_dops {
|
2017-07-01 15:17:24 -03:00
|
|
|
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
|
|
|
|
uint16_t gDOP; ///< Geometric DOP
|
|
|
|
uint16_t pDOP; ///< Position DOP
|
|
|
|
uint16_t vDOP; ///< Vertical DOP
|
|
|
|
uint16_t hDOP; ///< Horizontal DOP
|
2016-01-18 12:06:15 -04:00
|
|
|
};
|
|
|
|
struct PACKED erb_vel {
|
2017-07-01 15:17:24 -03:00
|
|
|
uint32_t time; ///< GPS time of week of the navigation epoch [ms]
|
|
|
|
int32_t vel_north; ///< North velocity component [cm/s]
|
|
|
|
int32_t vel_east; ///< East velocity component [cm/s]
|
|
|
|
int32_t vel_down; ///< Down velocity component [cm/s]
|
|
|
|
uint32_t speed_2d; ///< Ground speed (2-D) [cm/s]
|
|
|
|
int32_t heading_2d; ///< Heading of motion 2-D [1e5 deg]
|
|
|
|
uint32_t speed_accuracy; ///< Speed accuracy Estimate [cm/s]
|
2016-01-18 12:06:15 -04:00
|
|
|
};
|
2017-07-05 13:53:55 -03:00
|
|
|
struct PACKED erb_rtk {
|
|
|
|
uint8_t base_num_sats; ///< Current number of satellites used for RTK calculation
|
|
|
|
uint16_t age_cs; ///< Age of the corrections in centiseconds (0 when no corrections, 0xFFFF indicates overflow)
|
|
|
|
int32_t baseline_N_mm; ///< distance between base and rover along the north axis in millimeters
|
|
|
|
int32_t baseline_E_mm; ///< distance between base and rover along the east axis in millimeters
|
|
|
|
int32_t baseline_D_mm; ///< distance between base and rover along the down axis in millimeters
|
|
|
|
uint16_t ar_ratio; ///< AR ratio multiplied by 10
|
|
|
|
uint16_t base_week_number; ///< GPS Week Number of last baseline
|
|
|
|
uint32_t base_time_week_ms; ///< GPS Time of Week of last baseline in milliseconds
|
|
|
|
};
|
2016-01-18 12:06:15 -04:00
|
|
|
|
|
|
|
// Receive buffer
|
|
|
|
union PACKED {
|
2016-06-06 10:49:46 -03:00
|
|
|
DEFINE_BYTE_ARRAY_METHODS
|
2016-01-18 12:06:15 -04:00
|
|
|
erb_ver ver;
|
|
|
|
erb_pos pos;
|
|
|
|
erb_stat stat;
|
|
|
|
erb_dops dops;
|
|
|
|
erb_vel vel;
|
2017-07-05 13:53:55 -03:00
|
|
|
erb_rtk rtk;
|
2016-01-18 12:06:15 -04:00
|
|
|
} _buffer;
|
|
|
|
|
|
|
|
enum erb_protocol_bytes {
|
|
|
|
PREAMBLE1 = 0x45,
|
|
|
|
PREAMBLE2 = 0x52,
|
|
|
|
MSG_VER = 0x01,
|
|
|
|
MSG_POS = 0x02,
|
|
|
|
MSG_STAT = 0x03,
|
|
|
|
MSG_DOPS = 0x04,
|
|
|
|
MSG_VEL = 0x05,
|
2017-07-05 13:53:55 -03:00
|
|
|
MSG_RTK = 0x07,
|
2016-01-18 12:06:15 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
enum erb_fix_type {
|
|
|
|
FIX_NONE = 0x00,
|
|
|
|
FIX_SINGLE = 0x01,
|
|
|
|
FIX_FLOAT = 0x02,
|
|
|
|
FIX_FIX = 0x03,
|
|
|
|
};
|
|
|
|
|
|
|
|
// Packet checksum accumulators
|
|
|
|
uint8_t _ck_a;
|
|
|
|
uint8_t _ck_b;
|
|
|
|
|
|
|
|
// State machine state
|
|
|
|
uint8_t _step;
|
|
|
|
uint8_t _msg_id;
|
|
|
|
uint16_t _payload_length;
|
|
|
|
uint16_t _payload_counter;
|
|
|
|
|
|
|
|
// 8 bit count of fix messages processed, used for periodic processing
|
|
|
|
uint8_t _fix_count;
|
|
|
|
|
|
|
|
uint32_t _last_pos_time;
|
|
|
|
uint32_t _last_vel_time;
|
|
|
|
|
|
|
|
// do we have new position information?
|
|
|
|
bool _new_position:1;
|
|
|
|
// do we have new speed information?
|
|
|
|
bool _new_speed:1;
|
|
|
|
|
|
|
|
// Buffer parse & GPS state update
|
|
|
|
bool _parse_gps();
|
|
|
|
|
|
|
|
// used to update fix between status and position packets
|
|
|
|
AP_GPS::GPS_Status next_fix;
|
|
|
|
};
|