Classes | Defines | Enumerations | Functions
orientus_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  boot_mode_packet_t
struct  dcm_orientation_packet_t
struct  device_information_packet_t
struct  euler_orientation_packet_t
struct  euler_orientation_standard_deviation_packet_t
struct  external_heading_packet_t
struct  external_position_packet_t
struct  external_position_velocity_packet_t
struct  external_velocity_packet_t
struct  filter_options_packet_t
struct  gpio_configuration_packet_t
struct  installation_alignment_packet_t
struct  local_magnetics_packet_t
struct  magnetic_calibration_configuration_packet_t
struct  magnetic_calibration_status_packet_t
struct  magnetic_calibration_values_packet_t
struct  packet_period_t
struct  packet_periods_packet_t
struct  packet_timer_period_packet_t
struct  quaternion_orientation_packet_t
struct  quaternion_orientation_standard_deviation_packet_t
struct  raw_sensors_packet_t
struct  running_time_packet_t
struct  sensor_ranges_packet_t
struct  status_packet_t
struct  system_state_packet_t
struct  unix_time_packet_t
struct  zero_alignment_packet_t

Defines

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

Enumerations

enum  accelerometer_range_e { accelerometer_range_2g, accelerometer_range_4g, accelerometer_range_16g }
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  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
}
enum  gpio_index_e {
  gpio1, gpio2, gpio3, gpio4,
  gpio5, gpio6
}
enum  gyroscope_range_e { gyroscope_range_250dps, gyroscope_range_500dps, gyroscope_range_2000dps }
enum  magnetic_calibration_action_e { magnetic_calibration_action_cancel, magnetic_calibration_action_stabilise, magnetic_calibration_action_start_2d, magnetic_calibration_action_start_3d }
enum  magnetic_calibration_status_e {
  magnetic_calibration_status_not_completed, magnetic_calibration_status_completed_2d, magnetic_calibration_status_completed_3d, magnetic_calibration_status_completed_user,
  magnetic_calibration_status_stabilizing, magnetic_calibration_status_in_progress_2d, magnetic_calibration_status_in_progress_3d, magnetic_calibration_status_error_excessive_roll,
  magnetic_calibration_status_error_excessive_pitch, magnetic_calibration_status_error_overrange_event, magnetic_calibration_status_error_timeout, magnetic_calibration_status_error_system
}
enum  magnetometer_range_e { magnetometer_range_2g, magnetometer_range_4g, magnetometer_range_8g }
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, 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_estimation, packet_id_heave, 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_advanced_parameters, 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, end_configuration_packets
}
enum  vehicle_type_e {
  vehicle_type_unconstrained, vehicle_type_motorcycle, 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
}

Functions

