26 #define NOVA_DEBUGGING 0 30 # define Debug(fmt, args ...) \ 32 printf("%s:%d: " fmt "\n", \ 33 __FUNCTION__, __LINE__, \ 35 hal.scheduler->delay(1); \ 38 # define Debug(fmt, args ...) 50 port->
write((
const uint8_t*)init_str, strlen(init_str));
51 port->
write((
const uint8_t*)init_str1, strlen(init_str1));
65 port->
write((
const uint8_t*)init_str, strlen(init_str));
112 Debug(
"NOVA HEADERLENGTH\n");
144 Debug(
"NOVA DATA exit\n");
187 Debug(
"NOVA process_message messid=%u\n",messageid);
263 if (messageid == 174)
289 Debug(
"NOVA: Not enough TXSPACE");
293 #define CRC32_POLYNOMIAL 0xEDB88320L 298 for ( i = 8 ; i > 0; i-- )
310 while ( length-- != 0 )
312 crc = ((crc >> 8) & 0x00FFFFFFL) ^ (
CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff));
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
uint32_t solstat
Solution status.
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
static const uint8_t NOVA_PREAMBLE1
float latsdev
latitude standard deviation (m)
GPS_Status status
driver fix status
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Vector3f velocity
3D velocity in m/s, in NED format
AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
struct PACKED AP_GPS_NOVA::nova_msg_parser nova_msg
virtual uint32_t txspace()=0
#define Debug(fmt, args ...)
float lngsdev
longitude standard deviation (m)
enum AP_GPS_NOVA::nova_msg_parser::@30 nova_state
uint32_t postype
Position type.
int32_t lat
param 3 - Latitude * 10**7
Receiving valid messages and 3D RTK Fixed.
void inject_data(const uint8_t *data, uint16_t len) override
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Receiving valid messages and 3D lock with differential improvements.
uint8_t rtk_num_sats
Current number of satellites used for RTK calculation.
Receiving valid messages and 3D RTK Float.
uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc)
virtual size_t write(uint8_t)=0
uint16_t time_week
GPS week number.
uint32_t rtk_age_ms
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates over...
AP_GPS::GPS_State & state
public state for this instance
uint32_t crc_error_counter
float hgtsdev
height standard deviation (m)
uint8_t svsused
number of satellites used in solution
static const uint8_t NOVA_PREAMBLE2
uint32_t CRC32Value(uint32_t icrc)
uint16_t vdop
vertical dilution of precision in cm
virtual uint32_t available()=0
Location location
last fix location
int32_t lng
param 4 - Longitude * 10**7
void fill_3d_velocity(void)
Receiving valid GPS messages but no lock.
double hgt
height above mean sea level (m)
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
AP_HAL::UARTDriver * port
UART we are attached to.
static const uint8_t NOVA_PREAMBLE3
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
float horizontal_accuracy
horizontal RMS accuracy estimate in m
float ground_speed
ground speed in m/sec
Receiving valid messages and 3D lock.
double lng
longitude (deg)
float vertical_accuracy
vertical RMS accuracy estimate in m
uint32_t last_injected_data_ms
const char * _initialisation_blob[6]
uint16_t hdop
horizontal dilution of precision in cm
float diffage
differential position age (sec)
uint8_t num_sats
Number of visible satellites.
float ground_course
ground course in degrees