Classes | Macros | Enumerations | Functions
spatial_packets.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  acceleration_packet_t
 
struct  acknowledge_packet_t
 
struct  angular_acceleration_packet_t
 
struct  angular_velocity_packet_t
 
struct  baud_rates_packet_t
 
struct  body_acceleration_packet_t
 
struct  body_velocity_packet_t
 
struct  boot_mode_packet_t
 
struct  dcm_orientation_packet_t
 
struct  detailed_satellites_packet_t
 
struct  device_information_packet_t
 
struct  dual_antenna_configuration_packet_t
 
struct  ecef_position_packet_t
 
struct  euler_orientation_packet_t
 
struct  euler_orientation_standard_deviation_packet_t
 
struct  external_air_data_packet_t
 
struct  external_body_velocity_packet_t
 
struct  external_depth_packet_t
 
struct  external_heading_packet_t
 
struct  external_pitot_pressure_packet_t
 
struct  external_position_packet_t
 
struct  external_position_velocity_packet_t
 
struct  external_time_packet_t
 
struct  external_velocity_packet_t
 
struct  file_transfer_acknowledge_packet_t
 
struct  file_transfer_first_packet_t
 
struct  file_transfer_ongoing_packet_t
 
struct  filter_options_packet_t
 
struct  formatted_time_packet_t
 
struct  geodetic_position_packet_t
 
struct  geoid_height_packet_t
 
struct  gnss_receiver_information_packet_t
 
struct  gpio_configuration_packet_t
 
struct  gpio_output_configuration_packet_t
 
union  gpio_output_rate_u
 
struct  heave_offset_packet_t
 
struct  heave_packet_t
 
struct  installation_alignment_packet_t
 
struct  local_magnetics_packet_t
 
struct  ned_velocity_packet_t
 
struct  north_seeking_status_packet_t
 
struct  odometer_configuration_packet_t
 
struct  odometer_packet_t
 
struct  odometer_state_packet_t
 
struct  packet_period_t
 
struct  packet_periods_packet_t
 
struct  packet_timer_period_packet_t
 
struct  position_standard_deviation_packet_t
 
struct  quaternion_orientation_packet_t
 
struct  quaternion_orientation_standard_deviation_packet_t
 
struct  raw_gnss_packet_t
 
struct  raw_satellite_data_packet_t
 
struct  raw_sensors_packet_t
 
struct  running_time_packet_t
 
struct  satellite_t
 
struct  satellites_packet_t
 
struct  status_packet_t
 
struct  system_state_packet_t
 
struct  unix_time_packet_t
 
struct  utm_position_packet_t
 
struct  velocity_standard_deviation_packet_t
 
struct  wind_packet_t
 
struct  zero_alignment_packet_t
 

Macros

#define MAXIMUM_DETAILED_SATELLITES   32
 
#define MAXIMUM_PACKET_PERIODS   50
 
#define START_CONFIGURATION_PACKETS   180
 
#define START_STATE_PACKETS   20
 
#define START_SYSTEM_PACKETS   0
 

Enumerations

enum  acknowledge_result_e {
  acknowledge_success, acknowledge_failure_crc, acknowledge_failure_length, acknowledge_failure_range,
  acknowledge_failure_flash, acknowledge_failure_not_ready, acknowledge_failure_unknown_packet
}
 
enum  boot_mode_e { boot_mode_bootloader, boot_mode_main_program }
 
enum  data_encoding_e { data_encoding_binary, data_encoding_aes256 }
 
enum  dual_antenna_automatic_offset_orientation_e { dual_antenna_automatic_offset_primary_front_secondary_rear, dual_antenna_automatic_offset_primary_rear_secondary_front, dual_antenna_automatic_offset_primary_right_secondary_left, dual_antenna_automatic_offset_primary_left_secondary_right }
 
enum  dual_antenna_offset_type_e { dual_antenna_offset_type_manual, dual_antenna_offset_type_automatic }
 
enum  file_transfer_metadata_e { file_transfer_metadata_none, file_transfer_metadata_extended_anpp, file_transfer_metadata_utf8_filename, file_transfer_metadata_an_firmware }
 
enum  file_transfer_response_e {
  file_transfer_response_completed_successfully, file_transfer_response_ready, file_transfer_response_index_mismatch, file_transfer_response_refused = 64,
  file_transfer_response_bad_metadata, file_transfer_response_timeout, file_transfer_response_retry_error, file_transfer_response_storage_error,
  file_transfer_response_data_invalid, file_transfer_response_packet_length_invalid, file_transfer_response_total_size_invalid, file_transfer_response_overflow_error,
  file_transfer_response_busy, file_transfer_response_cancelled, file_transfer_response_file_not_found = 128, file_transfer_response_access_denied
}
 
enum  gnss_fix_type_e {
  gnss_fix_none, gnss_fix_2d, gnss_fix_3d, gnss_fix_sbas,
  gnss_fix_differential, gnss_fix_omnistar, gnss_fix_rtk_float, gnss_fix_rtk_fixed
}
 
