spatial_packets.h
Go to the documentation of this file.
1 /****************************************************************/
2 /* */
3 /* Advanced Navigation Packet Protocol Library */
4 /* C Language Dynamic Spatial SDK, Version 4.0 */
5 /* Copyright 2014, Xavier Orr, Advanced Navigation Pty Ltd */
6 /* */
7 /****************************************************************/
8 /*
9  * Copyright (C) 2014 Advanced Navigation Pty Ltd
10  *
11  * Permission is hereby granted, free of charge, to any person obtaining
12  * a copy of this software and associated documentation files (the "Software"),
13  * to deal in the Software without restriction, including without limitation
14  * the rights to use, copy, modify, merge, publish, distribute, sublicense,
15  * and/or sell copies of the Software, and to permit persons to whom the
16  * Software is furnished to do so, subject to the following conditions:
17  *
18  * The above copyright notice and this permission notice shall be included
19  * in all copies or substantial portions of the Software.
20  *
21  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS
22  * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
23  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
24  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
25  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
26  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
27  * DEALINGS IN THE SOFTWARE.
28  */
29 
30 #ifdef __cplusplus
31 extern "C"
32 {
33 #endif
34 
35 #define MAXIMUM_PACKET_PERIODS 50
36 #define MAXIMUM_DETAILED_SATELLITES 32
37 
38 #define START_SYSTEM_PACKETS 0
39 #define START_STATE_PACKETS 20
40 #define START_CONFIGURATION_PACKETS 180
41 
42 typedef enum
43 {
56 
108 
127 } packet_id_e;
128 
129 /* start of system packets typedef structs */
130 
131 typedef enum
132 {
141 
142 typedef struct
143 {
144  uint8_t packet_id;
145  uint16_t packet_crc;
148 
149 typedef enum
150 {
153 } boot_mode_e;
154 
155 typedef struct
156 {
157  uint8_t boot_mode;
159 
160 typedef struct
161 {
163  uint32_t device_id;
165  uint32_t serial_number[3];
167 
168 typedef enum
169 {
173 
174 typedef enum
175 {
193 
194 typedef enum
195 {
201 
202 typedef struct
203 {
204  uint32_t unique_id;
205  uint32_t data_index;
206  uint8_t response_code;
208 
209 typedef struct
210 {
211  uint32_t unique_id;
212  uint32_t data_index;
213  uint32_t total_size;
214  uint8_t data_encoding;
215  uint8_t metadata_type;
216  uint8_t *metadata;
217  uint8_t *packet_data;
219 
220 typedef struct
221 {
222  uint32_t unique_id;
223  uint32_t data_index;
224  uint8_t *packet_data;
226 
227 /* start of state packets typedef structs */
228 
229 typedef enum
230 {
240 
241 typedef struct
242 {
243  union
244  {
245  uint16_t r;
246  struct
247  {
248  unsigned int system_failure :1;
249  unsigned int accelerometer_sensor_failure :1;
250  unsigned int gyroscope_sensor_failure :1;
251  unsigned int magnetometer_sensor_failure :1;
252  unsigned int pressure_sensor_failure :1;
253  unsigned int gnss_failure :1;
254  unsigned int accelerometer_over_range :1;
255  unsigned int gyroscope_over_range :1;
256  unsigned int magnetometer_over_range :1;
257  unsigned int pressure_over_range :1;
258  unsigned int minimum_temperature_alarm :1;
259  unsigned int maximum_temperature_alarm :1;
260  unsigned int low_voltage_alarm :1;
261  unsigned int high_voltage_alarm :1;
262  unsigned int gnss_antenna_disconnected :1;
263  unsigned int serial_port_overflow_alarm :1;
264  } b;
265  } system_status;
266  union
267  {
268  uint16_t r;
269  struct
270  {
271  unsigned int orientation_filter_initialised :1;
272  unsigned int ins_filter_initialised :1;
273  unsigned int heading_initialised :1;
274  unsigned int utc_time_initialised :1;
275  unsigned int gnss_fix_type :3;
276  unsigned int event1_flag :1;
277  unsigned int event2_flag :1;
278  unsigned int internal_gnss_enabled :1;
279  unsigned int magnetic_heading_enabled :1;
280  unsigned int velocity_heading_enabled :1;
281  unsigned int atmospheric_altitude_enabled :1;
282  unsigned int external_position_active :1;
283  unsigned int external_velocity_active :1;
284  unsigned int external_heading_active :1;
285  } b;
286  } filter_status;
288  uint32_t microseconds;
289  double latitude;
290  double longitude;
291  double height;
292  float velocity[3];
293  float body_acceleration[3];
294  float g_force;
295  float orientation[3];
296  float angular_velocity[3];
297  float standard_deviation[3];
299 
300 typedef struct
301 {
303  uint32_t microseconds;
305 
306 typedef struct
307 {
308  uint32_t microseconds;
309  uint16_t year;
310  uint16_t year_day;
311  uint8_t month;
312  uint8_t month_day;
313  uint8_t week_day;
314  uint8_t hour;
315  uint8_t minute;
316  uint8_t second;
318 
319 typedef struct
320 {
321  union
322  {
323  uint16_t r;
324  struct
325  {
326  unsigned int system_failure :1;
327  unsigned int accelerometer_sensor_failure :1;
328  unsigned int gyroscope_sensor_failure :1;
329  unsigned int magnetometer_sensor_failure :1;
330  unsigned int pressure_sensor_failure :1;
331  unsigned int gnss_failure :1;
332  unsigned int accelerometer_over_range :1;
333  unsigned int gyroscope_over_range :1;
334  unsigned int magnetometer_over_range :1;
335  unsigned int pressure_over_range :1;
336  unsigned int minimum_temperature_alarm :1;
337  unsigned int maximum_temperature_alarm :1;
338  unsigned int low_voltage_alarm :1;
339  unsigned int high_voltage_alarm :1;
340  unsigned int gnss_antenna_disconnected :1;
341  unsigned int serial_port_overflow_alarm :1;
342  } b;
343  } system_status;
344  union
345  {
346  uint16_t r;
347  struct
348  {
349  unsigned int orientation_filter_initialised :1;
350  unsigned int ins_filter_initialised :1;
351  unsigned int heading_initialised :1;
352  unsigned int utc_time_initialised :1;
353  unsigned int gnss_fix_type :3;
354  unsigned int event1_flag :1;
355  unsigned int event2_flag :1;
356  unsigned int internal_gnss_enabled :1;
357  unsigned int dual_antenna_heading_active :1;
358  unsigned int velocity_heading_enabled :1;
359  unsigned int atmospheric_altitude_enabled :1;
360  unsigned int external_position_active :1;
361  unsigned int external_velocity_active :1;
362  unsigned int external_heading_active :1;
363  } b;
364  } filter_status;
366 
367 typedef struct
368 {
369  float standard_deviation[3];
371 
372 typedef struct
373 {
374  float standard_deviation[3];
376 
377 typedef struct
378 {
379  float standard_deviation[3];
381 
382 typedef struct
383 {
384  float standard_deviation[4];
386 
387 typedef struct
388 {
389  float accelerometers[3];
390  float gyroscopes[3];
391  float magnetometers[3];
393  float pressure;
396 
397 typedef struct
398 {
400  uint32_t microseconds;
401  double position[3];
402  float velocity[3];
403  float position_standard_deviation[3];
404  float tilt; /* This field will only be valid if an external dual antenna GNSS system is connected */
405  float heading; /* This field will only be valid if an external dual antenna GNSS system is connected */
406  float tilt_standard_deviation; /* This field will only be valid if an external dual antenna GNSS system is connected */
407  float heading_standard_deviation; /* This field will only be valid if an external dual antenna GNSS system is connected */
408  union
409  {
410  uint16_t r;
411  struct
412  {
413  unsigned int fix_type:3;
414  unsigned int velocity_valid:1;
415  unsigned int time_valid:1;
416  unsigned int external_gnss:1;
417  unsigned int tilt_valid:1; /* This field will only be valid if an external dual antenna GNSS system is connected */
418  unsigned int heading_valid:1; /* This field will only be valid if an external dual antenna GNSS system is connected */
419  } b;
420  } flags;
422 
423 typedef struct
424 {
425  float hdop;
426  float vdop;
427  uint8_t gps_satellites;
433 
434 typedef enum
435 {
446 
447 typedef struct
448 {
450  uint8_t number;
451  union
452  {
453  uint8_t r;
454  struct
455  {
456  unsigned int l1_ca :1;
457  unsigned int l1_c :1;
458  unsigned int l1_p :1;
459  unsigned int l1_m :1;
460  unsigned int l2_c :1;
461  unsigned int l2_p :1;
462  unsigned int l2_m :1;
463  unsigned int l5 :1;
464  } b;
465  } frequencies;
466  uint8_t elevation;
467  uint16_t azimuth;
468  uint8_t snr;
469 } satellite_t;
470 
471 typedef struct
472 {
475 
476 typedef struct
477 {
478  double position[3];
480 
481 typedef struct
482 {
483  double position[3];
485 
486 typedef struct
487 {
488  double position[3];
489  char zone;
491 
492 typedef struct
493 {
494  float velocity[3];
496 
497 typedef struct
498 {
499  float velocity[3];
501 
502 typedef struct
503 {
504  float acceleration[3];
506 
507 typedef struct
508 {
509  float acceleration[3];
510  float g_force;
512 
513 typedef struct
514 {
515  float orientation[3];
517 
518 typedef struct
519 {
520  float orientation[4];
522 
523 typedef struct
524 {
525  float orientation[3][3];
527 
528 typedef struct
529 {
530  float angular_velocity[3];
532 
533 typedef struct
534 {
535  float angular_acceleration[3];
537 
538 typedef struct
539 {
540  double position[3];
541  float velocity[3];
542  float position_standard_deviation[3];
543  float velocity_standard_deviation[3];
545 
546 typedef struct
547 {
548  double position[3];
549  float standard_deviation[3];
551 
552 typedef struct
553 {
554  float velocity[3];
555  float standard_deviation[3];
557 
558 typedef struct
559 {
560  float velocity[3];
563 
564 typedef struct
565 {
566  float heading;
569 
570 typedef struct
571 {
572  uint32_t seconds;
573  uint32_t microseconds;
575 
576 typedef struct
577 {
578  float magnetic_field[3];
580 
581 typedef struct
582 {
583  uint32_t pulse_count;
584  float distance;
585  float speed;
586  float slip;
587  uint8_t active;
589 
590 typedef struct
591 {
593  uint32_t microseconds;
595 
596 typedef struct
597 {
598  float depth;
601 
602 typedef struct
603 {
606 
607 typedef struct
608 {
612 
613 typedef struct
614 {
615  float wind_velocity[2];
617 } wind_packet_t;
618 
619 typedef struct
620 {
626 
627 typedef struct
628 {
629  float delay;
630  float speed;
632  union
633  {
634  uint8_t r;
635  struct
636  {
637  unsigned int reverse_detection_supported:1;
638  } b;
639  } flags;
641 
642 typedef struct
643 {
646  float altitude;
647  float airspeed;
650  union
651  {
652  uint8_t r;
653  struct
654  {
655  unsigned int altitude_set :1;
656  unsigned int airspeed_set :1;
657  unsigned int reset_qnh :1;
658  } b;
659  } flags;
661 
662 /* start of configuration packets typedef structs */
663 
664 typedef struct
665 {
666  uint8_t permanent;
670 
671 typedef struct
672 {
673  uint8_t packet_id;
674  uint32_t period;
676 
677 typedef struct
678 {
679  uint8_t permanent;
683 
684 typedef struct
685 {
686  uint8_t permanent;
690  uint32_t reserved;
692 
693 typedef enum
694 {
699 
700 typedef enum
701 {
706 
707 typedef enum
708 {
713 
714 typedef struct
715 {
716  uint8_t permanent;
721 
722 typedef struct
723 {
724  uint8_t permanent;
725  float alignment_dcm[3][3];
726  float gnss_antenna_offset[3];
727  float odometer_offset[3];
728  float external_data_offset[3];
730 
731 typedef enum
732 {
747 
748 typedef struct
749 {
750  uint8_t permanent;
751  uint8_t vehicle_type;
760 
761 typedef enum
762 {
802 
803 typedef enum
804 {
809 } gpio_index_e;
810 
811 typedef struct
812 {
813  uint8_t permanent;
814  uint8_t gpio_function[4];
816 
817 typedef struct
818 {
819  uint8_t permanent;
820  float hard_iron[3];
821  float soft_iron[3][3];
823 
824 typedef enum
825 {
831 
832 typedef struct
833 {
836 
837 typedef enum
838 {
852 
853 typedef struct
854 {
859 
860 typedef struct
861 {
862  uint8_t permanent;
866 
867 typedef struct
868 {
869  uint8_t permanent;
871 
872 typedef struct
873 {
874  uint8_t permanent;
875  float heave_point_1_offset[3];
876  float heave_point_2_offset[3];
877  float heave_point_3_offset[3];
878  float heave_point_4_offset[3];
880 
881 typedef enum
882 {
893 } gpio_rate_e;
894 
895 typedef enum
896 {
900 
901 typedef union
902 {
903  uint16_t r;
904  struct
905  {
906  unsigned int gpio1_rate:4;
907  unsigned int auxiliary_rate:4;
908  } b;
910 
911 typedef struct
912 {
913  uint8_t permanent;
924  uint8_t reserved[13];
926 
927 int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet);
928 an_packet_t *encode_request_packet(uint8_t requested_packet_id);
929 int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet);
931 int decode_device_information_packet(device_information_packet_t *device_information_packet, an_packet_t *an_packet);
934 int decode_file_transfer_acknowledge_packet(file_transfer_acknowledge_packet_t *file_transfer_acknowledge_packet, an_packet_t *an_packet);
935 int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet);
936 int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet);
937 int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet);
938 int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet);
939 int decode_position_standard_deviation_packet(position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet);
940 int decode_velocity_standard_deviation_packet(velocity_standard_deviation_packet_t *velocity_standard_deviation_packet, an_packet_t *an_packet);
943 int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet);
944 int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet);
945 int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet);
946 int decode_detailed_satellites_packet(detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet);
947 int decode_geodetic_position_packet(geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet);
948 int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet);
949 int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet);
950 int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet);
951 int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet);
952 int decode_acceleration_packet(acceleration_packet_t *acceleration, an_packet_t *an_packet);
954 int decode_euler_orientation_packet(euler_orientation_packet_t *euler_orientation_packet, an_packet_t *an_packet);
955 int decode_quaternion_orientation_packet(quaternion_orientation_packet_t *quaternion_orientation_packet, an_packet_t *an_packet);
956 int decode_dcm_orientation_packet(dcm_orientation_packet_t *dcm_orientation_packet, an_packet_t *an_packet);
957 int decode_angular_velocity_packet(angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet);
958 int decode_angular_acceleration_packet(angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet);
959 int decode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet, an_packet_t *an_packet);
961 int decode_external_position_packet(external_position_packet_t *external_position_packet, an_packet_t *an_packet);
963 int decode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet, an_packet_t *an_packet);
965 int decode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet, an_packet_t *an_packet);
967 int decode_external_heading_packet(external_heading_packet_t *external_heading_packet, an_packet_t *an_packet);
969 int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet);
970 int decode_local_magnetics_packet(local_magnetics_packet_t *local_magnetics_packet, an_packet_t *an_packet);
971 int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet);
972 int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet);
974 int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet);
976 int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet);
977 int decode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet, an_packet_t *an_packet);
979 int decode_wind_packet(wind_packet_t *wind_packet, an_packet_t *an_packet);
981 int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet);
982 int decode_odometer_packet(odometer_packet_t *external_odometer_packet, an_packet_t *an_packet);
984 int decode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet, an_packet_t *an_packet);
986 int decode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet);
988 int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet);
990 int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet);
992 int decode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet, an_packet_t *an_packet);
994 int decode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet, an_packet_t *an_packet);
996 int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet);
998 int decode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet, an_packet_t *an_packet);
1000 int decode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet, an_packet_t *an_packet);
1003 int decode_magnetic_calibration_status_packet(magnetic_calibration_status_packet_t *magnetic_calibration_status_packet, an_packet_t *an_packet);
1004 int decode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet);
1007 int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet);
1009 int decode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet, an_packet_t *an_packet);
1011 
1012 #ifdef __cplusplus
1013 }
1014 #endif
int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet)
int decode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet, an_packet_t *an_packet)
an_packet_t * encode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet)
an_packet_t * encode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet)
gpio_function_e
int decode_external_position_packet(external_position_packet_t *external_position_packet, an_packet_t *an_packet)
int decode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet, an_packet_t *an_packet)
an_packet_t * encode_filter_options_packet(filter_options_packet_t *filter_options_packet)
int decode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet, an_packet_t *an_packet)
int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet)
int decode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet, an_packet_t *an_packet)
int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet)
int decode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet, an_packet_t *an_packet)
int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet)
magnetic_calibration_action_e
an_packet_t * encode_external_time_packet(external_time_packet_t *external_time_packet)
an_packet_t * encode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet)
int decode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet, an_packet_t *an_packet)
int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet)
satellite_system_e
int decode_body_acceleration_packet(body_acceleration_packet_t *body_acceleration, an_packet_t *an_packet)
int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet)
accelerometer_range_e
an_packet_t * encode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet)
int decode_odometer_packet(odometer_packet_t *external_odometer_packet, an_packet_t *an_packet)
an_packet_t * encode_external_heading_packet(external_heading_packet_t *external_heading_packet)
int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet)
uint8_t automatic_magnetic_calibration_enabled
file_transfer_metadata_e
int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet)
int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet)
int decode_quaternion_orientation_standard_deviation_packet(quaternion_orientation_standard_deviation_packet_t *quaternion_orientation_standard_deviation_packet, an_packet_t *an_packet)
int decode_detailed_satellites_packet(detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet)
int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet)
an_packet_t * encode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet)
an_packet_t * encode_zero_alignment_packet(zero_alignment_packet_t *zero_alignment_packet)
int decode_acceleration_packet(acceleration_packet_t *acceleration, an_packet_t *an_packet)
an_packet_t * encode_request_packet(uint8_t requested_packet_id)
float heading_standard_deviation
uint32_t unix_time_seconds
int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet)
packet_id_e
an_packet_t * encode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet)
an_packet_t * encode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet)
nmea_fix_behaviour_e
magnetic_calibration_status_e
int decode_external_heading_packet(external_heading_packet_t *external_heading_packet, an_packet_t *an_packet)
boot_mode_e
int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet)
int decode_euler_orientation_standard_deviation_packet(euler_orientation_standard_deviation_packet_t *euler_orientation_standard_deviation, an_packet_t *an_packet)
#define MAXIMUM_PACKET_PERIODS
an_packet_t * encode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet)
#define MAXIMUM_DETAILED_SATELLITES
an_packet_t * encode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet)
int decode_magnetic_calibration_status_packet(magnetic_calibration_status_packet_t *magnetic_calibration_status_packet, an_packet_t *an_packet)
int decode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet)
uint8_t satellite_system
int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet)
magnetometer_range_e
int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet)
#define START_CONFIGURATION_PACKETS
an_packet_t * encode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet)
float wind_standard_deviation
int decode_angular_acceleration_packet(angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet)
an_packet_t * encode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet)
int decode_geodetic_position_packet(geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet)
gpio_index_e
an_packet_t * encode_external_odometer_packet(odometer_packet_t *external_odometer_packet)
int decode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet, an_packet_t *an_packet)
int decode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet, an_packet_t *an_packet)
uint16_t azimuth
int decode_angular_velocity_packet(angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet)
an_packet_t * encode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet)
int decode_position_standard_deviation_packet(position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet)
int decode_local_magnetics_packet(local_magnetics_packet_t *local_magnetics_packet, an_packet_t *an_packet)
int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet)
int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet)
data_encoding_e
an_packet_t * encode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet)
an_packet_t * encode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet)
int decode_device_information_packet(device_information_packet_t *device_information_packet, an_packet_t *an_packet)
gnss_fix_type_e
acknowledge_result_e
an_packet_t * encode_wind_packet(wind_packet_t *wind_packet)
an_packet_t * encode_restore_factory_settings_packet()
uint8_t elevation
vehicle_type_e
int decode_quaternion_orientation_packet(quaternion_orientation_packet_t *quaternion_orientation_packet, an_packet_t *an_packet)
an_packet_t * encode_external_position_packet(external_position_packet_t *external_position_packet)
int decode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet)
int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet)
int decode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet, an_packet_t *an_packet)
an_packet_t * encode_magnetic_calibration_configuration_packet(magnetic_calibration_configuration_packet_t *magnetic_calibration_configuration_packet)
int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet)
gpio_rate_e
an_packet_t * encode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet)
an_packet_t * encode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet)
int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet)
int decode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet, an_packet_t *an_packet)
#define START_STATE_PACKETS
an_packet_t * encode_external_depth_packet(external_depth_packet_t *external_depth_packet)
int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet)
int decode_velocity_standard_deviation_packet(velocity_standard_deviation_packet_t *velocity_standard_deviation_packet, an_packet_t *an_packet)
int decode_dcm_orientation_packet(dcm_orientation_packet_t *dcm_orientation_packet, an_packet_t *an_packet)
int decode_file_transfer_acknowledge_packet(file_transfer_acknowledge_packet_t *file_transfer_acknowledge_packet, an_packet_t *an_packet)
int decode_euler_orientation_packet(euler_orientation_packet_t *euler_orientation_packet, an_packet_t *an_packet)
file_transfer_response_e
int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet)
an_packet_t * encode_reset_packet()
gyroscope_range_e
int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet)
int decode_wind_packet(wind_packet_t *wind_packet, an_packet_t *an_packet)
int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet)


advanced_navigation_driver
Author(s):
autogenerated on Thu Jun 6 2019 19:13:08