00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifdef __cplusplus
00031 extern "C" {
00032 #endif
00033
00034 #define MAXIMUM_PACKET_PERIODS 50
00035 #define MAXIMUM_DETAILED_SATELLITES 32
00036
00037 #define START_SYSTEM_PACKETS 0
00038 #define START_STATE_PACKETS 20
00039 #define START_CONFIGURATION_PACKETS 180
00040
00041 typedef enum
00042 {
00043 packet_id_acknowledge,
00044 packet_id_request,
00045 packet_id_boot_mode,
00046 packet_id_device_information,
00047 packet_id_restore_factory_settings,
00048 packet_id_reset,
00049 packet_id_print,
00050 packet_id_file_transfer_request,
00051 packet_id_file_transfer_acknowledge,
00052 packet_id_file_transfer,
00053 end_system_packets,
00054
00055 packet_id_system_state = START_STATE_PACKETS,
00056 packet_id_unix_time,
00057 packet_id_formatted_time,
00058 packet_id_status,
00059 packet_id_position_standard_deviation,
00060 packet_id_velocity_standard_deviation,
00061 packet_id_euler_orientation_standard_deviation,
00062 packet_id_quaternion_orientation_standard_deviation,
00063 packet_id_raw_sensors,
00064 packet_id_raw_gnss,
00065 packet_id_satellites,
00066 packet_id_satellites_detailed,
00067 packet_id_geodetic_position,
00068 packet_id_ecef_position,
00069 packet_id_utm_position,
00070 packet_id_ned_velocity,
00071 packet_id_body_velocity,
00072 packet_id_acceleration,
00073 packet_id_body_acceleration,
00074 packet_id_euler_orientation,
00075 packet_id_quaternion_orientation,
00076 packet_id_dcm_orientation,
00077 packet_id_angular_velocity,
00078 packet_id_angular_acceleration,
00079 packet_id_external_position_velocity,
00080 packet_id_external_position,
00081 packet_id_external_velocity,
00082 packet_id_external_body_velocity,
00083 packet_id_external_heading,
00084 packet_id_running_time,
00085 packet_id_local_magnetics,
00086 packet_id_odometer_state,
00087 packet_id_external_time,
00088 packet_id_external_depth,
00089 packet_id_geoid_height,
00090 packet_id_rtcm_corrections,
00091 packet_id_external_pitot_pressure,
00092 packet_id_wind_estimation,
00093 packet_id_heave,
00094 end_state_packets,
00095
00096 packet_id_packet_timer_period = START_CONFIGURATION_PACKETS,
00097 packet_id_packet_periods,
00098 packet_id_baud_rates,
00099 packet_id_bus_configuration,
00100 packet_id_sensor_ranges,
00101 packet_id_installation_alignment,
00102 packet_id_filter_options,
00103 packet_id_filter_advanced_parameters,
00104 packet_id_gpio_configuration,
00105 packet_id_magnetic_calibration_values,
00106 packet_id_magnetic_calibration_configuration,
00107 packet_id_magnetic_calibration_status,
00108 packet_id_odometer_configuration,
00109 packet_id_zero_alignment,
00110 packet_id_heave_offset,
00111 end_configuration_packets
00112 }packet_id_e;
00113
00114
00115
00116 typedef enum
00117 {
00118 acknowledge_success,
00119 acknowledge_failure_crc,
00120 acknowledge_failure_length,
00121 acknowledge_failure_range,
00122 acknowledge_failure_flash,
00123 acknowledge_failure_not_ready,
00124 acknowledge_failure_unknown_packet
00125 } acknowledge_result_e;
00126
00127 typedef struct
00128 {
00129 uint8_t packet_id;
00130 uint16_t packet_crc;
00131 uint8_t acknowledge_result;
00132 } acknowledge_packet_t;
00133
00134 typedef enum
00135 {
00136 boot_mode_bootloader,
00137 boot_mode_main_program
00138 } boot_mode_e;
00139
00140 typedef struct
00141 {
00142 uint8_t boot_mode;
00143 } boot_mode_packet_t;
00144
00145 typedef struct
00146 {
00147 uint32_t software_version;
00148 uint32_t device_id;
00149 uint32_t hardware_revision;
00150 uint32_t serial_number[3];
00151 } device_information_packet_t;
00152
00153
00154
00155 typedef struct
00156 {
00157 union
00158 {
00159 uint16_t r;
00160 struct
00161 {
00162 unsigned int system_failure :1;
00163 unsigned int accelerometer_sensor_failure :1;
00164 unsigned int gyroscope_sensor_failure :1;
00165 unsigned int magnetometer_sensor_failure :1;
00166 unsigned int pressure_sensor_failure :1;
00167 unsigned int gnss_failure :1;
00168 unsigned int accelerometer_over_range :1;
00169 unsigned int gyroscope_over_range :1;
00170 unsigned int magnetometer_over_range :1;
00171 unsigned int pressure_over_range :1;
00172 unsigned int minimum_temperature_alarm :1;
00173 unsigned int maximum_temperature_alarm :1;
00174 unsigned int low_voltage_alarm :1;
00175 unsigned int high_voltage_alarm :1;
00176 unsigned int gnss_antenna_disconnected :1;
00177 unsigned int serial_port_overflow_alarm :1;
00178 } b;
00179 } system_status;
00180 union
00181 {
00182 uint16_t r;
00183 struct
00184 {
00185 unsigned int orientation_filter_initialised :1;
00186 unsigned int ins_filter_initialised :1;
00187 unsigned int heading_initialised :1;
00188 unsigned int utc_time_initialised :1;
00189 unsigned int gnss_2d_fix :1;
00190 unsigned int gnss_3d_fix :1;
00191 unsigned int gnss_sbas_fix :1;
00192 unsigned int gnss_differential_fix :1;
00193 unsigned int gnss_rtk_fix :1;
00194 unsigned int internal_gnss_enabled :1;
00195 unsigned int magnetometers_enabled :1;
00196 unsigned int velocity_heading_enabled :1;
00197 unsigned int atmospheric_altitude_enabled :1;
00198 unsigned int external_position_active :1;
00199 unsigned int external_velocity_active :1;
00200 unsigned int external_heading_active :1;
00201 } b;
00202 } filter_status;
00203 uint32_t unix_time_seconds;
00204 uint32_t microseconds;
00205 double latitude;
00206 double longitude;
00207 double height;
00208 float velocity[3];
00209 float body_acceleration[3];
00210 float g_force;
00211 float orientation[3];
00212 float angular_velocity[3];
00213 float standard_deviation[3];
00214 } system_state_packet_t;
00215
00216 typedef struct
00217 {
00218 uint32_t unix_time_seconds;
00219 uint32_t microseconds;
00220 } unix_time_packet_t;
00221
00222 typedef struct
00223 {
00224 uint32_t microseconds;
00225 uint16_t year;
00226 uint16_t year_day;
00227 uint8_t month;
00228 uint8_t month_day;
00229 uint8_t week_day;
00230 uint8_t hour;
00231 uint8_t minute;
00232 uint8_t second;
00233 } formatted_time_packet_t;
00234
00235 typedef struct
00236 {
00237 union
00238 {
00239 uint16_t r;
00240 struct
00241 {
00242 unsigned int system_failure :1;
00243 unsigned int accelerometer_sensor_failure :1;
00244 unsigned int gyroscope_sensor_failure :1;
00245 unsigned int magnetometer_sensor_failure :1;
00246 unsigned int pressure_sensor_failure :1;
00247 unsigned int gnss_failure :1;
00248 unsigned int accelerometer_over_range :1;
00249 unsigned int gyroscope_over_range :1;
00250 unsigned int magnetometer_over_range :1;
00251 unsigned int pressure_over_range :1;
00252 unsigned int minimum_temperature_alarm :1;
00253 unsigned int maximum_temperature_alarm :1;
00254 unsigned int low_voltage_alarm :1;
00255 unsigned int high_voltage_alarm :1;
00256 unsigned int gnss_antenna_disconnected :1;
00257 unsigned int serial_port_overflow_alarm :1;
00258 } b;
00259 } system_status;
00260 union
00261 {
00262 uint16_t r;
00263 struct
00264 {
00265 unsigned int orientation_filter_initialised :1;
00266 unsigned int ins_filter_initialised :1;
00267 unsigned int heading_initialised :1;
00268 unsigned int utc_time_initialised :1;
00269 unsigned int gnss_2d_fix :1;
00270 unsigned int gnss_3d_fix :1;
00271 unsigned int gnss_sbas_fix :1;
00272 unsigned int gnss_differential_fix :1;
00273 unsigned int gnss_rtk_fix :1;
00274 unsigned int internal_gnss_enabled :1;
00275 unsigned int magnetometers_enabled :1;
00276 unsigned int velocity_heading_enabled :1;
00277 unsigned int atmospheric_altitude_enabled :1;
00278 unsigned int external_position_active :1;
00279 unsigned int external_velocity_active :1;
00280 unsigned int external_heading_active :1;
00281 } b;
00282 } filter_status;
00283 } status_packet_t;
00284
00285 typedef struct
00286 {
00287 float standard_deviation[3];
00288 } position_standard_deviation_packet_t;
00289
00290 typedef struct
00291 {
00292 float standard_deviation[3];
00293 } velocity_standard_deviation_packet_t;
00294
00295 typedef struct
00296 {
00297 float standard_deviation[3];
00298 } euler_orientation_standard_deviation_packet_t;
00299
00300 typedef struct
00301 {
00302 float standard_deviation[4];
00303 } quaternion_orientation_standard_deviation_packet_t;
00304
00305 typedef struct
00306 {
00307 float accelerometers[3];
00308 float gyroscopes[3];
00309 float magnetometers[3];
00310 float imu_temperature;
00311 float pressure;
00312 float pressure_temperature;
00313 } raw_sensors_packet_t;
00314
00315 typedef struct
00316 {
00317 double position[3];
00318 float velocity[3];
00319 } raw_gnss_packet_t;
00320
00321 typedef struct
00322 {
00323 float hdop;
00324 float vdop;
00325 uint8_t gps_satellites;
00326 uint8_t glonass_satellites;
00327 uint8_t compass_satellites;
00328 uint8_t galileo_satellites;
00329 uint8_t sbas_satellites;
00330 } satellites_packet_t;
00331
00332 typedef enum
00333 {
00334 satellite_system_gps = 1,
00335 satellite_system_glonass = 2,
00336 satellite_system_galileo = 5,
00337 satellite_system_compass = 6,
00338 satellite_system_sbas = 4
00339 } satellite_system_e;
00340
00341 typedef struct
00342 {
00343 uint8_t satellite_system;
00344 uint8_t number;
00345 int8_t frequency;
00346 uint8_t elevation;
00347 uint16_t azimuth;
00348 uint8_t snr;
00349 } satellite_t;
00350
00351 typedef struct
00352 {
00353 satellite_t satellites[MAXIMUM_DETAILED_SATELLITES];
00354 } detailed_satellites_packet_t;
00355
00356 typedef struct
00357 {
00358 double position[3];
00359 } geodetic_position_packet_t;
00360
00361 typedef struct
00362 {
00363 double position[3];
00364 } ecef_position_packet_t;
00365
00366 typedef struct
00367 {
00368 double position[3];
00369 char zone;
00370 } utm_position_packet_t;
00371
00372 typedef struct
00373 {
00374 float velocity[3];
00375 } ned_velocity_packet_t;
00376
00377 typedef struct
00378 {
00379 float velocity[3];
00380 } body_velocity_packet_t;
00381
00382 typedef struct
00383 {
00384 float acceleration[3];
00385 } acceleration_packet_t;
00386
00387 typedef struct
00388 {
00389 float acceleration[3];
00390 float g_force;
00391 } body_acceleration_packet_t;
00392
00393 typedef struct
00394 {
00395 float orientation[3];
00396 } euler_orientation_packet_t;
00397
00398 typedef struct
00399 {
00400 float orientation[4];
00401 } quaternion_orientation_packet_t;
00402
00403 typedef struct
00404 {
00405 float orientation[3][3];
00406 } dcm_orientation_packet_t;
00407
00408 typedef struct
00409 {
00410 float angular_velocity[3];
00411 } angular_velocity_packet_t;
00412
00413 typedef struct
00414 {
00415 float angular_acceleration[3];
00416 } angular_acceleration_packet_t;
00417
00418 typedef struct
00419 {
00420 double position[3];
00421 float velocity[3];
00422 float position_standard_deviation[3];
00423 float velocity_standard_deviation[3];
00424 } external_position_velocity_packet_t;
00425
00426 typedef struct
00427 {
00428 double position[3];
00429 float standard_deviation[3];
00430 } external_position_packet_t;
00431
00432 typedef struct
00433 {
00434 float velocity[3];
00435 float standard_deviation[3];
00436 } external_velocity_packet_t;
00437
00438 typedef struct
00439 {
00440 float velocity[3];
00441 float standard_deviation;
00442 } external_body_velocity_packet_t;
00443
00444 typedef struct
00445 {
00446 float heading;
00447 float standard_deviation;
00448 } external_heading_packet_t;
00449
00450 typedef struct
00451 {
00452 uint32_t seconds;
00453 uint32_t microseconds;
00454 } running_time_packet_t;
00455
00456 typedef struct
00457 {
00458 float magnetic_field[3];
00459 } local_magnetics_packet_t;
00460
00461 typedef struct
00462 {
00463 uint32_t pulse_count;
00464 float distance;
00465 float speed;
00466 float slip;
00467 uint8_t active;
00468 } odometer_state_packet_t;
00469
00470 typedef struct
00471 {
00472 uint32_t unix_time_seconds;
00473 uint32_t microseconds;
00474 } external_time_packet_t;
00475
00476 typedef struct
00477 {
00478 float depth;
00479 float standard_deviation;
00480 } external_depth_packet_t;
00481
00482 typedef struct
00483 {
00484 float geoid_height;
00485 } geoid_height_packet_t;
00486
00487 typedef struct
00488 {
00489 float differential_pressure;
00490 float outside_air_temperature;
00491 } external_pitot_pressure_packet_t;
00492
00493 typedef struct
00494 {
00495 float wind_velocity[3];
00496 } wind_estimation_packet_t;
00497
00498 typedef struct
00499 {
00500 float heave_point_1;
00501 float heave_point_2;
00502 float heave_point_3;
00503 float heave_point_4;
00504 } heave_packet_t;
00505
00506
00507
00508 typedef struct
00509 {
00510 uint8_t permanent;
00511 uint8_t utc_synchronisation;
00512 uint16_t packet_timer_period;
00513 } packet_timer_period_packet_t;
00514
00515 typedef struct
00516 {
00517 uint8_t packet_id;
00518 uint32_t period;
00519 } packet_period_t;
00520
00521 typedef struct
00522 {
00523 uint8_t permanent;
00524 uint8_t clear_existing_packets;
00525 packet_period_t packet_periods[MAXIMUM_PACKET_PERIODS];
00526 } packet_periods_packet_t;
00527
00528 typedef struct
00529 {
00530 uint8_t permanent;
00531 uint32_t primary_baud_rate;
00532 uint32_t gpio_1_2_baud_rate;
00533 uint32_t gpio_3_4_baud_rate;
00534 uint32_t reserved;
00535 } baud_rates_packet_t;
00536
00537 typedef enum
00538 {
00539 accelerometer_range_2g,
00540 accelerometer_range_4g,
00541 accelerometer_range_16g
00542 } accelerometer_range_e;
00543
00544 typedef enum
00545 {
00546 gyroscope_range_250dps,
00547 gyroscope_range_500dps,
00548 gyroscope_range_2000dps
00549 } gyroscope_range_e;
00550
00551 typedef enum
00552 {
00553 magnetometer_range_2g,
00554 magnetometer_range_4g,
00555 magnetometer_range_8g
00556 } magnetometer_range_e;
00557
00558 typedef struct
00559 {
00560 uint8_t permanent;
00561 uint8_t accelerometers_range;
00562 uint8_t gyroscopes_range;
00563 uint8_t magnetometers_range;
00564 } sensor_ranges_packet_t;
00565
00566 typedef struct
00567 {
00568 uint8_t permanent;
00569 float alignment_dcm[3][3];
00570 float gnss_antenna_offset[3];
00571 float odometer_offset[3];
00572 float external_data_offset[3];
00573 } installation_alignment_packet_t;
00574
00575 typedef enum
00576 {
00577 vehicle_type_unconstrained,
00578 vehicle_type_motorcycle,
00579 vehicle_type_car,
00580 vehicle_type_hovercraft,
00581 vehicle_type_submarine,
00582 vehicle_type_3d_underwater,
00583 vehicle_type_fixed_wing_plane,
00584 vehicle_type_3d_aircraft,
00585 vehicle_type_human
00586 } vehicle_type_e;
00587
00588 typedef struct
00589 {
00590 uint8_t permanent;
00591 uint8_t vehicle_type;
00592 uint8_t internal_gnss_enabled;
00593 uint8_t magnetometers_enabled;
00594 uint8_t atmospheric_altitude_enabled;
00595 uint8_t velocity_heading_enabled;
00596 } filter_options_packet_t;
00597
00598 typedef enum
00599 {
00600 inactive,
00601 pps_output,
00602 gnss_fix_output,
00603 odometer_input,
00604 stationary_input,
00605 pitot_tube_input,
00606 nmea_input,
00607 nmea_output,
00608 novatel_gnss_input,
00609 topcon_gnss_input,
00610 motec_output,
00611 anpp_input,
00612 anpp_output,
00613 disable_magnetometers,
00614 disable_gnss,
00615 disable_pressure,
00616 set_zero_alignment,
00617 packet_trigger_system_state,
00618 packet_trigger_raw_sensors,
00619 rtcm_corrections_input,
00620 trimble_gnss_input,
00621 ublox_gnss_input,
00622 hemisphere_gnss_input,
00623 teledyne_dvl_input,
00624 tritech_usbl_input,
00625 linkquest_dvl_input,
00626 pressure_depth_sensor,
00627 left_wheel_speed_sensor,
00628 right_wheel_speed_sensor
00629 } gpio_function_e;
00630
00631 typedef enum
00632 {
00633 gpio1,
00634 gpio2,
00635 gpio3,
00636 gpio4,
00637 gpio5,
00638 gpio6
00639 } gpio_index_e;
00640
00641 typedef struct
00642 {
00643 uint8_t permanent;
00644 uint8_t gpio_function[4];
00645 } gpio_configuration_packet_t;
00646
00647 typedef struct
00648 {
00649 uint8_t permanent;
00650 float hard_iron[3];
00651 float soft_iron[3][3];
00652 } magnetic_calibration_values_packet_t;
00653
00654 typedef enum
00655 {
00656 magnetic_calibration_action_cancel,
00657 magnetic_calibration_action_stabilise,
00658 magnetic_calibration_action_start_2d,
00659 magnetic_calibration_action_start_3d
00660 } magnetic_calibration_action_e;
00661
00662 typedef struct
00663 {
00664 uint8_t magnetic_calibration_action;
00665 } magnetic_calibration_configuration_packet_t;
00666
00667 typedef enum
00668 {
00669 magnetic_calibration_status_not_completed,
00670 magnetic_calibration_status_completed_2d,
00671 magnetic_calibration_status_completed_3d,
00672 magnetic_calibration_status_completed_user,
00673 magnetic_calibration_status_stabilizing,
00674 magnetic_calibration_status_in_progress_2d,
00675 magnetic_calibration_status_in_progress_3d,
00676 magnetic_calibration_status_error_excessive_roll,
00677 magnetic_calibration_status_error_excessive_pitch,
00678 magnetic_calibration_status_error_overrange_event,
00679 magnetic_calibration_status_error_timeout,
00680 magnetic_calibration_status_error_system
00681 } magnetic_calibration_status_e;
00682
00683 typedef struct
00684 {
00685 uint8_t magnetic_calibration_status;
00686 uint8_t magnetic_calibration_progress_percentage;
00687 uint8_t local_magnetic_error_percentage;
00688 } magnetic_calibration_status_packet_t;
00689
00690 typedef struct
00691 {
00692 uint8_t permanent;
00693 uint8_t automatic_calibration;
00694 float pulse_length;
00695 } odometer_configuration_packet_t;
00696
00697 typedef struct
00698 {
00699 uint8_t permanent;
00700 } zero_alignment_packet_t;
00701
00702 typedef struct
00703 {
00704 uint8_t permanent;
00705 float heave_point_1_offset[3];
00706 float heave_point_2_offset[3];
00707 float heave_point_3_offset[3];
00708 float heave_point_4_offset[3];
00709 } heave_offset_packet_t;
00710
00711 int decode_acknowledge_packet(acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet);
00712 an_packet_t *encode_request_packet(uint8_t requested_packet_id);
00713 int decode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet, an_packet_t *an_packet);
00714 an_packet_t *encode_boot_mode_packet(boot_mode_packet_t *boot_mode_packet);
00715 int decode_device_information_packet(device_information_packet_t *device_information_packet, an_packet_t *an_packet);
00716 an_packet_t *encode_restore_factory_settings_packet();
00717 an_packet_t *encode_reset_packet();
00718 int decode_system_state_packet(system_state_packet_t *system_state_packet, an_packet_t *an_packet);
00719 int decode_unix_time_packet(unix_time_packet_t *unix_time_packet, an_packet_t *an_packet);
00720 int decode_formatted_time_packet(formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet);
00721 int decode_status_packet(status_packet_t *status_packet, an_packet_t *an_packet);
00722 int decode_position_standard_deviation_packet(position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet);
00723 int decode_velocity_standard_deviation_packet(velocity_standard_deviation_packet_t *velocity_standard_deviation_packet, an_packet_t *an_packet);
00724 int decode_euler_orientation_standard_deviation_packet(euler_orientation_standard_deviation_packet_t *euler_orientation_standard_deviation, an_packet_t *an_packet);
00725 int decode_quaternion_orientation_standard_deviation_packet(quaternion_orientation_standard_deviation_packet_t *quaternion_orientation_standard_deviation_packet, an_packet_t *an_packet);
00726 int decode_raw_sensors_packet(raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet);
00727 int decode_raw_gnss_packet(raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet);
00728 int decode_satellites_packet(satellites_packet_t *satellites_packet, an_packet_t *an_packet);
00729 int decode_detailed_satellites_packet(detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet);
00730 int decode_geodetic_position_packet(geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet);
00731 int decode_ecef_position_packet(ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet);
00732 int decode_utm_position_packet(utm_position_packet_t *utm_position_packet, an_packet_t *an_packet);
00733 int decode_ned_velocity_packet(ned_velocity_packet_t *ned_velocity_packet, an_packet_t *an_packet);
00734 int decode_body_velocity_packet(body_velocity_packet_t *body_velocity_packet, an_packet_t *an_packet);
00735 int decode_acceleration_packet(acceleration_packet_t *acceleration, an_packet_t *an_packet);
00736 int decode_body_acceleration_packet(body_acceleration_packet_t *body_acceleration, an_packet_t *an_packet);
00737 int decode_euler_orientation_packet(euler_orientation_packet_t *euler_orientation_packet, an_packet_t *an_packet);
00738 int decode_quaternion_orientation_packet(quaternion_orientation_packet_t *quaternion_orientation_packet, an_packet_t *an_packet);
00739 int decode_dcm_orientation_packet(dcm_orientation_packet_t *dcm_orientation_packet, an_packet_t *an_packet);
00740 int decode_angular_velocity_packet(angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet);
00741 int decode_angular_acceleration_packet(angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet);
00742 int decode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet, an_packet_t *an_packet);
00743 an_packet_t *encode_external_position_velocity_packet(external_position_velocity_packet_t *external_position_velocity_packet);
00744 int decode_external_position_packet(external_position_packet_t *external_position_packet, an_packet_t *an_packet);
00745 an_packet_t *encode_external_position_packet(external_position_packet_t *external_position_packet);
00746 int decode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet, an_packet_t *an_packet);
00747 an_packet_t *encode_external_velocity_packet(external_velocity_packet_t *external_velocity_packet);
00748 int decode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet, an_packet_t *an_packet);
00749 an_packet_t *encode_external_body_velocity_packet(external_body_velocity_packet_t *external_body_velocity_packet);
00750 int decode_external_heading_packet(external_heading_packet_t *external_heading_packet, an_packet_t *an_packet);
00751 an_packet_t *encode_external_heading_packet(external_heading_packet_t *external_heading_packet);
00752 int decode_running_time_packet(running_time_packet_t *running_time_packet, an_packet_t *an_packet);
00753 int decode_local_magnetics_packet(local_magnetics_packet_t *local_magnetics_packet, an_packet_t *an_packet);
00754 int decode_odometer_state_packet(odometer_state_packet_t *odometer_state_packet, an_packet_t *an_packet);
00755 int decode_external_time_packet(external_time_packet_t *external_time_packet, an_packet_t *an_packet);
00756 an_packet_t *encode_external_time_packet(external_time_packet_t *external_time_packet);
00757 int decode_external_depth_packet(external_depth_packet_t *external_depth_packet, an_packet_t *an_packet);
00758 an_packet_t *encode_external_depth_packet(external_depth_packet_t *external_depth_packet);
00759 int decode_geoid_height_packet(geoid_height_packet_t *geoid_height_packet, an_packet_t *an_packet);
00760 int decode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet, an_packet_t *an_packet);
00761 an_packet_t *encode_external_pitot_pressure_packet(external_pitot_pressure_packet_t *external_pitot_pressure_packet);
00762 int decode_wind_estimation_packet(wind_estimation_packet_t *wind_estimation_packet, an_packet_t *an_packet);
00763 int decode_heave_packet(heave_packet_t *heave_packet, an_packet_t *an_packet);
00764 int decode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet, an_packet_t *an_packet);
00765 an_packet_t *encode_packet_timer_period_packet(packet_timer_period_packet_t *packet_timer_period_packet);
00766 int decode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet, an_packet_t *an_packet);
00767 an_packet_t *encode_packet_periods_packet(packet_periods_packet_t *packet_periods_packet);
00768 int decode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet);
00769 an_packet_t *encode_baud_rates_packet(baud_rates_packet_t *baud_rates_packet);
00770 int decode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet, an_packet_t *an_packet);
00771 an_packet_t *encode_sensor_ranges_packet(sensor_ranges_packet_t *sensor_ranges_packet);
00772 int decode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet, an_packet_t *an_packet);
00773 an_packet_t *encode_installation_alignment_packet(installation_alignment_packet_t *installation_alignment_packet);
00774 int decode_filter_options_packet(filter_options_packet_t *filter_options_packet, an_packet_t *an_packet);
00775 an_packet_t *encode_filter_options_packet(filter_options_packet_t *filter_options_packet);
00776 int decode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet, an_packet_t *an_packet);
00777 an_packet_t *encode_gpio_configuration_packet(gpio_configuration_packet_t *gpio_configuration_packet);
00778 int decode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet, an_packet_t *an_packet);
00779 an_packet_t *encode_magnetic_calibration_values_packet(magnetic_calibration_values_packet_t *magnetic_calibration_values_packet);
00780 an_packet_t *encode_magnetic_calibration_configuration_packet(magnetic_calibration_configuration_packet_t *magnetic_calibration_configuration_packet);
00781 int decode_magnetic_calibration_status_packet(magnetic_calibration_status_packet_t *magnetic_calibration_status_packet, an_packet_t *an_packet);
00782 int decode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet);
00783 an_packet_t *encode_odometer_configuration_packet(odometer_configuration_packet_t *odometer_configuration_packet);
00784 an_packet_t *encode_zero_alignment_packet(zero_alignment_packet_t *zero_alignment_packet);
00785 int decode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet);
00786 an_packet_t *encode_heave_offset_packet(heave_offset_packet_t *heave_offset_packet);
00787
00788 #ifdef __cplusplus
00789 }
00790 #endif