enum  gnss_manufacturers_e { gnss_manufacturer_unknown, gnss_manufacturer_trimble }
 
enum  gnss_receiver_models_e { gnss_receiver_model_unknown, gnss_receiver_model_trimble_bd920, gnss_receiver_model_trimble_bd930, gnss_receiver_model_trimble_bd982 }
 
enum  gpio_function_e {
  inactive, pps_output, gnss_fix_output, odometer_input,
  stationary_input, pitot_tube_input, nmea_input, nmea_output,
  novatel_gnss_input, topcon_gnss_input, motec_output, anpp_input,
  anpp_output, disable_magnetometers, disable_gnss, disable_pressure,
  set_zero_alignment, packet_trigger_system_state, packet_trigger_raw_sensors, rtcm_corrections_input,
  trimble_gnss_input, ublox_gnss_input, hemisphere_gnss_input, teledyne_dvl_input,
  tritech_usbl_input, linkquest_dvl_input, pressure_depth_sensor, left_wheel_speed_sensor,
  right_wheel_speed_sensor, pps_input, wheel_speed_sensor, wheel_encoder_phase_a,
  wheel_encoder_phase_b, event1_input, event2_input, linkquest_usbl_input,
  ixblue_input, sonardyne_input
}
 
enum  gpio_index_e { gpio1, gpio2, auxiliary_tx, auxiliary_rx }
 
enum  gpio_rate_e {
  gpio_rate_disabled, gpio_rate_0o1hz, gpio_rate_0o2hz, gpio_rate_0o5hz,
  gpio_rate_1hz, gpio_rate_2hz, gpio_rate_5hz, gpio_rate_10hz,
  gpio_rate_25hz, gpio_rate_50hz
}
 
enum  nmea_fix_behaviour_e { nmea_fix_behaviour_normal, nmea_fix_behaviour_always_3d }
 
enum  packet_id_e {
  packet_id_acknowledge, packet_id_request, packet_id_boot_mode, packet_id_device_information,
  packet_id_restore_factory_settings, packet_id_reset, packet_id_print, packet_id_file_transfer_request,
  packet_id_file_transfer_acknowledge, packet_id_file_transfer, packet_id_serial_port_passthrough, end_system_packets,
  packet_id_system_state = START_STATE_PACKETS, packet_id_unix_time, packet_id_formatted_time, packet_id_status,
  packet_id_position_standard_deviation, packet_id_velocity_standard_deviation, packet_id_euler_orientation_standard_deviation, packet_id_quaternion_orientation_standard_deviation,
  packet_id_raw_sensors, packet_id_raw_gnss, packet_id_satellites, packet_id_satellites_detailed,
  packet_id_geodetic_position, packet_id_ecef_position, packet_id_utm_position, packet_id_ned_velocity,
  packet_id_body_velocity, packet_id_acceleration, packet_id_body_acceleration, packet_id_euler_orientation,
  packet_id_quaternion_orientation, packet_id_dcm_orientation, packet_id_angular_velocity, packet_id_angular_acceleration,
  packet_id_external_position_velocity, packet_id_external_position, packet_id_external_velocity, packet_id_external_body_velocity,
  packet_id_external_heading, packet_id_running_time, packet_id_local_magnetics, packet_id_odometer_state,
  packet_id_external_time, packet_id_external_depth, packet_id_geoid_height, packet_id_rtcm_corrections,
  packet_id_external_pitot_pressure, packet_id_wind, packet_id_heave, packet_id_post_processing,
  packet_id_raw_satellite_data, packet_id_raw_satellite_ephemeris, packet_id_depth, packet_id_water_profiling,
  packet_id_external_usbl, packet_id_speed_of_sound, packet_id_lockheed, packet_id_external_odometer,
  packet_id_external_air_data, packet_id_gnss_receiver_information, packet_id_raw_dvl_data, packet_id_north_seeking_status,
  end_state_packets, packet_id_packet_timer_period = START_CONFIGURATION_PACKETS, packet_id_packet_periods, packet_id_baud_rates,
  packet_id_bus_configuration, packet_id_sensor_ranges, packet_id_installation_alignment, packet_id_filter_options,
  packet_id_filter_trust, packet_id_gpio_configuration, packet_id_magnetic_calibration_values, packet_id_magnetic_calibration_configuration,
  packet_id_magnetic_calibration_status, packet_id_odometer_configuration, packet_id_zero_alignment, packet_id_heave_offset,
  packet_id_gpio_output_configuration, packet_id_dual_antenna_configuration, end_configuration_packets
}
 
enum  satellite_frequencies_e {
  satellite_frequency_unknown, satellite_frequency_l1_ca, satellite_frequency_l1_c, satellite_frequency_l1_p,
  satellite_frequency_l1_m, satellite_frequency_l2_c, satellite_frequency_l2_p, satellite_frequency_l2_m,
  satellite_frequency_l5, satellite_frequency_l3
}
 
