| MIP_SDK
    v4.0.0
    MicroStrain Communications Library for embedded systems | 
Sets the sensor-to-vehicle frame transformation using Yaw, Pitch, and Roll Euler angles. More...
| Classes | |
| struct | mip::commands_3dm::Sensor2VehicleTransformEuler | 
| Functions | |
| TypedResult< Sensor2VehicleTransformEuler > | mip::commands_3dm::writeSensor2VehicleTransformEuler (C::mip_interface &device, float roll, float pitch, float yaw) | 
| TypedResult< Sensor2VehicleTransformEuler > | mip::commands_3dm::readSensor2VehicleTransformEuler (C::mip_interface &device, float *rollOut, float *pitchOut, float *yawOut) | 
| TypedResult< Sensor2VehicleTransformEuler > | mip::commands_3dm::saveSensor2VehicleTransformEuler (C::mip_interface &device) | 
| TypedResult< Sensor2VehicleTransformEuler > | mip::commands_3dm::loadSensor2VehicleTransformEuler (C::mip_interface &device) | 
| TypedResult< Sensor2VehicleTransformEuler > | mip::commands_3dm::defaultSensor2VehicleTransformEuler (C::mip_interface &device) | 
These are the Yaw, Pitch, and Roll mounting angles of the sensor with respect to vehicle frame of reference, and describe the transformation of vectors from the sensor body frame to the vehicle frame.
Note: This is the transformation, the inverse of the rotation defined in our legacy products.
The transformation may be stored in the device as a matrix or quaternion. When Euler angles are read back from the device, they may not be exactly equal to the Euler angles used to set the transformation, but they are functionally equivalent, such that they result in the same transformation.
 
 This transformation to the vehicle frame will be applied to the following output quantities:
 IMU:
 Scaled Acceleration
 Scaled Gyro
 Scaled Magnetometer
 Delta Theta
 Delta Velocity
 Complementary Filter Orientation
 
 Estimation Filter:
 Estimated Orientation, Quaternion
 Estimated Orientation, Matrix
 Estimated Orientation, Euler Angles
 Estimated Linear Acceleration
 Estimated Angular Rate
 Estimated Gravity Vector
 
 Changing this setting will force all low-pass filters, the complementary filter, and the estimation filter to reset. 
| TypedResult< Sensor2VehicleTransformEuler > mip::commands_3dm::writeSensor2VehicleTransformEuler | ( | C::mip_interface & | device, | 
| float | roll, | ||
| float | pitch, | ||
| float | yaw | ||
| ) | 
| TypedResult< Sensor2VehicleTransformEuler > mip::commands_3dm::readSensor2VehicleTransformEuler | ( | C::mip_interface & | device, | 
| float * | rollOut, | ||
| float * | pitchOut, | ||
| float * | yawOut | ||
| ) | 
| TypedResult< Sensor2VehicleTransformEuler > mip::commands_3dm::saveSensor2VehicleTransformEuler | ( | C::mip_interface & | device | ) | 
| TypedResult< Sensor2VehicleTransformEuler > mip::commands_3dm::loadSensor2VehicleTransformEuler | ( | C::mip_interface & | device | ) | 
| TypedResult< Sensor2VehicleTransformEuler > mip::commands_3dm::defaultSensor2VehicleTransformEuler | ( | C::mip_interface & | device | ) | 
 1.8.17
 1.8.17