int decode_acceleration_packet (acceleration_packet_t *acceleration_packet, 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_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_device_information_packet (device_information_packet_t *device_information_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_heading_packet (external_heading_packet_t *external_heading_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_velocity_packet (external_velocity_packet_t *external_velocity_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_gpio_configuration_packet (gpio_configuration_packet_t *gpio_configuration_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_magnetic_calibration_status_packet (magnetic_calibration_status_packet_t *magnetic_calibration_status_packet, an_packet_t *an_packet)
int decode_magnetic_calibration_values_packet (magnetic_calibration_values_packet_t *magnetic_calibration_values_packet, an_packet_t *an_packet)
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_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_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_sensor_ranges_packet (sensor_ranges_packet_t *sensor_ranges_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)
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_external_heading_packet (external_heading_packet_t *external_heading_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_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_installation_alignment_packet (installation_alignment_packet_t *installation_alignment_packet)
an_packet_tencode_magnetic_calibration_configuration_packet (magnetic_calibration_configuration_packet_t *magnetic_calibration_configuration_packet)
an_packet_tencode_magnetic_calibration_values_packet (magnetic_calibration_values_packet_t *magnetic_calibration_values_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_sensor_ranges_packet (sensor_ranges_packet_t *sensor_ranges_packet)
an_packet_tencode_zero_alignment_packet (zero_alignment_packet_t *zero_alignment_packet)

Define Documentation

#define MAXIMUM_PACKET_PERIODS   50

Definition at line 34 of file orientus_packets.h.

#define START_CONFIGURATION_PACKETS   180

Definition at line 38 of file orientus_packets.h.

#define START_STATE_PACKETS   20

Definition at line 37 of file orientus_packets.h.

#define START_SYSTEM_PACKETS   0

Definition at line 36 of file orientus_packets.h.


Enumeration Type Documentation

Enumerator:
accelerometer_range_2g 
accelerometer_range_4g 
accelerometer_range_16g 

Definition at line 379 of file orientus_packets.h.

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 115 of file orientus_packets.h.

Enumerator:
boot_mode_bootloader 
boot_mode_main_program 

Definition at line 133 of file orientus_packets.h.

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 

Definition at line 435 of file orientus_packets.h.

Enumerator:
gpio1 
gpio2 
gpio3 
gpio4 
gpio5 
gpio6 

Definition at line 468 of file orientus_packets.h.

Enumerator:
gyroscope_range_250dps 
gyroscope_range_500dps 
gyroscope_range_2000dps 

Definition at line 386 of file orientus_packets.h.

Enumerator:
magnetic_calibration_action_cancel 
magnetic_calibration_action_stabilise 
magnetic_calibration_action_start_2d 
magnetic_calibration_action_start_3d 

Definition at line 491 of file orientus_packets.h.

Enumerator:
magnetic_calibration_status_not_completed 
magnetic_calibration_status_completed_2d 
magnetic_calibration_status_completed_3d 
magnetic_calibration_status_completed_user 
magnetic_calibration_status_stabilizing 
magnetic_calibration_status_in_progress_2d 
magnetic_calibration_status_in_progress_3d 
magnetic_calibration_status_error_excessive_roll 
magnetic_calibration_status_error_excessive_pitch 
magnetic_calibration_status_error_overrange_event 
magnetic_calibration_status_error_timeout 
magnetic_calibration_status_error_system 

Definition at line 504 of file orientus_packets.h.

Enumerator:
magnetometer_range_2g 
magnetometer_range_4g 
magnetometer_range_8g 

Definition at line 393 of file orientus_packets.h.

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 
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_estimation 
packet_id_heave 
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_advanced_parameters 
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 
end_configuration_packets 

Definition at line 40 of file orientus_packets.h.

Enumerator:
vehicle_type_unconstrained 
vehicle_type_motorcycle 
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 

Definition at line 414 of file orientus_packets.h.


Function Documentation

int decode_acceleration_packet ( acceleration_packet_t acceleration_packet,
an_packet_t an_packet 
)

Definition at line 619 of file orientus_packets.c.

int decode_acknowledge_packet ( acknowledge_packet_t acknowledge_packet,
an_packet_t an_packet 
)

Definition at line 67 of file orientus_packets.c.

int decode_angular_acceleration_packet ( angular_acceleration_packet_t angular_acceleration_packet,
an_packet_t an_packet 
)

Definition at line 251 of file orientus_packets.c.

int decode_angular_velocity_packet ( angular_velocity_packet_t angular_velocity_packet,
an_packet_t an_packet 
)

Definition at line 241 of file orientus_packets.c.

int decode_baud_rates_packet ( baud_rates_packet_t baud_rates_packet,
an_packet_t an_packet 
)

Definition at line 442 of file orientus_packets.c.

int decode_boot_mode_packet ( boot_mode_packet_t boot_mode_packet,
an_packet_t an_packet 
)

Definition at line 86 of file orientus_packets.c.

int decode_dcm_orientation_packet ( dcm_orientation_packet_t dcm_orientation_packet,
an_packet_t an_packet 
)

Definition at line 231 of file orientus_packets.c.

int decode_device_information_packet ( device_information_packet_t device_information_packet,
an_packet_t an_packet 
)

Definition at line 106 of file orientus_packets.c.

int decode_euler_orientation_packet ( euler_orientation_packet_t euler_orientation_packet,
an_packet_t an_packet 
)

Definition at line 211 of file orientus_packets.c.

Definition at line 178 of file orientus_packets.c.

int decode_external_heading_packet ( external_heading_packet_t external_heading_packet,
an_packet_t an_packet 
)

Definition at line 331 of file orientus_packets.c.

int decode_external_position_packet ( external_position_packet_t external_position_packet,
an_packet_t an_packet 
)

Definition at line 287 of file orientus_packets.c.

int decode_external_position_velocity_packet ( external_position_velocity_packet_t external_position_velocity_packet,
an_packet_t an_packet 
)

Definition at line 261 of file orientus_packets.c.

int decode_external_velocity_packet ( external_velocity_packet_t external_velocity_packet,
an_packet_t an_packet 
)

Definition at line 309 of file orientus_packets.c.

int decode_filter_options_packet ( filter_options_packet_t filter_options_packet,
an_packet_t an_packet 
)

Definition at line 512 of file orientus_packets.c.

int decode_gpio_configuration_packet ( gpio_configuration_packet_t gpio_configuration_packet,
an_packet_t an_packet 
)

Definition at line 539 of file orientus_packets.c.

int decode_installation_alignment_packet ( installation_alignment_packet_t installation_alignment_packet,
an_packet_t an_packet 
)

Definition at line 489 of file orientus_packets.c.

int decode_local_magnetics_packet ( local_magnetics_packet_t local_magnetics_packet,
an_packet_t an_packet 
)

Definition at line 364 of file orientus_packets.c.

int decode_magnetic_calibration_status_packet ( magnetic_calibration_status_packet_t magnetic_calibration_status_packet,
an_packet_t an_packet 
)

Definition at line 594 of file orientus_packets.c.

int decode_magnetic_calibration_values_packet ( magnetic_calibration_values_packet_t magnetic_calibration_values_packet,
an_packet_t an_packet 
)

Definition at line 560 of file orientus_packets.c.

int decode_packet_periods_packet ( packet_periods_packet_t packet_periods_packet,
an_packet_t an_packet 
)

Definition at line 398 of file orientus_packets.c.

int decode_packet_timer_period_packet ( packet_timer_period_packet_t packet_timer_period_packet,
an_packet_t an_packet 
)

Definition at line 374 of file orientus_packets.c.

int decode_quaternion_orientation_packet ( quaternion_orientation_packet_t quaternion_orientation_packet,
an_packet_t an_packet 
)

Definition at line 221 of file orientus_packets.c.

int decode_quaternion_orientation_standard_deviation_packet ( quaternion_orientation_standard_deviation_packet_t quaternion_orientation_standard_deviation_packet,
an_packet_t an_packet 
)

Definition at line 188 of file orientus_packets.c.

int decode_raw_sensors_packet ( raw_sensors_packet_t raw_sensors_packet,
an_packet_t an_packet 
)

Definition at line 198 of file orientus_packets.c.

int decode_running_time_packet ( running_time_packet_t running_time_packet,
an_packet_t an_packet 
)

Definition at line 353 of file orientus_packets.c.

int decode_sensor_ranges_packet ( sensor_ranges_packet_t sensor_ranges_packet,
an_packet_t an_packet 
)

Definition at line 469 of file orientus_packets.c.

int decode_status_packet ( status_packet_t status_packet,
an_packet_t an_packet 
)

Definition at line 167 of file orientus_packets.c.

int decode_system_state_packet ( system_state_packet_t system_state_packet,
an_packet_t an_packet 
)

Definition at line 141 of file orientus_packets.c.

int decode_unix_time_packet ( unix_time_packet_t unix_time_packet,
an_packet_t an_packet 
)

Definition at line 156 of file orientus_packets.c.

Definition at line 455 of file orientus_packets.c.

Definition at line 96 of file orientus_packets.c.

Definition at line 342 of file orientus_packets.c.

Definition at line 298 of file orientus_packets.c.

Definition at line 274 of file orientus_packets.c.

Definition at line 320 of file orientus_packets.c.

Definition at line 525 of file orientus_packets.c.

Definition at line 549 of file orientus_packets.c.

Definition at line 500 of file orientus_packets.c.

Definition at line 584 of file orientus_packets.c.

Definition at line 572 of file orientus_packets.c.

Definition at line 420 of file orientus_packets.c.

Definition at line 386 of file orientus_packets.c.

an_packet_t* encode_request_packet ( uint8_t  requested_packet_id)

Definition at line 79 of file orientus_packets.c.

Definition at line 130 of file orientus_packets.c.

Definition at line 119 of file orientus_packets.c.

Definition at line 479 of file orientus_packets.c.

Definition at line 606 of file orientus_packets.c.



orientus_sdk_c
Author(s): Advanced Navigation, Nick Otero
autogenerated on Wed Aug 26 2015 15:12:17