enum  satellite_system_e {
  satellite_system_unknown, satellite_system_gps, satellite_system_glonass, satellite_system_beidou,
  satellite_system_galileo, satellite_system_sbas, satellite_system_qzss, satellite_system_starfire,
  satellite_system_omnistar
}
 
enum  vehicle_type_e {
  vehicle_type_unlimited, vehicle_type_bicycle, vehicle_type_car, vehicle_type_hovercraft,
  vehicle_type_submarine, vehicle_type_3d_underwater, vehicle_type_fixed_wing_plane, vehicle_type_3d_aircraft,
  vehicle_type_human, vehicle_type_small_boat, vehicle_type_ship, vehicle_type_stationary,
  vehicle_type_stunt_plane
}
 

Functions

int decode_acceleration_packet (acceleration_packet_t *acceleration, an_packet_t *an_packet)
 
int decode_acknowledge_packet (acknowledge_packet_t *acknowledge_packet, an_packet_t *an_packet)
 
int decode_angular_acceleration_packet (angular_acceleration_packet_t *angular_acceleration_packet, an_packet_t *an_packet)
 
int decode_angular_velocity_packet (angular_velocity_packet_t *angular_velocity_packet, an_packet_t *an_packet)
 
int decode_baud_rates_packet (baud_rates_packet_t *baud_rates_packet, an_packet_t *an_packet)
 
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)
 
