Go to the documentation of this file.00001
00010
00011 #define UM6_FIRMWARE_REVISION (('U' << 24) | ('M' << 16) | ('2' << 8) | 'B')
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #define CONFIG_ARRAY_SIZE 59
00023 #define DATA_ARRAY_SIZE 48
00024 #define COMMAND_COUNT 10
00025
00026
00027 #define CONFIG_REG_START_ADDRESS 0
00028 #define DATA_REG_START_ADDRESS 85
00029 #define COMMAND_START_ADDRESS 170
00030
00031
00032
00033
00034
00035
00036
00037 #define UM6_COMMUNICATION CONFIG_REG_START_ADDRESS // Stores settings in individual bits
00038 #define UM6_MISC_CONFIG (CONFIG_REG_START_ADDRESS + 1) // Stores settings in individual bits
00039 #define UM6_MAG_REF_X (CONFIG_REG_START_ADDRESS + 2) // Mag reference values are stored as 32-bit IEEE floating point values (these reflect data AFTER scale factors and compensation are applied)
00040 #define UM6_MAG_REF_Y (CONFIG_REG_START_ADDRESS + 3)
00041 #define UM6_MAG_REF_Z (CONFIG_REG_START_ADDRESS + 4)
00042 #define UM6_ACCEL_REF_X (CONFIG_REG_START_ADDRESS + 5) // Accel reference values are stored as 32-bit IEEE floating point values (these reflect data AFTER scale factors and compensation are applied)
00043 #define UM6_ACCEL_REF_Y (CONFIG_REG_START_ADDRESS + 6)
00044 #define UM6_ACCEL_REF_Z (CONFIG_REG_START_ADDRESS + 7)
00045 #define UM6_EKF_MAG_VARIANCE (CONFIG_REG_START_ADDRESS + 8) // Variances are stored as 32-bit IEEE floating point values.
00046 #define UM6_EKF_ACCEL_VARIANCE (CONFIG_REG_START_ADDRESS + 9)
00047 #define UM6_EKF_PROCESS_VARIANCE (CONFIG_REG_START_ADDRESS + 10)
00048 #define UM6_GYRO_BIAS_XY (CONFIG_REG_START_ADDRESS + 11) // Gyro biases are stored as 16-bit signed integers. Bias correction is applied BEFORE scale factors are applied
00049 #define UM6_GYRO_BIAS_Z (CONFIG_REG_START_ADDRESS + 12)
00050 #define UM6_ACCEL_BIAS_XY (CONFIG_REG_START_ADDRESS + 13) // Accel biases are stored as 16-bit signed integers. Bias correction is applied BEFORE scale factors are applied
00051 #define UM6_ACCEL_BIAS_Z (CONFIG_REG_START_ADDRESS + 14)
00052 #define UM6_MAG_BIAS_XY (CONFIG_REG_START_ADDRESS + 15) // Mag biases are stored as 16-bit signed integers. Bias correction is applied BEFORE magnetometer adjustment
00053 #define UM6_MAG_BIAS_Z (CONFIG_REG_START_ADDRESS + 16)
00054 #define UM6_ACCEL_CAL_00 (CONFIG_REG_START_ADDRESS + 17) // The accelerometer alignment matrix is a 3x3 matrix with 32-bit IEEE floating point entries
00055 #define UM6_ACCEL_CAL_01 (CONFIG_REG_START_ADDRESS + 18)
00056 #define UM6_ACCEL_CAL_02 (CONFIG_REG_START_ADDRESS + 19)
00057 #define UM6_ACCEL_CAL_10 (CONFIG_REG_START_ADDRESS + 20)
00058 #define UM6_ACCEL_CAL_11 (CONFIG_REG_START_ADDRESS + 21)
00059 #define UM6_ACCEL_CAL_12 (CONFIG_REG_START_ADDRESS + 22)
00060 #define UM6_ACCEL_CAL_20 (CONFIG_REG_START_ADDRESS + 23)
00061 #define UM6_ACCEL_CAL_21 (CONFIG_REG_START_ADDRESS + 24)
00062 #define UM6_ACCEL_CAL_22 (CONFIG_REG_START_ADDRESS + 25)
00063 #define UM6_GYRO_CAL_00 (CONFIG_REG_START_ADDRESS + 26) // The gyro alignment matrix is a 3x3 matrix with 32-bit IEEE floating point entries
00064 #define UM6_GYRO_CAL_01 (CONFIG_REG_START_ADDRESS + 27)
00065 #define UM6_GYRO_CAL_02 (CONFIG_REG_START_ADDRESS + 28)
00066 #define UM6_GYRO_CAL_10 (CONFIG_REG_START_ADDRESS + 29)
00067 #define UM6_GYRO_CAL_11 (CONFIG_REG_START_ADDRESS + 30)
00068 #define UM6_GYRO_CAL_12 (CONFIG_REG_START_ADDRESS + 31)
00069 #define UM6_GYRO_CAL_20 (CONFIG_REG_START_ADDRESS + 32)
00070 #define UM6_GYRO_CAL_21 (CONFIG_REG_START_ADDRESS + 33)
00071 #define UM6_GYRO_CAL_22 (CONFIG_REG_START_ADDRESS + 34)
00072 #define UM6_MAG_CAL_00 (CONFIG_REG_START_ADDRESS + 35) // The magnetometer calibration matrix is a 3x3 matrix with 32-bit IEEE floating point entries
00073 #define UM6_MAG_CAL_01 (CONFIG_REG_START_ADDRESS + 36)
00074 #define UM6_MAG_CAL_02 (CONFIG_REG_START_ADDRESS + 37)
00075 #define UM6_MAG_CAL_10 (CONFIG_REG_START_ADDRESS + 38)
00076 #define UM6_MAG_CAL_11 (CONFIG_REG_START_ADDRESS + 39)
00077 #define UM6_MAG_CAL_12 (CONFIG_REG_START_ADDRESS + 40)
00078 #define UM6_MAG_CAL_20 (CONFIG_REG_START_ADDRESS + 41)
00079 #define UM6_MAG_CAL_21 (CONFIG_REG_START_ADDRESS + 42)
00080 #define UM6_MAG_CAL_22 (CONFIG_REG_START_ADDRESS + 43)
00081
00082 #define UM6_GYROX_BIAS_0 (CONFIG_REG_START_ADDRESS + 44) // Terms used for gyro temperature compensation. Each item is a floating point number, to be
00083 #define UM6_GYROX_BIAS_1 (CONFIG_REG_START_ADDRESS + 45) // applied to the raw data directly.
00084 #define UM6_GYROX_BIAS_2 (CONFIG_REG_START_ADDRESS + 46)
00085 #define UM6_GYROX_BIAS_3 (CONFIG_REG_START_ADDRESS + 47)
00086 #define UM6_GYROY_BIAS_0 (CONFIG_REG_START_ADDRESS + 48)
00087 #define UM6_GYROY_BIAS_1 (CONFIG_REG_START_ADDRESS + 49)
00088 #define UM6_GYROY_BIAS_2 (CONFIG_REG_START_ADDRESS + 50)
00089 #define UM6_GYROY_BIAS_3 (CONFIG_REG_START_ADDRESS + 51)
00090 #define UM6_GYROZ_BIAS_0 (CONFIG_REG_START_ADDRESS + 52)
00091 #define UM6_GYROZ_BIAS_1 (CONFIG_REG_START_ADDRESS + 53)
00092 #define UM6_GYROZ_BIAS_2 (CONFIG_REG_START_ADDRESS + 54)
00093 #define UM6_GYROZ_BIAS_3 (CONFIG_REG_START_ADDRESS + 55)
00094 #define UM6_GPS_HOME_LAT (CONFIG_REG_START_ADDRESS + 56)
00095 #define UM6_GPS_HOME_LONG (CONFIG_REG_START_ADDRESS + 57)
00096 #define UM6_GPS_HOME_ALTITUDE (CONFIG_REG_START_ADDRESS + 58)
00097
00098
00099
00100
00101 #define UM6_STATUS DATA_REG_START_ADDRESS // Status register defines error codes with individual bits
00102 #define UM6_GYRO_RAW_XY (DATA_REG_START_ADDRESS + 1) // Raw gyro data is stored in 16-bit signed integers
00103 #define UM6_GYRO_RAW_Z (DATA_REG_START_ADDRESS + 2)
00104 #define UM6_ACCEL_RAW_XY (DATA_REG_START_ADDRESS + 3) // Raw accel data is stored in 16-bit signed integers
00105 #define UM6_ACCEL_RAW_Z (DATA_REG_START_ADDRESS + 4)
00106 #define UM6_MAG_RAW_XY (DATA_REG_START_ADDRESS + 5) // Raw mag data is stored in 16-bit signed integers
00107 #define UM6_MAG_RAW_Z (DATA_REG_START_ADDRESS + 6)
00108 #define UM6_GYRO_PROC_XY (DATA_REG_START_ADDRESS + 7) // Processed gyro data has scale factors applied and alignment correction performed. Data is 16-bit signed integer.
00109 #define UM6_GYRO_PROC_Z (DATA_REG_START_ADDRESS + 8)
00110 #define UM6_ACCEL_PROC_XY (DATA_REG_START_ADDRESS + 9) // Processed accel data has scale factors applied and alignment correction performed. Data is 16-bit signed integer.
00111 #define UM6_ACCEL_PROC_Z (DATA_REG_START_ADDRESS + 10)
00112 #define UM6_MAG_PROC_XY (DATA_REG_START_ADDRESS + 11) // Processed mag data has scale factors applied and alignment correction performed. Data is 16-bit signed integer.
00113 #define UM6_MAG_PROC_Z (DATA_REG_START_ADDRESS + 12)
00114 #define UM6_EULER_PHI_THETA (DATA_REG_START_ADDRESS + 13) // Euler angles are 32-bit IEEE floating point
00115 #define UM6_EULER_PSI (DATA_REG_START_ADDRESS + 14)
00116 #define UM6_QUAT_AB (DATA_REG_START_ADDRESS + 15) // Quaternions are 16-bit signed integers.
00117 #define UM6_QUAT_CD (DATA_REG_START_ADDRESS + 16)
00118 #define UM6_ERROR_COV_00 (DATA_REG_START_ADDRESS + 17) // Error covariance is a 4x4 matrix of 32-bit IEEE floating point values
00119 #define UM6_ERROR_COV_01 (DATA_REG_START_ADDRESS + 18)
00120 #define UM6_ERROR_COV_02 (DATA_REG_START_ADDRESS + 19)
00121 #define UM6_ERROR_COV_03 (DATA_REG_START_ADDRESS + 20)
00122 #define UM6_ERROR_COV_10 (DATA_REG_START_ADDRESS + 21)
00123 #define UM6_ERROR_COV_11 (DATA_REG_START_ADDRESS + 22)
00124 #define UM6_ERROR_COV_12 (DATA_REG_START_ADDRESS + 23)
00125 #define UM6_ERROR_COV_13 (DATA_REG_START_ADDRESS + 24)
00126 #define UM6_ERROR_COV_20 (DATA_REG_START_ADDRESS + 25)
00127 #define UM6_ERROR_COV_21 (DATA_REG_START_ADDRESS + 26)
00128 #define UM6_ERROR_COV_22 (DATA_REG_START_ADDRESS + 27)
00129 #define UM6_ERROR_COV_23 (DATA_REG_START_ADDRESS + 28)
00130 #define UM6_ERROR_COV_30 (DATA_REG_START_ADDRESS + 29)
00131 #define UM6_ERROR_COV_31 (DATA_REG_START_ADDRESS + 30)
00132 #define UM6_ERROR_COV_32 (DATA_REG_START_ADDRESS + 31)
00133 #define UM6_ERROR_COV_33 (DATA_REG_START_ADDRESS + 32)
00134 #define UM6_TEMPERATURE (DATA_REG_START_ADDRESS + 33) // Temperature measured by onboard temperature sensors
00135 #define UM6_GPS_LONGITUDE (DATA_REG_START_ADDRESS + 34) // GPS longitude
00136 #define UM6_GPS_LATITUDE (DATA_REG_START_ADDRESS + 35) // GPS latitude
00137 #define UM6_GPS_ALTITUDE (DATA_REG_START_ADDRESS + 36) // GPS altitude
00138 #define UM6_GPS_POSITION_N (DATA_REG_START_ADDRESS + 37) // GPS position (meters north of home position)
00139 #define UM6_GPS_POSITION_E (DATA_REG_START_ADDRESS + 38) // GPS position (meters east of home position)
00140 #define UM6_GPS_POSITION_H (DATA_REG_START_ADDRESS + 39) // GPS position (meters east of home position)
00141 #define UM6_GPS_COURSE_SPEED (DATA_REG_START_ADDRESS + 40) // GPS course over ground in degrees and speed in m/s
00142 #define UM6_GPS_SAT_SUMMARY (DATA_REG_START_ADDRESS + 41) // Summarizes GPS satellite data (mode, satellite count, HDOP, and VDOP)
00143 #define UM6_GPS_SAT_1_2 (DATA_REG_START_ADDRESS + 42) // ID and SNR for satellites being tracked
00144 #define UM6_GPS_SAT_3_4 (DATA_REG_START_ADDRESS + 43) // ID and SNR for satellites being tracked
00145 #define UM6_GPS_SAT_5_6 (DATA_REG_START_ADDRESS + 44) // ID and SNR for satellites being tracked
00146 #define UM6_GPS_SAT_7_8 (DATA_REG_START_ADDRESS + 45) // ID and SNR for satellites being tracked
00147 #define UM6_GPS_SAT_9_10 (DATA_REG_START_ADDRESS + 46) // ID and SNR for satellites being tracked
00148 #define UM6_GPS_SAT_11_12 (DATA_REG_START_ADDRESS + 47) // ID and SNR for satellites being tracked
00149
00150
00151 #define UM6_GPS_MODE_START_BIT 30
00152 #define UM6_GPS_MODE_MASK 0x03 // 2 bits
00153
00154 #define UM6_GPS_SAT_COUNT_START_BIT 26
00155 #define UM6_GPS_SAT_COUNT_MASK 0x0F // 4 bits
00156
00157 #define UM6_GPS_HDOP_START_BIT 16
00158 #define UM6_GPS_HDOP_MASK 0x03FF // 10 bits
00159
00160 #define UM6_GPS_VDOP_START_BIT 6
00161 #define UM6_GPS_VDOP_MASK 0x03FF // 10 bits
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172 #define UM6_GET_FW_VERSION COMMAND_START_ADDRESS // Causes the UM6 to report the firmware revision
00173 #define UM6_FLASH_COMMIT (COMMAND_START_ADDRESS + 1) // Causes the UM6 to write all configuration values to FLASH
00174 #define UM6_ZERO_GYROS (COMMAND_START_ADDRESS + 2) // Causes the UM6 to start a zero gyros command
00175 #define UM6_RESET_EKF (COMMAND_START_ADDRESS + 3) // Causes the UM6 to reset the EKF
00176 #define UM6_GET_DATA (COMMAND_START_ADDRESS + 4) // Causes the UM6 to transmit a data packet containing data from all enabled channels
00177 #define UM6_SET_ACCEL_REF (COMMAND_START_ADDRESS + 5) // Causes the UM6 to set the current measured accel data to the reference vector
00178 #define UM6_SET_MAG_REF (COMMAND_START_ADDRESS + 6) // Causes the UM6 to set the current measured magnetometer data to the reference vector
00179 #define UM6_RESET_TO_FACTORY (COMMAND_START_ADDRESS + 7) // Causes the UM6 to load default factory settings
00180
00181 #define UM6_SAVE_FACTORY (COMMAND_START_ADDRESS + 8) // Causes the UM6 to save the current settings to the factory flash location
00182
00183 #define UM6_SET_HOME_POSITION (COMMAND_START_ADDRESS + 9) // Causes the UM6 to save the current GPS position as the "home" position (used to compute relative position)
00184
00185 #define UM6_USE_CONFIG_ADDRESS 0
00186 #define UM6_USE_FACTORY_ADDRESS 1
00187
00188 #define UM6_BAD_CHECKSUM 253 // Sent if the UM6 receives a packet with a bad checksum
00189 #define UM6_UNKNOWN_ADDRESS 254 // Sent if the UM6 receives a packet with an unknown address
00190 #define UM6_INVALID_BATCH_SIZE 255 // Sent if a requested batch read or write operation would go beyond the bounds of the config or data array
00191
00192
00193
00194 #define UM6_BROADCAST_ENABLED (1 << 30) // Enable serial data transmission
00195 #define UM6_GYROS_RAW_ENABLED (1 << 29) // Enable transmission of raw gyro data
00196 #define UM6_ACCELS_RAW_ENABLED (1 << 28) // Enable transmission of raw accelerometer data
00197 #define UM6_MAG_RAW_ENABLED (1 << 27) // Enable transmission of raw magnetometer data
00198 #define UM6_GYROS_PROC_ENABLED (1 << 26) // Enable transmission of processed gyro data (biases removed, scale factor applied, rotation correction applied)
00199 #define UM6_ACCELS_PROC_ENABLED (1 << 25) // Enable transmission of processed accel data (biases removed, scale factor applied, rotation correction applied)
00200 #define UM6_MAG_PROC_ENABLED (1 << 24) // Enable transmission of processed mag data (biases removed, scale factor applied, rotation correction applied)
00201 #define UM6_QUAT_ENABLED (1 << 23) // Enable transmission of quaternion data
00202 #define UM6_EULER_ENABLED (1 << 22) // Enable transmission of euler angle data
00203 #define UM6_COV_ENABLED (1 << 21) // Enable transmission of state covariance data
00204 #define UM6_TEMPERATURE_ENABLED (1 << 20) // Enable transmission of gyro temperature readings
00205 #define UM6_GPS_POSITION_ENABLED (1 << 19) // Enable transmission of latitude and longitude data
00206 #define UM6_GPS_REL_POSITION_ENABLED (1 << 18) // Enable transmission of computed North and East position (with respect to home position)
00207 #define UM6_GPS_COURSE_SPEED_ENABLED (1 << 17) // Enable transmission of computed GPS course and speed
00208 #define UM6_GPS_SAT_SUMMARY_ENABLED (1 << 16) // Enable transmission of satellite summary data (count, HDOP, VDP, mode)
00209 #define UM6_GPS_SAT_DATA_ENABLED (1 << 15) // Enable transmission of satellite data (ID and SNR of each satellite)
00210
00211 #define UM6_GPS_BAUD_RATE_MASK (0x07)
00212 #define UM6_GPS_BAUD_START_BIT 11
00213
00214 #define UM6_BAUD_RATE_MASK (0x07) // Mask specifying the number of bits used to set the serial baud rate
00215 #define UM6_BAUD_START_BIT 8 // Specifies the start location of the baud rate bits
00216
00217 #define UM6_SERIAL_RATE_MASK (0x000FF) // Mask specifying which bits in this register are used to indicate the broadcast frequency
00218
00219
00220 #define UM6_MAG_UPDATE_ENABLED (1 << 31) // Enable magnetometer-based updates in the EKF
00221 #define UM6_ACCEL_UPDATE_ENABLED (1 << 30) // Enable accelerometer-based updates in the EKF
00222 #define UM6_GYRO_STARTUP_CAL (1 << 29) // Enable automatic gyro calibration on startup
00223 #define UM6_QUAT_ESTIMATE_ENABLED (1 << 28) // Enable quaternion-based state estimation
00224
00225
00226 #define UM6_MAG_INIT_FAILED (1 << 31) // Indicates magnetometer initialization failed
00227 #define UM6_ACCEL_INIT_FAILED (1 << 30) // Indicates accelerometer initialization failed
00228 #define UM6_GYRO_INIT_FAILED (1 << 29) // Indicates gyro initialization failed
00229 #define UM6_GYRO_ST_FAILED_X (1 << 28) // Indicates that the x-axis gyro self test failed
00230 #define UM6_GYRO_ST_FAILED_Y (1 << 27) // Indicates that the y-axis gyro self test failed
00231 #define UM6_GYRO_ST_FAILED_Z (1 << 26) // Indicates that the z-axis gyro self test failed
00232 #define UM6_ACCEL_ST_FAILED_X (1 << 25) // Indicates that the x-axis accel self test failed
00233 #define UM6_ACCEL_ST_FAILED_Y (1 << 24) // Indicates that the y-axis accel self test failed
00234 #define UM6_ACCEL_ST_FAILED_Z (1 << 23) // Indicates that the z-axis accel self test failed
00235 #define UM6_MAG_ST_FAILED_X (1 << 22) // Indicates that the x-axis mag self test failed
00236 #define UM6_MAG_ST_FAILED_Y (1 << 21) // Indicates that the y-axis mag self test failed
00237 #define UM6_MAG_ST_FAILED_Z (1 << 20) // Indicates that the z-axis mag self test failed
00238 #define UM6_I2C_GYRO_BUS_ERROR (1 << 19) // Indicates that there was an i2c bus error while communicating with the rate gyros
00239 #define UM6_I2C_ACCEL_BUS_ERROR (1 << 18) // Indicates that there was an i2c bus error while communicating with the accelerometers
00240 #define UM6_I2C_MAG_BUS_ERROR (1 << 17) // Indicates that there was an i2c bus error while communicating with the magnetometer
00241 #define UM6_EKF_DIVERGENT (1 << 16) // Indicates that the EKF estimate failed and had to be restarted
00242 #define UM6_GYRO_UNRESPONSIVE (1 << 15) // Inidicates that the rate gyros failed to signal new data for longer than expected
00243 #define UM6_ACCEL_UNRESPONSIVE (1 << 14) // Indicates that the accelerometer failed to signal new data for longer than expected
00244 #define UM6_MAG_UNRESPONSIVE (1 << 13) // Indicates that the magnetometer failed to signal new data for longer than expected
00245 #define UM6_FLASH_WRITE_FAILED (1 << 12) // Indicates that a write to flash command failed to complete properly
00246
00247 #define UM6_SELF_TEST_COMPLETE (1 << 0) // Indicates that a self-test was completed
00248
00249
00250