|
C MIP-SDK
|
Go to the source code of this file.
Data Structures | |
| struct | _mip_nav_external_gps_update_command |
| struct | _mip_nav_external_heading_update_command |
| struct | _mip_nav_llh_pos |
| struct | _mip_nav_ned_velocity |
| struct | _mip_nav_attitude_quaternion |
| struct | _mip_nav_attitude_dcm |
| struct | _mip_nav_attitude_euler_angles |
| struct | _mip_nav_gyro_bias |
| struct | _mip_nav_accel_bias |
| struct | _mip_nav_llh_pos_uncertainty |
| struct | _mip_nav_ned_vel_uncertainty |
| struct | _mip_nav_euler_attitude_uncertainty |
| struct | _mip_nav_gyro_bias_uncertainty |
| struct | _mip_nav_accel_bias_uncertainty |
| struct | _mip_nav_timestamp |
| struct | _mip_nav_status |
| struct | _mip_nav_acceleration |
| struct | _mip_nav_gravity_vector |
| struct | _mip_nav_angular_rate |
| struct | _mip_nav_quaternion_attitude_uncertainty |
| struct | _mip_nav_wgs84_gravity_mag |
| struct | _mip_nav_heading_update_state |
| struct | _mip_nav_magnetic_model |
Defines | |
| #define | MIP_NAV_COMMAND_SET 0x0D |
| #define | MIP_NAV_DATA_SET 0x82 |
| #define | MIP_NAV_CMD_RESET_FILTER 0x01 |
| #define | MIP_NAV_CMD_SET_INITIAL_ATTITUDE 0x02 |
| #define | MIP_NAV_CMD_SET_INITIAL_HEADING 0x03 |
| #define | MIP_NAV_CMD_SET_INITIAL_HEADING_FROM_AHRS 0x04 |
| #define | MIP_NAV_CMD_VEHICLE_DYNAMICS_MODE 0x10 |
| #define | MIP_NAV_CMD_SENSOR2VEHICLE_TRANSFORMATION 0x11 |
| #define | MIP_NAV_CMD_SENSOR2VEHICLE_OFFSET 0x12 |
| #define | MIP_NAV_CMD_ANTENNA_OFFSET 0x13 |
| #define | MIP_NAV_CMD_BIAS_ESTIMATION_CONTROL 0x14 |
| #define | MIP_NAV_CMD_GPS_SOURCE_CONTROL 0x15 |
| #define | MIP_NAV_CMD_EXTERNAL_GPS_UPDATE 0x16 |
| #define | MIP_NAV_CMD_EXTERNAL_HEADING_UPDATE 0x17 |
| #define | MIP_NAV_CMD_HEADING_UPDATE_CONTROL 0x18 |
| #define | MIP_NAV_CMD_AUTOINIT_CONTROL 0x19 |
| #define | MIP_NAV_CMD_ACCEL_NOISE 0x1A |
| #define | MIP_NAV_CMD_GYRO_NOISE 0x1B |
| #define | MIP_NAV_CMD_ACCEL_BIAS_MODEL 0x1C |
| #define | MIP_NAV_CMD_GYRO_BIAS_MODEL 0x1D |
| #define | MIP_NAV_REPLY_VEHICLE_DYNAMICS_MODE 0x80 |
| #define | MIP_NAV_REPLY_SENSOR2VEHICLE_TRANSFORMATION 0x81 |
| #define | MIP_NAV_REPLY_SENSOR2VEHICLE_OFFSET 0x82 |
| #define | MIP_NAV_REPLY_ANTENNA_OFFSET 0x83 |
| #define | MIP_NAV_REPLY_BIAS_ESTIMATION_CONTROL 0x84 |
| #define | MIP_NAV_REPLY_GPS_SOURCE_CONTROL 0x86 |
| #define | MIP_NAV_REPLY_HEADING_UPDATE_CONTROL 0x87 |
| #define | MIP_NAV_REPLY_AUTOINIT_CONTROL 0x88 |
| #define | MIP_NAV_REPLY_ACCEL_NOISE 0x89 |
| #define | MIP_NAV_REPLY_GYRO_NOISE 0x8A |
| #define | MIP_NAV_REPLY_ACCEL_BIAS_MODEL 0x8B |
| #define | MIP_NAV_REPLY_GYRO_BIAS_MODEL 0x8C |
| #define | MIP_NAV_DATA_LLH_POS 0x01 |
| #define | MIP_NAV_DATA_NED_VEL 0x02 |
| #define | MIP_NAV_DATA_ATT_QUATERNION 0x03 |
| #define | MIP_NAV_DATA_ATT_MATRIX 0x04 |
| #define | MIP_NAV_DATA_ATT_EULER_ANGLES 0x05 |
| #define | MIP_NAV_DATA_GYRO_BIAS 0x06 |
| #define | MIP_NAV_DATA_ACCEL_BIAS 0x07 |
| #define | MIP_NAV_DATA_POS_UNCERTAINTY 0x08 |
| #define | MIP_NAV_DATA_VEL_UNCERTAINTY 0x09 |
| #define | MIP_NAV_DATA_ATT_UNCERTAINTY_EULER 0x0A |
| #define | MIP_NAV_DATA_GYRO_BIAS_UNCERTAINTY 0x0B |
| #define | MIP_NAV_DATA_ACCEL_BIAS_UNCERTAINTY 0x0C |
| #define | MIP_NAV_DATA_ACCELERATION 0x0D |
| #define | MIP_NAV_DATA_ANGULAR_RATE 0x0E |
| #define | MIP_NAV_DATA_WGS84_GRAVITY 0x0F |
| #define | MIP_NAV_DATA_FILTER_STATUS 0x10 |
| #define | MIP_NAV_DATA_FILTER_TIMESTAMP 0x11 |
| #define | MIP_NAV_DATA_ATT_UNCERTAINTY_QUATERNION 0x12 |
| #define | MIP_NAV_DATA_GRAVITY_VECTOR 0x13 |
| #define | MIP_NAV_DATA_HEADING_UPDATE_STATE 0x14 |
| #define | MIP_NAV_DATA_MAGNETIC_MODEL 0x15 |
| #define | IS_NAV_DATA_DESCRIPTOR(DESC) |
| #define | MIP_NAV_BIAS_ESTIMATION_OFF 0x00 |
| #define | MIP_NAV_BIAS_ESTIMATION_ON 0x01 |
| #define | MIP_NAV_DYNAMICS_MODE_PORTABLE 0x01 |
| #define | MIP_NAV_DYNAMICS_MODE_AUTOMOTIVE 0x02 |
| #define | MIP_NAV_DYNAMICS_MODE_AIRBORNE 0x03 |
| #define | MIP_NAV_HEADING_SOURCE_NONE 0x00 |
| #define | MIP_NAV_HEADING_SOURCE_MAGNETOMETER 0x01 |
| #define | MIP_NAV_HEADING_SOURCE_GPS_VELOCITY 0x02 |
| #define | MIP_NAV_HEADING_SOURCE_EXTERNAL 0x03 |
| #define | IS_NAV_HEADING_SOURCE(SOURCE) |
| #define | MIP_NAV_HEADING_UPDATE_TYPE_TRUE_NORTH 0x01 |
| #define | MIP_NAV_HEADING_UPDATE_TYPE_MAGNETIC_NORTH 0x02 |
| #define | IS_NAV_HEADING_UPDATE_TYPE(TYPE) |
| #define | MIP_NAV_EKF_STATE_STARTUP 0x00 |
| #define | MIP_NAV_EKF_STATE_INIT 0x01 |
| #define | MIP_NAV_EKF_STATE_RUN_SOLUTION_VALID 0x02 |
| #define | MIP_NAV_EKF_STATE_RUN_SOLUTION_ERROR 0x03 |
| #define | MIP_NAV_EKF_DYNAMICS_MODE_PORTABLE 0x01 |
| #define | MIP_NAV_EKF_DYNAMICS_MODE_AUTOMOTIVE 0x02 |
| #define | MIP_NAV_EKF_DYNAMICS_MODE_AIRBORNE 0x03 |
| #define | IS_MIP_NAV_EKF_DYNAMICS_MODE(MODE) |
| #define | MIP_NAV_EKF_STATUS_FLAG_INIT_NO_ATTITUDE 0x1000 |
| #define | MIP_NAV_EKF_STATUS_FLAG_INIT_NO_POSITION_VELOCITY 0x2000 |
| #define | MIP_NAV_EKF_STATUS_FLAG_IMU_UNAVAILABLE 0x0001 |
| #define | MIP_NAV_EKF_STATUS_FLAG_GPS_UNAVAILABLE 0x0002 |
| #define | MIP_NAV_EKF_STATUS_FLAG_MATRIX_SINGULARITY 0x0008 |
| #define | MIP_NAV_EKF_STATUS_FLAG_POSITION_COVARIANCE_WARNING 0x0010 |
| #define | MIP_NAV_EKF_STATUS_FLAG_VELOCITY_COVARIANCE_WARNING 0x0020 |
| #define | MIP_NAV_EKF_STATUS_FLAG_ATTITUDE_COVARIANCE_WARNING 0x0040 |
| #define | MIP_NAV_EKF_STATUS_FLAG_NAN_IN_SOLUTION_WARNING 0x0080 |
| #define | MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL_OFF 0x00 |
| #define | MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL_ON 0x01 |
| #define | IS_MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL(CONTROL) |
| #define | NAV_HEADING_UPDATE_STATE_SOURCE_VALID 0x0001 |
| #define | NAV_HEADING_UPDATE_STATE_HEADING_VALID 0x0002 |
| #define | NAV_HEADING_UPDATE_STATE_HEADING_1SIGMA_VALID 0x0004 |
| #define | NAV_HEADING_UPDATE_STATE_PACKET_VALID (NAV_HEADING_UPDATE_STATE_SOURCE_VALID | NAV_HEADING_UPDATE_STATE_HEADING_VALID | NAV_HEADING_UPDATE_STATE_HEADING_1SIGMA_VALID) |
Typedefs | |
|
typedef struct _mip_nav_external_gps_update_command | mip_nav_external_gps_update_command |
|
typedef struct _mip_nav_external_heading_update_command | mip_nav_external_heading_update_command |
| typedef struct _mip_nav_llh_pos | mip_nav_llh_pos |
|
typedef struct _mip_nav_ned_velocity | mip_nav_ned_velocity |
|
typedef struct _mip_nav_attitude_quaternion | mip_nav_attitude_quaternion |
|
typedef struct _mip_nav_attitude_dcm | mip_nav_attitude_dcm |
|
typedef struct _mip_nav_attitude_euler_angles | mip_nav_attitude_euler_angles |
| typedef struct _mip_nav_gyro_bias | mip_nav_gyro_bias |
| typedef struct _mip_nav_accel_bias | mip_nav_accel_bias |
|
typedef struct _mip_nav_llh_pos_uncertainty | mip_nav_llh_pos_uncertainty |
|
typedef struct _mip_nav_ned_vel_uncertainty | mip_nav_ned_vel_uncertainty |
|
typedef struct _mip_nav_euler_attitude_uncertainty | mip_nav_euler_attitude_uncertainty |
|
typedef struct _mip_nav_gyro_bias_uncertainty | mip_nav_gyro_bias_uncertainty |
|
typedef struct _mip_nav_accel_bias_uncertainty | mip_nav_accel_bias_uncertainty |
| typedef struct _mip_nav_timestamp | mip_nav_timestamp |
| typedef struct _mip_nav_status | mip_nav_status |
|
typedef struct _mip_nav_acceleration | mip_nav_acceleration |
|
typedef struct _mip_nav_gravity_vector | mip_nav_gravity_vector |
|
typedef struct _mip_nav_angular_rate | mip_nav_angular_rate |
|
typedef struct _mip_nav_quaternion_attitude_uncertainty | mip_nav_quaternion_attitude_uncertainty |
|
typedef struct _mip_nav_wgs84_gravity_mag | mip_nav_wgs84_gravity_mag |
|
typedef struct _mip_nav_heading_update_state | mip_nav_heading_update_state |
|
typedef struct _mip_nav_magnetic_model | mip_nav_magnetic_model |
Functions | |
| void | mip_nav_llh_pos_byteswap (mip_nav_llh_pos *llh_pos) |
| void | mip_nav_ned_velocity_byteswap (mip_nav_ned_velocity *ned_velocity) |
| void | mip_nav_attitude_quaternion_byteswap (mip_nav_attitude_quaternion *attitude_quaternion) |
| void | mip_nav_attitude_dcm_byteswap (mip_nav_attitude_dcm *attitude_dcm) |
| void | mip_nav_attitude_euler_angles_byteswap (mip_nav_attitude_euler_angles *attitude_euler_angles) |
| void | mip_nav_gyro_bias_byteswap (mip_nav_gyro_bias *gyro_bias) |
| void | mip_nav_accel_bias_byteswap (mip_nav_accel_bias *accel_bias) |
| void | mip_nav_llh_pos_uncertainty_byteswap (mip_nav_llh_pos_uncertainty *llh_pos_uncertainty) |
| void | mip_nav_ned_vel_uncertainty_byteswap (mip_nav_ned_vel_uncertainty *ned_vel_uncertainty) |
| void | mip_nav_euler_attitude_uncertainty_byteswap (mip_nav_euler_attitude_uncertainty *euler_attitude_uncertainty) |
| void | mip_nav_gyro_bias_uncertainty_byteswap (mip_nav_gyro_bias_uncertainty *gyro_bias_uncertainty) |
| void | mip_nav_accel_bias_uncertainty_byteswap (mip_nav_accel_bias_uncertainty *accel_bias_uncertainty) |
| void | mip_nav_timestamp_byteswap (mip_nav_timestamp *timestamp) |
| void | mip_nav_status_byteswap (mip_nav_status *status) |
| void | mip_nav_acceleration_byteswap (mip_nav_acceleration *acceleration) |
| void | mip_nav_gravity_vector_byteswap (mip_nav_gravity_vector *gravity_vector) |
| void | mip_nav_angular_rate_byteswap (mip_nav_angular_rate *angular_rate) |
| void | mip_nav_quaternion_attitude_uncertainty_byteswap (mip_nav_quaternion_attitude_uncertainty *quaternion_attitude_uncertainty) |
| void | mip_nav_wgs84_gravity_mag_byteswap (mip_nav_wgs84_gravity_mag *wgs84_gravity_mag) |
| void | mip_nav_heading_update_state_byteswap (mip_nav_heading_update_state *heading_update_state) |
| void | mip_nav_magnetic_model_byteswap (mip_nav_magnetic_model *magnetic_model) |
| u16 | mip_nav_reset_filter (mip_interface *device_interface) |
| u16 | mip_nav_set_init_attitude (mip_interface *device_interface, float euler_angles[3]) |
| u16 | mip_nav_set_init_heading (mip_interface *device_interface, float heading) |
| u16 | mip_nav_set_init_attitude_from_ahrs (mip_interface *device_interface, float declination) |
| u16 | mip_nav_vehicle_dynamics_mode (mip_interface *device_interface, u8 function_selector, u8 *dynamics_mode) |
| u16 | mip_nav_sensor2vehicle_tranformation (mip_interface *device_interface, u8 function_selector, float euler_angles[3]) |
| u16 | mip_nav_sensor2vehicle_offset (mip_interface *device_interface, u8 function_selector, float offset[3]) |
| u16 | mip_nav_antenna_offset (mip_interface *device_interface, u8 function_selector, float offset[3]) |
| u16 | mip_nav_bias_estimation (mip_interface *device_interface, u8 function_selector, u16 *bias_control) |
| u16 | mip_nav_gps_source (mip_interface *device_interface, u8 function_selector, u8 *gps_source) |
| u16 | mip_nav_external_gps_update (mip_interface *device_interface, mip_nav_external_gps_update_command *command) |
| u16 | mip_nav_external_heading_update (mip_interface *device_interface, mip_nav_external_heading_update_command *command) |
| u16 | mip_nav_heading_source (mip_interface *device_interface, u8 function_selector, u8 *heading_source) |
| u16 | mip_nav_auto_initialization (mip_interface *device_interface, u8 function_selector, u8 *enable) |
| u16 | mip_nav_accel_white_noise (mip_interface *device_interface, u8 function_selector, float noise_1sigma[3]) |
| u16 | mip_nav_gyro_white_noise (mip_interface *device_interface, u8 function_selector, float noise_1sigma[3]) |
| u16 | mip_nav_gyro_bias_model (mip_interface *device_interface, u8 function_selector, float bias_beta[3], float bias_noise_1sigma[3]) |
| #define IS_MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL | ( | CONTROL | ) |
(((CONTROL) == MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL_OFF) || \
((CONTROL) == MIP_NAV_EKF_BIAS_ESTIMATION_CONTROL_ON))
| #define IS_MIP_NAV_EKF_DYNAMICS_MODE | ( | MODE | ) |
(((MODE) == MIP_NAV_EKF_DYNAMICS_MODE_PORTABLE) || \
((MODE) == MIP_NAV_EKF_DYNAMICS_MODE_AUTOMOTIVE) || \
((MODE) == MIP_NAV_EKF_DYNAMICS_MODE_AIRBORNE))
| #define IS_NAV_DATA_DESCRIPTOR | ( | DESC | ) |
(((DESC) == MIP_NAV_DATA_LLH_POS) || \
((DESC) == MIP_NAV_DATA_NED_VEL) || \
((DESC) == MIP_NAV_DATA_ATT_QUATERNION) || \
((DESC) == MIP_NAV_DATA_ATT_MATRIX) || \
((DESC) == MIP_NAV_DATA_ATT_EULER_ANGLES) || \
((DESC) == MIP_NAV_DATA_GYRO_BIAS) || \
((DESC) == MIP_NAV_DATA_ACCEL_BIAS) || \
((DESC) == MIP_NAV_DATA_POS_UNCERTAINTY) || \
((DESC) == MIP_NAV_DATA_VEL_UNCERTAINTY) || \
((DESC) == MIP_NAV_DATA_ATT_UNCERTAINTY_EULER) || \
((DESC) == MIP_NAV_DATA_GYRO_BIAS_UNCERTAINTY) || \
((DESC) == MIP_NAV_DATA_ACCEL_BIAS_UNCERTAINTY) || \
((DESC) == MIP_NAV_DATA_ACCELERATION) || \
((DESC) == MIP_NAV_DATA_ANGULAR_RATE) || \
((DESC) == MIP_NAV_DATA_WGS84_GRAVITY) || \
((DESC) == MIP_NAV_DATA_FILTER_STATUS) || \
((DESC) == MIP_NAV_DATA_FILTER_TIMESTAMP) || \
((DESC) == MIP_NAV_DATA_ATT_UNCERTAINTY_QUATERNION) || \
((DESC) == MIP_NAV_DATA_GRAVITY_VECTOR) || \
((DESC) == MIP_NAV_DATA_HEADING_UPDATE_STATE) || \
((DESC) == MIP_NAV_DATA_MAGNETIC_MODEL))
| #define IS_NAV_HEADING_SOURCE | ( | SOURCE | ) |
(((SOURCE) == MIP_NAV_HEADING_SOURCE_NONE) || \
((SOURCE) == MIP_NAV_HEADING_SOURCE_MAGNETOMETER) || \
((SOURCE) == MIP_NAV_HEADING_SOURCE_GPS_VELOCITY) || \
((SOURCE) == MIP_NAV_HEADING_SOURCE_EXTERNAL))
| #define IS_NAV_HEADING_UPDATE_TYPE | ( | TYPE | ) |
(((TYPE) == MIP_NAV_HEADING_UPDATE_TYPE_TRUE_NORTH) || \
((TYPE) == MIP_NAV_HEADING_UPDATE_TYPE_MAGNETIC_NORTH))
| void mip_nav_accel_bias_byteswap | ( | mip_nav_accel_bias * | accel_bias | ) |
| void mip_nav_accel_bias_uncertainty_byteswap | ( | mip_nav_accel_bias_uncertainty * | accel_bias_uncertainty | ) |
| u16 mip_nav_accel_white_noise | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | noise_1sigma[3] | ||
| ) |
Set or read the filter's accelerometer white noise values.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | noise_1sigma[3] - The accelerometer 1-sigma white noise values in m/(s^2). (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The accelerometer 1-sigma white noise values are ordered [x, y, z] in the
sensor frame in m/(s^2). These values are used as process noise and allow the user to tune
the behavior of the Kalman filter for their particular application.
| void mip_nav_acceleration_byteswap | ( | mip_nav_acceleration * | acceleration | ) |
| void mip_nav_angular_rate_byteswap | ( | mip_nav_angular_rate * | angular_rate | ) |
| u16 mip_nav_antenna_offset | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | offset[3] | ||
| ) |
Set or read the filter's antenna offset settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | offset - The offset of the antenna with-respect-to the sensor in meters. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The offset is [x, y, z] in meters from the sensor to the antenna, expressed in the sensor frame.
| void mip_nav_attitude_dcm_byteswap | ( | mip_nav_attitude_dcm * | attitude_dcm | ) |
| void mip_nav_attitude_euler_angles_byteswap | ( | mip_nav_attitude_euler_angles * | attitude_euler_angles | ) |
| void mip_nav_attitude_quaternion_byteswap | ( | mip_nav_attitude_quaternion * | attitude_quaternion | ) |
| u16 mip_nav_auto_initialization | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| u8 * | enable | ||
| ) |
Set or read the filter's auto-initialization setting.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | u8 | *enable - The auto-initialization setting. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
Please consult the device DCP for valid auto-initialization values.
| u16 mip_nav_bias_estimation | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| u16 * | bias_control | ||
| ) |
Set or read the filter's bias estimation control settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | u16 | *bias_control - The bais control value. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
Please consult the device DCP for valid bias control values
| void mip_nav_euler_attitude_uncertainty_byteswap | ( | mip_nav_euler_attitude_uncertainty * | euler_attitude_uncertainty | ) |
| u16 mip_nav_external_gps_update | ( | mip_interface * | device_interface, |
| mip_nav_external_gps_update_command * | command | ||
| ) |
Provide an external GPS update to the filter.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | mip_nav_external_gps_update_command | *command - The external GPS update command. |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
The device will only accept this command when external GPS is selected
as the GPS source. Please consult the device DCP for how to configure this setting.
| u16 mip_nav_external_heading_update | ( | mip_interface * | device_interface, |
| mip_nav_external_heading_update_command * | command | ||
| ) |
Provide an external heading update to the filter.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | mip_nav_external_heading_update_command | *command - The external heading update command. |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
The device will only accept this command when external heading is selected
as the heading update source. Please consult the device DCP for how to configure this setting.
| u16 mip_nav_gps_source | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| u8 * | gps_source | ||
| ) |
Set or read the filter's GPS source settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | u8 | *gps_source - The source of GPS updates to the filter. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
Please consult the device DCP for valid GPS source values.
| void mip_nav_gravity_vector_byteswap | ( | mip_nav_gravity_vector * | gravity_vector | ) |
| void mip_nav_gyro_bias_byteswap | ( | mip_nav_gyro_bias * | gyro_bias | ) |
| u16 mip_nav_gyro_bias_model | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | bias_beta[3], | ||
| float | bias_noise_1sigma[3] | ||
| ) |
Set or read the filter's gyroscope Guass-Markov bias model values.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | bias_beta[3] - The gyroscope bias model time constants in 1/sec. (used to set or get depending on function_selector) |
| [in,out] | float | bias_noise_1sigma[3] - The gyroscope bias model 1-sigma white noise values in rad/sec. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The gyroscope Gauss-Markov bias model time constant values are ordered [x, y, z] in the
sensor frame in units of 1/sec. The gyro Gauss-Markov bias model 1-sigma white noise values are ordered [x, y, z] in the
sensor frame in units of rad/sec. These values are used as process noise to the gyro bias model and allow the user to tune
the behavior of the Kalman filter for their particular application.
| void mip_nav_gyro_bias_uncertainty_byteswap | ( | mip_nav_gyro_bias_uncertainty * | gyro_bias_uncertainty | ) |
| u16 mip_nav_gyro_white_noise | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | noise_1sigma[3] | ||
| ) |
Set or read the filter's gyroscope white noise values.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | noise_1sigma[3] - The gyroscope 1-sigma white noise values in rad/sec. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The gyroscope 1-sigma white noise values are ordered [x, y, z] in the
sensor frame in rad/sec. These values are used as process noise and allow the user to tune
the behavior of the Kalman filter for their particular application.
| u16 mip_nav_heading_source | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| u8 * | heading_source | ||
| ) |
Set or read the filter's heading update source settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | u8 | *heading_source - The source of heading updates to the filter. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
Please consult the device DCP for valid heading update source values.
| void mip_nav_heading_update_state_byteswap | ( | mip_nav_heading_update_state * | heading_update_state | ) |
| void mip_nav_llh_pos_byteswap | ( | mip_nav_llh_pos * | llh_pos | ) |
| void mip_nav_llh_pos_uncertainty_byteswap | ( | mip_nav_llh_pos_uncertainty * | llh_pos_uncertainty | ) |
| void mip_nav_magnetic_model_byteswap | ( | mip_nav_magnetic_model * | magnetic_model | ) |
| void mip_nav_ned_vel_uncertainty_byteswap | ( | mip_nav_ned_vel_uncertainty * | ned_vel_uncertainty | ) |
| void mip_nav_ned_velocity_byteswap | ( | mip_nav_ned_velocity * | ned_velocity | ) |
| void mip_nav_quaternion_attitude_uncertainty_byteswap | ( | mip_nav_quaternion_attitude_uncertainty * | quaternion_attitude_uncertainty | ) |
| u16 mip_nav_reset_filter | ( | mip_interface * | device_interface | ) |
| u16 mip_nav_sensor2vehicle_offset | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | offset[3] | ||
| ) |
Set or read the filter's sensor to vehicle frame offset settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | offset - The sensor to vehicle frame offset in meters. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The offset is [x, y, z] in meters from the sensor frame to the vehicle frame, expressed in the sensor frame.
| u16 mip_nav_sensor2vehicle_tranformation | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| float | euler_angles[3] | ||
| ) |
Set or read the filter's sensor to vehicle transformation settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | float | euler_angles[3] - The sensor to vehicle transformation expressed as Euler angles in radians. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
The angles are [roll, pitch, yaw] in radians from the sensor frame to the vehicle frame.
| u16 mip_nav_set_init_attitude | ( | mip_interface * | device_interface, |
| float | euler_angles[3] | ||
| ) |
Initialize the Kalman Filter with the provided Euler angles.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | float | euler_angles[3] - The Euler angles in radians. |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Order of angles is [roll, pitch, yaw] in radians.
| u16 mip_nav_set_init_attitude_from_ahrs | ( | mip_interface * | device_interface, |
| float | declination | ||
| ) |
Initialize the Kalman Filter from the AHRS algorithm output, taking into account the magnetic declination angle povided.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | float | declination - The local magnetic declination angle in radians. |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
The output of the internal AHRS orientation algorithm will be used to initialize
the filter, taking into account the user-provided magnetic declination angle.
| u16 mip_nav_set_init_heading | ( | mip_interface * | device_interface, |
| float | heading | ||
| ) |
Initialize the Kalman Filter with the provided true heading angle.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | float | heading - The true heading angle in radians. |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Roll and Pitch will be calculated by the device using the accelerometers.
| void mip_nav_status_byteswap | ( | mip_nav_status * | status | ) |
| void mip_nav_timestamp_byteswap | ( | mip_nav_timestamp * | timestamp | ) |
| u16 mip_nav_vehicle_dynamics_mode | ( | mip_interface * | device_interface, |
| u8 | function_selector, | ||
| u8 * | dynamics_mode | ||
| ) |
Set or read the filter's vehicle dynamics mode settings.
| [in] | mip_interface | *device_interface - The device interface. |
| [in] | u8 | function_selector - Selects which function to perform. |
| [in,out] | u8 | *dynamics_mode - The vehicle dynamics mode. (used to set or get depending on function_selector) |
| MIP_INTERFACE_ERROR | When there is a problem with the command format or the the device communications failed. |
| MIP_INTERFACE_OK | The command was successful. |
Possible function_selector values:
settings may be NULL for the following function_selector values:
Please reference the device DCP for valid dynamics_mode values.
| void mip_nav_wgs84_gravity_mag_byteswap | ( | mip_nav_wgs84_gravity_mag * | wgs84_gravity_mag | ) |
1.7.5.1