int decode_boot_mode_packet (boot_mode_packet_t *boot_mode_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_detailed_satellites_packet (detailed_satellites_packet_t *detailed_satellites_packet, an_packet_t *an_packet)
 
int decode_device_information_packet (device_information_packet_t *device_information_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)
 
int decode_ecef_position_packet (ecef_position_packet_t *ecef_position_packet, an_packet_t *an_packet)
 
int decode_euler_orientation_packet (euler_orientation_packet_t *euler_orientation_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)
 
int decode_external_air_data_packet (external_air_data_packet_t *external_air_data_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_external_depth_packet (external_depth_packet_t *external_depth_packet, an_packet_t *an_packet)
 
int decode_external_heading_packet (external_heading_packet_t *external_heading_packet, an_packet_t *an_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_packet (external_position_packet_t *external_position_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)
 
int decode_external_time_packet (external_time_packet_t *external_time_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_file_transfer_acknowledge_packet (file_transfer_acknowledge_packet_t *file_transfer_acknowledge_packet, an_packet_t *an_packet)
 
int decode_filter_options_packet (filter_options_packet_t *filter_options_packet, an_packet_t *an_packet)
 
int decode_formatted_time_packet (formatted_time_packet_t *formatted_time_packet, an_packet_t *an_packet)
 
int decode_geodetic_position_packet (geodetic_position_packet_t *geodetic_position_packet, an_packet_t *an_packet)
 
int decode_geoid_height_packet (geoid_height_packet_t *geoid_height_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_gpio_configuration_packet (gpio_configuration_packet_t *gpio_configuration_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_heave_offset_packet (heave_offset_packet_t *heave_offset_packet, an_packet_t *an_packet)
 
int decode_heave_packet (heave_packet_t *heave_packet, an_packet_t *an_packet)
 
int decode_installation_alignment_packet (installation_alignment_packet_t *installation_alignment_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_ned_velocity_packet (ned_velocity_packet_t *ned_velocity_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)
 
int decode_odometer_configuration_packet (odometer_configuration_packet_t *odometer_configuration_packet, an_packet_t *an_packet)
 
int decode_odometer_packet (odometer_packet_t *external_odometer_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_packet_periods_packet (packet_periods_packet_t *packet_periods_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)
 
int decode_position_standard_deviation_packet (position_standard_deviation_packet_t *position_standard_deviation_packet, an_packet_t *an_packet)
 
int decode_quaternion_orientation_packet (quaternion_orientation_packet_t *quaternion_orientation_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_raw_gnss_packet (raw_gnss_packet_t *raw_gnss_packet, an_packet_t *an_packet)
 
int decode_raw_sensors_packet (raw_sensors_packet_t *raw_sensors_packet, an_packet_t *an_packet)
 
int decode_running_time_packet (running_time_packet_t *running_time_packet, an_packet_t *an_packet)
 
int decode_satellites_packet (satellites_packet_t *satellites_packet, an_packet_t *an_packet)
 
int decode_status_packet (status_packet_t *status_packet, an_packet_t *an_packet)
 
int decode_system_state_packet (system_state_packet_t *system_state_packet, an_packet_t *an_packet)
 
int decode_unix_time_packet (unix_time_packet_t *unix_time_packet, an_packet_t *an_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_wind_packet (wind_packet_t *wind_packet, an_packet_t *an_packet)
 
an_packet_tencode_baud_rates_packet (baud_rates_packet_t *baud_rates_packet)
 
an_packet_tencode_boot_mode_packet (boot_mode_packet_t *boot_mode_packet)
 
an_packet_tencode_dual_antenna_configuration_packet (dual_antenna_configuration_packet_t *dual_antenna_configuration_packet)
 
an_packet_tencode_external_air_data_packet (external_air_data_packet_t *external_air_data_packet)
 
an_packet_tencode_external_body_velocity_packet (external_body_velocity_packet_t *external_body_velocity_packet)
 
an_packet_tencode_external_depth_packet (external_depth_packet_t *external_depth_packet)
 
an_packet_tencode_external_heading_packet (external_heading_packet_t *external_heading_packet)
 
an_packet_tencode_external_odometer_packet (odometer_packet_t *external_odometer_packet)
 
an_packet_tencode_external_pitot_pressure_packet (external_pitot_pressure_packet_t *external_pitot_pressure_packet)
 
an_packet_tencode_external_position_packet (external_position_packet_t *external_position_packet)
 
an_packet_tencode_external_position_velocity_packet (external_position_velocity_packet_t *external_position_velocity_packet)
 
an_packet_tencode_external_time_packet (external_time_packet_t *external_time_packet)
 
an_packet_tencode_external_velocity_packet (external_velocity_packet_t *external_velocity_packet)
 
an_packet_tencode_filter_options_packet (filter_options_packet_t *filter_options_packet)
 
an_packet_tencode_gpio_configuration_packet (gpio_configuration_packet_t *gpio_configuration_packet)
 
an_packet_tencode_gpio_output_configuration_packet (gpio_output_configuration_packet_t *gpio_output_configuration_packet)
 
an_packet_tencode_heave_offset_packet (heave_offset_packet_t *heave_offset_packet)
 
an_packet_tencode_installation_alignment_packet (installation_alignment_packet_t *installation_alignment_packet)
 
an_packet_tencode_odometer_configuration_packet (odometer_configuration_packet_t *odometer_configuration_packet)
 
an_packet_tencode_packet_periods_packet (packet_periods_packet_t *packet_periods_packet)
 
an_packet_tencode_packet_timer_period_packet (packet_timer_period_packet_t *packet_timer_period_packet)
 
an_packet_tencode_request_packet (uint8_t requested_packet_id)
 
an_packet_tencode_reset_packet ()
 
an_packet_tencode_restore_factory_settings_packet ()
 
an_packet_tencode_wind_packet (wind_packet_t *wind_packet)
 
an_packet_tencode_zero_alignment_packet (zero_alignment_packet_t *zero_alignment_packet)
 

Macro Definition Documentation

◆ MAXIMUM_DETAILED_SATELLITES

#define MAXIMUM_DETAILED_SATELLITES   32

Definition at line 39 of file spatial_packets.h.

◆ MAXIMUM_PACKET_PERIODS

#define MAXIMUM_PACKET_PERIODS   50

Definition at line 38 of file spatial_packets.h.

◆ START_CONFIGURATION_PACKETS

#define START_CONFIGURATION_PACKETS   180

Definition at line 43 of file spatial_packets.h.

◆ START_STATE_PACKETS

#define START_STATE_PACKETS   20

Definition at line 42 of file spatial_packets.h.

◆ START_SYSTEM_PACKETS

#define START_SYSTEM_PACKETS   0

Definition at line 41 of file spatial_packets.h.

Enumeration Type Documentation

◆ acknowledge_result_e

Enumerator
acknowledge_success 
acknowledge_failure_crc 
acknowledge_failure_length 
acknowledge_failure_range 
acknowledge_failure_flash 
acknowledge_failure_not_ready 
acknowledge_failure_unknown_packet 

Definition at line 136 of file spatial_packets.h.

◆ boot_mode_e

Enumerator
boot_mode_bootloader 
boot_mode_main_program 

Definition at line 154 of file spatial_packets.h.

◆ data_encoding_e

Enumerator
data_encoding_binary 
data_encoding_aes256 

Definition at line 173 of file spatial_packets.h.

◆ dual_antenna_automatic_offset_orientation_e

Enumerator
dual_antenna_automatic_offset_primary_front_secondary_rear 
dual_antenna_automatic_offset_primary_rear_secondary_front 
dual_antenna_automatic_offset_primary_right_secondary_left 
dual_antenna_automatic_offset_primary_left_secondary_right 

Definition at line 962 of file spatial_packets.h.

◆ dual_antenna_offset_type_e

Enumerator
dual_antenna_offset_type_manual 
dual_antenna_offset_type_automatic 

Definition at line 956 of file spatial_packets.h.

◆ file_transfer_metadata_e

Enumerator
file_transfer_metadata_none 
file_transfer_metadata_extended_anpp 
file_transfer_metadata_utf8_filename 
file_transfer_metadata_an_firmware 

Definition at line 199 of file spatial_packets.h.

◆ file_transfer_response_e

Enumerator
file_transfer_response_completed_successfully 
file_transfer_response_ready 
file_transfer_response_index_mismatch 
file_transfer_response_refused 
file_transfer_response_bad_metadata 
file_transfer_response_timeout 
file_transfer_response_retry_error 
file_transfer_response_storage_error 
file_transfer_response_data_invalid 
file_transfer_response_packet_length_invalid 
file_transfer_response_total_size_invalid 
file_transfer_response_overflow_error 
file_transfer_response_busy 
file_transfer_response_cancelled 
file_transfer_response_file_not_found 
file_transfer_response_access_denied 

Definition at line 179 of file spatial_packets.h.

◆ gnss_fix_type_e

Enumerator
gnss_fix_none 
gnss_fix_2d 
gnss_fix_3d 
gnss_fix_sbas 
gnss_fix_differential 
gnss_fix_omnistar 
gnss_fix_rtk_float 
gnss_fix_rtk_fixed 

Definition at line 234 of file spatial_packets.h.

◆ gnss_manufacturers_e

Enumerator
gnss_manufacturer_unknown 
gnss_manufacturer_trimble 

Definition at line 721 of file spatial_packets.h.

◆ gnss_receiver_models_e

Enumerator
gnss_receiver_model_unknown 
gnss_receiver_model_trimble_bd920 
gnss_receiver_model_trimble_bd930 
gnss_receiver_model_trimble_bd982 

Definition at line 727 of file spatial_packets.h.

◆ gpio_function_e

Enumerator
inactive 
pps_output 
gnss_fix_output 
odometer_input 
stationary_input 
pitot_tube_input 
nmea_input 
nmea_output 
novatel_gnss_input 
topcon_gnss_input 
motec_output 
anpp_input 
anpp_output 
disable_magnetometers 
disable_gnss 
disable_pressure 
set_zero_alignment 
packet_trigger_system_state 
packet_trigger_raw_sensors 
rtcm_corrections_input 
trimble_gnss_input 
ublox_gnss_input 
hemisphere_gnss_input 
teledyne_dvl_input 
tritech_usbl_input 
linkquest_dvl_input 
pressure_depth_sensor 
left_wheel_speed_sensor 
right_wheel_speed_sensor 
pps_input 
wheel_speed_sensor 
wheel_encoder_phase_a 
wheel_encoder_phase_b 
event1_input 
event2_input 
linkquest_usbl_input 
ixblue_input 
sonardyne_input 

Definition at line 833 of file spatial_packets.h.

◆ gpio_index_e

Enumerator
gpio1 
gpio2 
auxiliary_tx 
auxiliary_rx 

Definition at line 875 of file spatial_packets.h.

◆ gpio_rate_e

Enumerator
gpio_rate_disabled 
gpio_rate_0o1hz 
gpio_rate_0o2hz 
gpio_rate_0o5hz 
gpio_rate_1hz 
gpio_rate_2hz 
gpio_rate_5hz 
gpio_rate_10hz 
gpio_rate_25hz 
gpio_rate_50hz 

Definition at line 910 of file spatial_packets.h.

◆ nmea_fix_behaviour_e

Enumerator
nmea_fix_behaviour_normal 
nmea_fix_behaviour_always_3d 

Definition at line 924 of file spatial_packets.h.

◆ packet_id_e

Enumerator
packet_id_acknowledge 
packet_id_request 
packet_id_boot_mode 
packet_id_device_information 
packet_id_restore_factory_settings 
packet_id_reset 
packet_id_print 
packet_id_file_transfer_request 
packet_id_file_transfer_acknowledge 
packet_id_file_transfer 
packet_id_serial_port_passthrough 
end_system_packets 
packet_id_system_state 
packet_id_unix_time 
packet_id_formatted_time 
packet_id_status 
packet_id_position_standard_deviation 
packet_id_velocity_standard_deviation 
packet_id_euler_orientation_standard_deviation 
packet_id_quaternion_orientation_standard_deviation 
packet_id_raw_sensors 
packet_id_raw_gnss 
packet_id_satellites 
packet_id_satellites_detailed 
packet_id_geodetic_position 
packet_id_ecef_position 
packet_id_utm_position 
packet_id_ned_velocity 
packet_id_body_velocity 
packet_id_acceleration 
packet_id_body_acceleration 
packet_id_euler_orientation 
packet_id_quaternion_orientation 
packet_id_dcm_orientation 
packet_id_angular_velocity 
packet_id_angular_acceleration 
packet_id_external_position_velocity 
packet_id_external_position 
packet_id_external_velocity 
packet_id_external_body_velocity 
packet_id_external_heading 
packet_id_running_time 
packet_id_local_magnetics 
packet_id_odometer_state 
packet_id_external_time 
packet_id_external_depth 
packet_id_geoid_height 
packet_id_rtcm_corrections 
packet_id_external_pitot_pressure 
packet_id_wind 
packet_id_heave 
packet_id_post_processing 
packet_id_raw_satellite_data 
packet_id_raw_satellite_ephemeris 
packet_id_depth 
packet_id_water_profiling 
packet_id_external_usbl 
packet_id_speed_of_sound 
packet_id_lockheed 
packet_id_external_odometer 
packet_id_external_air_data 
packet_id_gnss_receiver_information 
packet_id_raw_dvl_data 
packet_id_north_seeking_status 
end_state_packets 
packet_id_packet_timer_period 
packet_id_packet_periods 
packet_id_baud_rates 
packet_id_bus_configuration 
packet_id_sensor_ranges 
packet_id_installation_alignment 
packet_id_filter_options 
packet_id_filter_trust 
packet_id_gpio_configuration 
packet_id_magnetic_calibration_values 
packet_id_magnetic_calibration_configuration 
packet_id_magnetic_calibration_status 
packet_id_odometer_configuration 
packet_id_zero_alignment 
packet_id_heave_offset 
packet_id_gpio_output_configuration 
packet_id_dual_antenna_configuration 
end_configuration_packets 

Definition at line 45 of file spatial_packets.h.

◆ satellite_frequencies_e

Enumerator
satellite_frequency_unknown 
satellite_frequency_l1_ca 
satellite_frequency_l1_c 
satellite_frequency_l1_p 
satellite_frequency_l1_m 
satellite_frequency_l2_c 
satellite_frequency_l2_p 
satellite_frequency_l2_m 
satellite_frequency_l5 
satellite_frequency_l3 

Definition at line 632 of file spatial_packets.h.

◆ satellite_system_e

Enumerator
satellite_system_unknown 
satellite_system_gps 
satellite_system_glonass 
satellite_system_beidou 
satellite_system_galileo 
satellite_system_sbas 
satellite_system_qzss 
satellite_system_starfire 
satellite_system_omnistar 

Definition at line 439 of file spatial_packets.h.

◆ vehicle_type_e

Enumerator
vehicle_type_unlimited 
vehicle_type_bicycle 
vehicle_type_car 
vehicle_type_hovercraft 
vehicle_type_submarine 
vehicle_type_3d_underwater 
vehicle_type_fixed_wing_plane 
vehicle_type_3d_aircraft 
vehicle_type_human 
vehicle_type_small_boat 
vehicle_type_ship 
vehicle_type_stationary 
vehicle_type_stunt_plane 

Definition at line 804 of file spatial_packets.h.

Function Documentation

◆ decode_acceleration_packet()

int decode_acceleration_packet ( acceleration_packet_t acceleration,
an_packet_t an_packet 
)

◆ decode_acknowledge_packet()

int decode_acknowledge_packet ( acknowledge_packet_t acknowledge_packet,
an_packet_t an_packet 
)

◆ decode_angular_acceleration_packet()

int decode_angular_acceleration_packet ( angular_acceleration_packet_t angular_acceleration_packet,
an_packet_t an_packet 
)

◆ decode_angular_velocity_packet()

int decode_angular_velocity_packet ( angular_velocity_packet_t angular_velocity_packet,
an_packet_t an_packet 
)

◆ decode_baud_rates_packet()

int decode_baud_rates_packet ( baud_rates_packet_t baud_rates_packet,
an_packet_t an_packet 
)

◆ decode_body_acceleration_packet()

int decode_body_acceleration_packet ( body_acceleration_packet_t body_acceleration,
an_packet_t an_packet 
)

◆ decode_body_velocity_packet()

int decode_body_velocity_packet ( body_velocity_packet_t body_velocity_packet,
an_packet_t an_packet 
)

◆ decode_boot_mode_packet()

int decode_boot_mode_packet ( boot_mode_packet_t boot_mode_packet,
an_packet_t an_packet 
)

◆ decode_dcm_orientation_packet()

int decode_dcm_orientation_packet ( dcm_orientation_packet_t dcm_orientation_packet,
an_packet_t an_packet 
)

◆ decode_detailed_satellites_packet()

int decode_detailed_satellites_packet ( detailed_satellites_packet_t detailed_satellites_packet,
an_packet_t an_packet 
)

◆ decode_device_information_packet()

int decode_device_information_packet ( device_information_packet_t device_information_packet,
an_packet_t an_packet 
)

◆ decode_dual_antenna_configuration_packet()

int decode_dual_antenna_configuration_packet ( dual_antenna_configuration_packet_t dual_antenna_configuration_packet,
an_packet_t an_packet 
)

◆ decode_ecef_position_packet()

int decode_ecef_position_packet ( ecef_position_packet_t ecef_position_packet,
an_packet_t an_packet 
)

◆ decode_euler_orientation_packet()

int decode_euler_orientation_packet ( euler_orientation_packet_t euler_orientation_packet,
an_packet_t an_packet 
)

◆ decode_euler_orientation_standard_deviation_packet()

int decode_euler_orientation_standard_deviation_packet ( euler_orientation_standard_deviation_packet_t euler_orientation_standard_deviation,
an_packet_t an_packet 
)

◆ decode_external_air_data_packet()

int decode_external_air_data_packet ( external_air_data_packet_t external_air_data_packet,
an_packet_t an_packet 
)

◆ decode_external_body_velocity_packet()

int decode_external_body_velocity_packet ( external_body_velocity_packet_t external_body_velocity_packet,
an_packet_t an_packet 
)

◆ decode_external_depth_packet()

int decode_external_depth_packet ( external_depth_packet_t external_depth_packet,
an_packet_t an_packet 
)

◆ decode_external_heading_packet()

int decode_external_heading_packet ( external_heading_packet_t external_heading_packet,
an_packet_t an_packet 
)

◆ decode_external_pitot_pressure_packet()

int decode_external_pitot_pressure_packet ( external_pitot_pressure_packet_t external_pitot_pressure_packet,
an_packet_t an_packet 
)

◆ decode_external_position_packet()

int decode_external_position_packet ( external_position_packet_t external_position_packet,
an_packet_t an_packet 
)

◆ decode_external_position_velocity_packet()

int decode_external_position_velocity_packet ( external_position_velocity_packet_t external_position_velocity_packet,
an_packet_t an_packet 
)

◆ decode_external_time_packet()

int decode_external_time_packet ( external_time_packet_t external_time_packet,
an_packet_t an_packet 
)

◆ decode_external_velocity_packet()

int decode_external_velocity_packet ( external_velocity_packet_t external_velocity_packet,
an_packet_t an_packet 
)

◆ decode_file_transfer_acknowledge_packet()

int decode_file_transfer_acknowledge_packet ( file_transfer_acknowledge_packet_t file_transfer_acknowledge_packet,
an_packet_t an_packet 
)

◆ decode_filter_options_packet()

int decode_filter_options_packet ( filter_options_packet_t filter_options_packet,
an_packet_t an_packet 
)

◆ decode_formatted_time_packet()

int decode_formatted_time_packet ( formatted_time_packet_t formatted_time_packet,
an_packet_t an_packet 
)

◆ decode_geodetic_position_packet()

int decode_geodetic_position_packet ( geodetic_position_packet_t geodetic_position_packet,
an_packet_t an_packet 
)

◆ decode_geoid_height_packet()

int decode_geoid_height_packet ( geoid_height_packet_t geoid_height_packet,
an_packet_t an_packet 
)

◆ decode_gnss_information_packet()

int decode_gnss_information_packet ( gnss_receiver_information_packet_t gnss_information_packet,
an_packet_t an_packet 
)

◆ decode_gpio_configuration_packet()

int decode_gpio_configuration_packet ( gpio_configuration_packet_t gpio_configuration_packet,
an_packet_t an_packet 
)

◆ decode_gpio_output_configuration_packet()

int decode_gpio_output_configuration_packet ( gpio_output_configuration_packet_t gpio_output_configuration_packet,
an_packet_t an_packet 
)

◆ decode_heave_offset_packet()

int decode_heave_offset_packet ( heave_offset_packet_t heave_offset_packet,
an_packet_t an_packet 
)

◆ decode_heave_packet()

int decode_heave_packet ( heave_packet_t heave_packet,
an_packet_t an_packet 
)

◆ decode_installation_alignment_packet()

int decode_installation_alignment_packet ( installation_alignment_packet_t installation_alignment_packet,
an_packet_t an_packet 
)

◆ decode_local_magnetics_packet()

int decode_local_magnetics_packet ( local_magnetics_packet_t local_magnetics_packet,
an_packet_t an_packet 
)

◆ decode_ned_velocity_packet()

int decode_ned_velocity_packet ( ned_velocity_packet_t ned_velocity_packet,
an_packet_t an_packet 
)

◆ decode_north_seeking_status_packet()

int decode_north_seeking_status_packet ( north_seeking_status_packet_t north_seeking_status_packet,
an_packet_t an_packet 
)

◆ decode_odometer_configuration_packet()

int decode_odometer_configuration_packet ( odometer_configuration_packet_t odometer_configuration_packet,
an_packet_t an_packet 
)

◆ decode_odometer_packet()

int decode_odometer_packet ( odometer_packet_t external_odometer_packet,
an_packet_t an_packet 
)

◆ decode_odometer_state_packet()

int decode_odometer_state_packet ( odometer_state_packet_t odometer_state_packet,
an_packet_t an_packet 
)

◆ decode_packet_periods_packet()

int decode_packet_periods_packet ( packet_periods_packet_t packet_periods_packet,
an_packet_t an_packet 
)

◆ decode_packet_timer_period_packet()

int decode_packet_timer_period_packet ( packet_timer_period_packet_t packet_timer_period_packet,
an_packet_t an_packet 
)

◆ decode_position_standard_deviation_packet()

int decode_position_standard_deviation_packet ( position_standard_deviation_packet_t position_standard_deviation_packet,
an_packet_t an_packet 
)

◆ decode_quaternion_orientation_packet()

int decode_quaternion_orientation_packet ( quaternion_orientation_packet_t quaternion_orientation_packet,
an_packet_t an_packet 
)

◆ decode_quaternion_orientation_standard_deviation_packet()

int decode_quaternion_orientation_standard_deviation_packet ( quaternion_orientation_standard_deviation_packet_t quaternion_orientation_standard_deviation_packet,
an_packet_t an_packet 
)

◆ decode_raw_gnss_packet()

int decode_raw_gnss_packet ( raw_gnss_packet_t raw_gnss_packet,
an_packet_t an_packet 
)

◆ decode_raw_sensors_packet()

int decode_raw_sensors_packet ( raw_sensors_packet_t raw_sensors_packet,
an_packet_t an_packet 
)

◆ decode_running_time_packet()

int decode_running_time_packet ( running_time_packet_t running_time_packet,
an_packet_t an_packet 
)

◆ decode_satellites_packet()

int decode_satellites_packet ( satellites_packet_t satellites_packet,
an_packet_t an_packet 
)

◆ decode_status_packet()

int decode_status_packet ( status_packet_t status_packet,
an_packet_t an_packet 
)

◆ decode_system_state_packet()

int decode_system_state_packet ( system_state_packet_t system_state_packet,
an_packet_t an_packet 
)

◆ decode_unix_time_packet()

int decode_unix_time_packet ( unix_time_packet_t unix_time_packet,
an_packet_t an_packet 
)

◆ decode_utm_position_packet()

int decode_utm_position_packet ( utm_position_packet_t utm_position_packet,
an_packet_t an_packet 
)

◆ decode_velocity_standard_deviation_packet()

int decode_velocity_standard_deviation_packet ( velocity_standard_deviation_packet_t velocity_standard_deviation_packet,
an_packet_t an_packet 
)

◆ decode_wind_packet()

int decode_wind_packet ( wind_packet_t wind_packet,
an_packet_t an_packet 
)

◆ encode_baud_rates_packet()

an_packet_t* encode_baud_rates_packet ( baud_rates_packet_t baud_rates_packet)

◆ encode_boot_mode_packet()

an_packet_t* encode_boot_mode_packet ( boot_mode_packet_t boot_mode_packet)

◆ encode_dual_antenna_configuration_packet()

an_packet_t* encode_dual_antenna_configuration_packet ( dual_antenna_configuration_packet_t dual_antenna_configuration_packet)

◆ encode_external_air_data_packet()

an_packet_t* encode_external_air_data_packet ( external_air_data_packet_t external_air_data_packet)

◆ encode_external_body_velocity_packet()

an_packet_t* encode_external_body_velocity_packet ( external_body_velocity_packet_t external_body_velocity_packet)

◆ encode_external_depth_packet()

an_packet_t* encode_external_depth_packet ( external_depth_packet_t external_depth_packet)

◆ encode_external_heading_packet()

an_packet_t* encode_external_heading_packet ( external_heading_packet_t external_heading_packet)

◆ encode_external_odometer_packet()

an_packet_t* encode_external_odometer_packet ( odometer_packet_t external_odometer_packet)

◆ encode_external_pitot_pressure_packet()

an_packet_t* encode_external_pitot_pressure_packet ( external_pitot_pressure_packet_t external_pitot_pressure_packet)

◆ encode_external_position_packet()

an_packet_t* encode_external_position_packet ( external_position_packet_t external_position_packet)

◆ encode_external_position_velocity_packet()

an_packet_t* encode_external_position_velocity_packet ( external_position_velocity_packet_t external_position_velocity_packet)

◆ encode_external_time_packet()

an_packet_t* encode_external_time_packet ( external_time_packet_t external_time_packet)

◆ encode_external_velocity_packet()

an_packet_t* encode_external_velocity_packet ( external_velocity_packet_t external_velocity_packet)

◆ encode_filter_options_packet()

an_packet_t* encode_filter_options_packet ( filter_options_packet_t filter_options_packet)

◆ encode_gpio_configuration_packet()

an_packet_t* encode_gpio_configuration_packet ( gpio_configuration_packet_t gpio_configuration_packet)

◆ encode_gpio_output_configuration_packet()

an_packet_t* encode_gpio_output_configuration_packet ( gpio_output_configuration_packet_t gpio_output_configuration_packet)

◆ encode_heave_offset_packet()

an_packet_t* encode_heave_offset_packet ( heave_offset_packet_t heave_offset_packet)

◆ encode_installation_alignment_packet()

an_packet_t* encode_installation_alignment_packet ( installation_alignment_packet_t installation_alignment_packet)

◆ encode_odometer_configuration_packet()

an_packet_t* encode_odometer_configuration_packet ( odometer_configuration_packet_t odometer_configuration_packet)

◆ encode_packet_periods_packet()

an_packet_t* encode_packet_periods_packet ( packet_periods_packet_t packet_periods_packet)

◆ encode_packet_timer_period_packet()

an_packet_t* encode_packet_timer_period_packet ( packet_timer_period_packet_t packet_timer_period_packet)

◆ encode_request_packet()

an_packet_t* encode_request_packet ( uint8_t  requested_packet_id)

◆ encode_reset_packet()

an_packet_t* encode_reset_packet ( )

◆ encode_restore_factory_settings_packet()

an_packet_t* encode_restore_factory_settings_packet ( )

◆ encode_wind_packet()

an_packet_t* encode_wind_packet ( wind_packet_t wind_packet)

◆ encode_zero_alignment_packet()

an_packet_t* encode_zero_alignment_packet ( zero_alignment_packet_t zero_alignment_packet)


kvh_geo_fog_3d_driver
Author(s): Trevor Bostic , Zach LaCelle
autogenerated on Wed Mar 2 2022 00:28:57