21 #define ALLOW_DOUBLE_MATH_FUNCTIONS 29 #define gsof_DEBUGGING 0 32 # define Debug(fmt, args ...) \ 34 hal.console->printf("%s:%d: " fmt "\n", \ 35 __FUNCTION__, __LINE__, \ 37 hal.scheduler->delay(1); \ 40 # define Debug(fmt, args ...) 142 uint8_t
buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00,
143 0x03, 0x00, 0x01, 0x00,
144 0x02, 0x04, portindex, 0x07, 0x00,0x00,
150 uint8_t checksum = 0;
151 for (uint8_t a = 1; a < (
sizeof(
buffer) - 1); a++) {
152 checksum += buffer[a];
155 buffer[17] = checksum;
157 port->
write((
const uint8_t*)buffer,
sizeof(buffer));
163 uint8_t
buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00,
165 0x07,0x06,0x0a,portindex,0x01,0x00,0x01,0x00,
170 buffer[17] = messagetype;
172 uint8_t checksum = 0;
173 for (uint8_t a = 1; a < (
sizeof(
buffer) - 1); a++) {
174 checksum += buffer[a];
177 buffer[19] = checksum;
179 port->
write((
const uint8_t*)buffer,
sizeof(buffer));
187 char bytes[
sizeof(double)];
189 doubleu.bytes[0] = src[pos + 7];
190 doubleu.bytes[1] = src[pos + 6];
191 doubleu.bytes[2] = src[pos + 5];
192 doubleu.bytes[3] = src[pos + 4];
193 doubleu.bytes[4] = src[pos + 3];
194 doubleu.bytes[5] = src[pos + 2];
195 doubleu.bytes[6] = src[pos + 1];
196 doubleu.bytes[7] = src[pos + 0];
206 char bytes[
sizeof(float)];
208 floatu.bytes[0] = src[pos + 3];
209 floatu.bytes[1] = src[pos + 2];
210 floatu.bytes[2] = src[pos + 1];
211 floatu.bytes[3] = src[pos + 0];
221 char bytes[
sizeof(uint32_t)];
223 uint32u.bytes[0] = src[pos + 3];
224 uint32u.bytes[1] = src[pos + 2];
225 uint32u.bytes[2] = src[pos + 1];
226 uint32u.bytes[3] = src[pos + 0];
236 char bytes[
sizeof(uint16_t)];
238 uint16u.bytes[0] = src[pos + 1];
239 uint16u.bytes[1] = src[pos + 0];
255 Debug(
"GSOF page: %u of %u (trans_number=%u)",
256 pageidx, maxpageidx, trans_number);
270 if (output_type == 1)
297 else if (output_type == 2)
307 else if (output_type == 8)
310 if ((vflag & 1) == 1)
320 else if (output_type == 9)
325 else if (output_type == 12)
334 a += output_length-1u;
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
enum AP_GPS_GSOF::gsof_msg_parser_t::@28 gsof_state
float SwapFloat(uint8_t *src, uint32_t pos)
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
int32_t lat
param 3 - Latitude * 10**7
Receiving valid messages and 3D RTK Fixed.
void requestGSOF(uint8_t messagetype, uint8_t portindex)
void requestBaud(uint8_t portindex)
AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
#define Debug(fmt, args ...)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Receiving valid messages and 3D lock with differential improvements.
Receiving valid messages and 3D RTK Float.
virtual size_t write(uint8_t)=0
uint16_t time_week
GPS week number.
AP_GPS::GPS_State & state
public state for this instance
static const uint8_t GSOF_STX
uint32_t SwapUint32(uint8_t *src, uint32_t pos)
struct AP_GPS_GSOF::gsof_msg_parser_t gsof_msg
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.
uint16_t SwapUint16(uint8_t *src, uint32_t pos)
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.
double SwapDouble(uint8_t *src, uint32_t pos)
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.
float vertical_accuracy
vertical RMS accuracy estimate in m
uint16_t hdop
horizontal dilution of precision in cm
uint8_t num_sats
Number of visible satellites.
float ground_course
ground course in degrees