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, 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 #ifndef SPATIAL
31 #define SPATIAL
32 
33 #ifdef __cplusplus
34 extern "C"
35 {
36 #endif
37 
38 #define MAXIMUM_PACKET_PERIODS 50
39 #define MAXIMUM_DETAILED_SATELLITES 32
40 
41 #define START_SYSTEM_PACKETS 0
42 #define START_STATE_PACKETS 20
43 #define START_CONFIGURATION_PACKETS 180
44 
45 typedef enum
46 {
59 
113 
132 } packet_id_e;
133 
134 /* start of system packets typedef structs */
135 
136 typedef enum
137 {
146 
147 typedef struct
148 {
149  uint8_t packet_id;
150  uint16_t packet_crc;
153 
154 typedef enum
155 {
158 } boot_mode_e;
159 
160 typedef struct
161 {
162  uint8_t boot_mode;
164 
165 typedef struct
166 {
168  uint32_t device_id;
170  uint32_t serial_number[3];
172 
173 typedef enum
174 {
178 
179 typedef enum
180 {
198 
199 typedef enum
200 {
206 
207 typedef struct
208 {
209  uint32_t unique_id;
210  uint32_t data_index;
211  uint8_t response_code;
213 
214 typedef struct
215 {
216  uint32_t unique_id;
217  uint32_t data_index;
218  uint32_t total_size;
219  uint8_t data_encoding;
220  uint8_t metadata_type;
221  uint8_t *metadata;
222  uint8_t *packet_data;
224 
225 typedef struct
226 {
227  uint32_t unique_id;
228  uint32_t data_index;
229  uint8_t *packet_data;
231 
232 /* start of state packets typedef structs */
233 
234 typedef enum
235 {
245 
246 typedef struct
247 {
248  union
249  {
250  uint16_t r;
251  struct
252  {
253  unsigned int system_failure :1;
254  unsigned int accelerometer_sensor_failure :1;
255  unsigned int gyroscope_sensor_failure :1;
256  unsigned int magnetometer_sensor_failure :1;
257  unsigned int pressure_sensor_failure :1;
258  unsigned int gnss_failure :1;
259  unsigned int accelerometer_over_range :1;
260  unsigned int gyroscope_over_range :1;
261  unsigned int magnetometer_over_range :1;
262  unsigned int pressure_over_range :1;
263  unsigned int minimum_temperature_alarm :1;
264  unsigned int maximum_temperature_alarm :1;
265  unsigned int low_voltage_alarm :1;
266  unsigned int high_voltage_alarm :1;
267  unsigned int gnss_antenna_disconnected :1;
268  unsigned int serial_port_overflow_alarm :1;
269  } b;
270  } system_status;
271  union
272  {
273  uint16_t r;
274  struct
275  {
276  unsigned int orientation_filter_initialised :1;
277  unsigned int ins_filter_initialised :1;
278  unsigned int heading_initialised :1;
279  unsigned int utc_time_initialised :1;
280  unsigned int gnss_fix_type :3;
281  unsigned int event1_flag :1;
282  unsigned int event2_flag :1;
283  unsigned int internal_gnss_enabled :1;
284  unsigned int dual_antenna_heading_active :1;
285  unsigned int velocity_heading_enabled :1;
286  unsigned int atmospheric_altitude_enabled :1;
287  unsigned int external_position_active :1;
288  unsigned int external_velocity_active :1;
289  unsigned int external_heading_active :1;
290  } b;
291  } filter_status;
293  uint32_t microseconds;
294  double latitude;
295  double longitude;
296  double height;
297  float velocity[3];
298  float body_acceleration[3];
299  float g_force;
300  float orientation[3];
301  float angular_velocity[3];
302  float standard_deviation[3];
304 
305 typedef struct
306 {
308  uint32_t microseconds;
310 
311 typedef struct
312 {
313  uint32_t microseconds;
314  uint16_t year;
315  uint16_t year_day;
316  uint8_t month;
317  uint8_t month_day;
318  uint8_t week_day;
319  uint8_t hour;
320  uint8_t minute;
321  uint8_t second;
323 
324 typedef struct
325 {
326  union
327  {
328  uint16_t r;
329  struct
330  {
331  unsigned int system_failure :1;
332  unsigned int accelerometer_sensor_failure :1;
333  unsigned int gyroscope_sensor_failure :1;
334  unsigned int magnetometer_sensor_failure :1;
335  unsigned int pressure_sensor_failure :1;
336  unsigned int gnss_failure :1;
337  unsigned int accelerometer_over_range :1;
338  unsigned int gyroscope_over_range :1;
339  unsigned int magnetometer_over_range :1;
340  unsigned int pressure_over_range :1;
341  unsigned int minimum_temperature_alarm :1;
342  unsigned int maximum_temperature_alarm :1;
343  unsigned int low_voltage_alarm :1;
344  unsigned int high_voltage_alarm :1;
345  unsigned int gnss_antenna_disconnected :1;
346  unsigned int serial_port_overflow_alarm :1;
347  } b;
348  } system_status;
349  union
350  {
351  uint16_t r;
352  struct
353  {
354  unsigned int orientation_filter_initialised :1;
355  unsigned int ins_filter_initialised :1;
356  unsigned int heading_initialised :1;
357  unsigned int utc_time_initialised :1;
358  unsigned int gnss_fix_type :3;
359  unsigned int event1_flag :1;
360  unsigned int event2_flag :1;
361  unsigned int internal_gnss_enabled :1;
362  unsigned int dual_antenna_heading_active :1;
363  unsigned int velocity_heading_enabled :1;
364  unsigned int atmospheric_altitude_enabled :1;
365  unsigned int external_position_active :1;
366  unsigned int external_velocity_active :1;
367  unsigned int external_heading_active :1;
368  } b;
369  } filter_status;
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[3];
386 
387 typedef struct
388 {
389  float standard_deviation[4];
391 
392 typedef struct
393 {
394  float accelerometers[3];
395  float gyroscopes[3];
396  float magnetometers[3];
398  float pressure;
401 
402 typedef struct
403 {
405  uint32_t microseconds;
406  double position[3];
407  float velocity[3];
408  float position_standard_deviation[3];
409  float tilt; /* This field will only be valid if an external dual antenna GNSS system is connected */
410  float heading; /* This field will only be valid if an external dual antenna GNSS system is connected */
411  float tilt_standard_deviation; /* This field will only be valid if an external dual antenna GNSS system is connected */
412  float heading_standard_deviation; /* This field will only be valid if an external dual antenna GNSS system is connected */
413  union
414  {
415  uint16_t r;
416  struct
417  {
418  unsigned int fix_type :3;
419  unsigned int velocity_valid :1;
420  unsigned int time_valid :1;
421  unsigned int external_gnss :1;
422  unsigned int tilt_valid :1; /* This field will only be valid if an external dual antenna GNSS system is connected */
423  unsigned int heading_valid :1; /* This field will only be valid if an external dual antenna GNSS system is connected */
424  } b;
425  } flags;
427 
428 typedef struct
429 {
430  float hdop;
431  float vdop;
432  uint8_t gps_satellites;
438 
439 typedef enum
440 {
451 
452 typedef struct
453 {
455  uint8_t number;
456  union
457  {
458  uint8_t r;
459  struct
460  {
461  unsigned int l1_ca :1;
462  unsigned int l1_c :1;
463  unsigned int l1_p :1;
464  unsigned int l1_m :1;
465  unsigned int l2_c :1;
466  unsigned int l2_p :1;
467  unsigned int l2_m :1;
468  unsigned int l5 :1;
469  } b;
470  } frequencies;
471  uint8_t elevation;
472  uint16_t azimuth;
473  uint8_t snr;
474 } satellite_t;
475 
476 typedef struct
477 {
480 
481 typedef struct
482 {
483  double position[3];
485 
486 typedef struct
487 {
488  double position[3];
490 
491 typedef struct
492 {
493  double position[3];
494  char zone;
496 
497 typedef struct
498 {
499  float velocity[3];
501 
502 typedef struct
503 {
504  float velocity[3];
506 
507 typedef struct
508 {
509  float acceleration[3];
511 
512 typedef struct
513 {
514  float acceleration[3];
515  float g_force;
517 
518 typedef struct
519 {
520  float orientation[3];
522 
523 typedef struct
524 {
525  float orientation[4];
527 
528 typedef struct
529 {
530  float orientation[3][3];
532 
533 typedef struct
534 {
535  float angular_velocity[3];
537 
538 typedef struct
539 {
540  float angular_acceleration[3];
542 
543 typedef struct
544 {
545  double position[3];
546  float velocity[3];
547  float position_standard_deviation[3];
548  float velocity_standard_deviation[3];
550 
551 typedef struct
552 {
553  double position[3];
554  float standard_deviation[3];
556 
557 typedef struct
558 {
559  float velocity[3];
560  float standard_deviation[3];
562 
563 typedef struct
564 {
565  float velocity[3];
568 
569 typedef struct
570 {
571  float heading;
574 
575 typedef struct
576 {
577  uint32_t seconds;
578  uint32_t microseconds;
580 
581 typedef struct
582 {
583  float magnetic_field[3];
585 
586 typedef struct
587 {
588  int32_t pulse_count;
589  float distance;
590  float speed;
591  float slip;
592  uint8_t active;
594 
595 typedef struct
596 {
598  uint32_t microseconds;
600 
601 typedef struct
602 {
603  float depth;
606 
607 typedef struct
608 {
611 
612 typedef struct
613 {
617 
618 typedef struct
619 {
620  float wind_velocity[2];
622 } wind_packet_t;
623 
624 typedef struct
625 {
631 
632 typedef enum
633 {
645 
646 typedef struct
647 {
649  uint32_t nanoseconds;
652  uint8_t packet_number;
653  uint8_t total_packets;
655  struct
656  {
658  uint8_t prn;
659  uint8_t elevation;
660  uint16_t azimuth;
662  struct
663  {
665  union
666  {
667  uint8_t r;
668  struct
669  {
670  unsigned int carrier_phase_valid :1;
671  unsigned int carrier_phase_cycle_slip_detected :1;
672  unsigned int carrier_phase_half_cycle_ambiguity :1;
673  unsigned int pseudo_range_valid :1;
674  unsigned int doppler_valid :1;
675  unsigned int signal_to_noise_ratio_valid :1;
676  } b;
677  } tracking_status;
679  double pseudo_range;
682  }*frequency;
683  }*satellite;
685 
686 typedef struct
687 {
688  float delay;
689  float speed;
691  union
692  {
693  uint8_t r;
694  struct
695  {
696  unsigned int reverse_detection_supported :1;
697  } b;
698  } flags;
700 
701 typedef struct
702 {
705  float altitude;
706  float airspeed;
709  union
710  {
711  uint8_t r;
712  struct
713  {
714  unsigned int altitude_set :1;
715  unsigned int airspeed_set :1;
716  unsigned int reset_qnh :1;
717  } b;
718  } flags;
720 
721 typedef enum
722 {
726 
727 typedef enum
728 {
734 
735 typedef struct
736 {
739  char serial_number[10];
741  uint32_t software_license[3];
743 
744 typedef struct
745 {
746  union
747  {
748  uint16_t r;
749  struct
750  {
751  unsigned int north_seeking_initialised :1;
752  unsigned int position_not_ready :1;
753  unsigned int excessive_roll :1;
754  unsigned int excessive_pitch :1;
755  unsigned int excessive_movement :1;
756  } b;
757  } north_seeking_status;
758  uint8_t quadrant_data_collection_progress[4];
760  float current_gyroscope_bias_solution[3];
763 
764 /* start of configuration packets typedef structs */
765 
766 typedef struct
767 {
768  uint8_t permanent;
772 
773 typedef struct
774 {
775  uint8_t packet_id;
776  uint32_t period;
778 
779 typedef struct
780 {
781  uint8_t permanent;
785 
786 typedef struct
787 {
788  uint8_t permanent;
792  uint32_t reserved;
794 
795 typedef struct
796 {
797  uint8_t permanent;
798  float alignment_dcm[3][3];
799  float gnss_antenna_offset[3];
800  float odometer_offset[3];
801  float external_data_offset[3];
803 
804 typedef enum
805 {
820 
821 typedef struct
822 {
823  uint8_t permanent;
824  uint8_t vehicle_type;
826  uint8_t reserved;
832 
833 typedef enum
834 {
874 
875 typedef enum
876 {
881 } gpio_index_e;
882 
883 typedef struct
884 {
885  uint8_t permanent;
886  uint8_t gpio_function[4];
888 
889 typedef struct
890 {
891  uint8_t permanent;
895 
896 typedef struct
897 {
898  uint8_t permanent;
900 
901 typedef struct
902 {
903  uint8_t permanent;
904  float heave_point_1_offset[3];
905  float heave_point_2_offset[3];
906  float heave_point_3_offset[3];
907  float heave_point_4_offset[3];
909 
910 typedef enum
911 {
922 } gpio_rate_e;
923 
924 typedef enum
925 {
929 
930 typedef union
931 {
932  uint16_t r;
933  struct
934  {
935  unsigned int gpio1_rate :4;
936  unsigned int auxiliary_rate :4;
937  } b;
939 
940 typedef struct
941 {
942  uint8_t permanent;
953  uint8_t reserved[13];
955 
956 typedef enum
957 {
961 
962 typedef enum
963 {
969 
970 typedef struct
971 {
972  uint8_t permanent;
973  union
974  {
975  uint16_t r;
976  struct
977  {
978  unsigned int automatic_offset_enabled :1;
979  } b;
980  } options;
982  uint8_t reserved;
983  float manual_offset[3];
985 
986 int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet);
987 an_packet_t *encode_request_packet(uint8_t requested_packet_id);
988 int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet);
990 int decode_device_information_packet(device_information_packet_t *device_information_packet, an_packet_t *an_packet);
993 int decode_file_transfer_acknowledge_packet(file_transfer_acknowledge_packet_t *file_transfer_acknowledge_packet, an_packet_t *an_packet);
994 int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet);
995 int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet);
996 int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet);
997 int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet);
998 int decode_position_standard_deviation_packet(position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet);
999 int decode_velocity_standard_deviation_packet(velocity_standard_deviation_packet_t *velocity_standard_deviation_packet, an_packet_t *an_packet);
1002 int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet);
1003 int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet);
1004 int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet);
1005 int decode_detailed_satellites_packet(detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet);
1006 int decode_geodetic_position_packet(geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet);
1007 int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet);
1008 int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet);
1009 int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet);
1010 int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet);
1011 int decode_acceleration_packet(acceleration_packet_t *acceleration, an_packet_t *an_packet);
1012 int decode_body_acceleration_packet(body_acceleration_packet_t *body_acceleration, an_packet_t *an_packet);
1013 int decode_euler_orientation_packet(euler_orientation_packet_t *euler_orientation_packet, an_packet_t *an_packet);
1014 int decode_quaternion_orientation_packet(quaternion_orientation_packet_t *quaternion_orientation_packet, an_packet_t *an_packet);
1015 int decode_dcm_orientation_packet(dcm_orientation_packet_t *dcm_orientation_packet, an_packet_t *an_packet);
1016 int decode_angular_velocity_packet(angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet);
1017 int decode_angular_acceleration_packet(angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet);
1018 int decode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet, an_packet_t *an_packet);
1020 int decode_external_position_packet(external_position_packet_t *external_position_packet, an_packet_t *an_packet);
1022 int decode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet, an_packet_t *an_packet);
1024 int decode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet, an_packet_t *an_packet);
1026 int decode_external_heading_packet(external_heading_packet_t *external_heading_packet, an_packet_t *an_packet);
1028 int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet);
1029 int decode_local_magnetics_packet(local_magnetics_packet_t *local_magnetics_packet, an_packet_t *an_packet);
1030 int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet);
1031 int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet);
1033 int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet);
1035 int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet);
1036 int decode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet, an_packet_t *an_packet);
1038 int decode_wind_packet(wind_packet_t *wind_packet, an_packet_t *an_packet);
1040 int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet);
1041 int decode_odometer_packet(odometer_packet_t *external_odometer_packet, an_packet_t *an_packet);
1043 int decode_external_air_data_packet(external_air_data_packet_t *external_air_data_packet, an_packet_t *an_packet);
1045 int decode_gnss_information_packet(gnss_receiver_information_packet_t *gnss_information_packet, an_packet_t *an_packet);
1046 int decode_north_seeking_status_packet(north_seeking_status_packet_t *north_seeking_status_packet, an_packet_t *an_packet);
1047 int decode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet);
1049 int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet);
1051 int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet);
1053 int decode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet, an_packet_t *an_packet);
1055 int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet);
1057 int decode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet, an_packet_t *an_packet);
1059 int decode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet);
1062 int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet);
1064 int decode_gpio_output_configuration_packet(gpio_output_configuration_packet_t *gpio_output_configuration_packet, an_packet_t *an_packet);
1066 int decode_dual_antenna_configuration_packet(dual_antenna_configuration_packet_t *dual_antenna_configuration_packet, an_packet_t *an_packet);
1068 
1069 #ifdef __cplusplus
1070 }
1071 #endif
1072 
1073 #endif
int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet)
gnss_manufacturers_e
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)
int decode_north_seeking_status_packet(north_seeking_status_packet_t *north_seeking_status_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)
an_packet_t * encode_dual_antenna_configuration_packet(dual_antenna_configuration_packet_t *dual_antenna_configuration_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)
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)
dual_antenna_offset_type_e
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)
gnss_receiver_models_e
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)
file_transfer_metadata_e
int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet)
int decode_gnss_information_packet(gnss_receiver_information_packet_t *gnss_information_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
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_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet)
uint8_t satellite_system
dual_antenna_automatic_offset_orientation_e
int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet)
int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet)
options
#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)
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)
int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet)
#define START_STATE_PACKETS
satellite_frequencies_e
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()
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)
int decode_dual_antenna_configuration_packet(dual_antenna_configuration_packet_t *dual_antenna_configuration_packet, an_packet_t *an_packet)


kvh_geo_fog_3d_driver
Author(s): Trevor Bostic , Zach LaCelle
autogenerated on Fri Jan 24 2020 03:18:17