00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef MS_3DMGX2_HH
00023 #define MS_3DMGX2_HH
00024
00025 #include <fstream>
00026 #include <stdexcept>
00027 #include <stdint.h>
00028
00029 namespace microstrain_3dmgx2_imu
00030 {
00031
00033 #define DEF_EXCEPTION(name, parent) \
00034 class name : public parent { \
00035 public: \
00036 name(const char* msg) : parent(msg) {} \
00037 }
00038
00039 DEF_EXCEPTION(Exception, std::runtime_error);
00040 DEF_EXCEPTION(TimeoutException, Exception);
00041 DEF_EXCEPTION(CorruptedDataException, Exception);
00042
00043 #undef DEF_EXCEPTION
00044
00046
00091 class IMU
00092 {
00093
00094 #if __cplusplus > 199711L
00095 #define const constexpr
00096 #endif
00097
00098 static const int TICKS_PER_SEC_GX2 = 19660800;
00099 static const int TICKS_PER_SEC_GX3 = 62500;
00101 static const int MAX_BYTES_SKIPPED = 1000;
00103 static const unsigned int KF_NUM_SUM= 100;
00105 static const double KF_K_1 = 0.00995031;
00107 static const double KF_K_2 = 0.0000497506;
00108
00109 public:
00110
00112 static const double G = 9.80665;
00113 #if __cplusplus > 199711L
00114 #undef const
00115 #endif
00116
00118 enum cmd {
00119 CMD_RAW = 0xC1,
00120 CMD_ACCEL_ANGRATE = 0xC2,
00121 CMD_DELVEL_DELANG = 0xC3,
00122 CMD_CONTINUOUS = 0xC4,
00123 CMD_ORIENT = 0xC5,
00124 CMD_ATT_UPDATE = 0xC6,
00125 CMD_MAG_VEC = 0xC7,
00126 CMD_ACCEL_ANGRATE_ORIENT = 0xC8,
00127 CMD_WRITE_ACCEL_BIAS = 0xC9,
00128 CMD_WRITE_GYRO_BIAS = 0xCA,
00129 CMD_ACCEL_ANGRATE_MAG = 0xCB,
00130 CMD_ACCEL_ANGRATE_MAG_ORIENT = 0xCC,
00131 CMD_CAPTURE_GYRO_BIAS = 0xCD,
00132 CMD_EULER = 0xCE,
00133 CMD_EULER_ANGRATE = 0xCF,
00134 CMD_TEMPERATURES = 0xD1,
00135 CMD_GYROSTAB_ANGRATE_MAG = 0xD2,
00136 CMD_DELVEL_DELANG_MAG = 0xD3,
00137 CMD_DEV_ID_STR = 0xEA,
00138 CMD_STOP_CONTINUOUS = 0xFA
00139 };
00140
00142
00143 enum id_string {
00144 ID_MODEL_NUMBER = 0,
00145 ID_SERIAL_NUMBER = 1,
00146 ID_DEVICE_NAME = 2,
00147 ID_DEVICE_OPTIONS = 3
00148 };
00149
00151 IMU();
00152
00153
00154 ~IMU();
00155
00157
00163 void openPort(const char *port_name);
00164
00166 void closePort();
00167
00169
00175 void initTime(double fix_off);
00176
00178
00188 void initGyros(double* bias_x = 0, double* bias_y = 0, double* bias_z = 0);
00189
00191
00199 bool setContinuous(cmd command);
00200
00202 void stopContinuous();
00203
00205
00210 void receiveAccelAngrate(uint64_t *time, double accel[3], double angrate[3]);
00211
00213
00218 void receiveDelvelDelang(uint64_t *time, double delvel[3], double delang[3]);
00219
00221
00227 void receiveAccelAngrateMag(uint64_t *time, double accel[3], double angrate[3], double mag[3]);
00228
00230
00236 void receiveEuler(uint64_t *time, double *roll, double *pitch, double *yaw);
00237
00239
00245 void receiveAccelAngrateOrientation(uint64_t *time, double accel[3], double angrate[3], double orientation[9]);
00246
00248
00255 void receiveAccelAngrateMagOrientation (uint64_t *time, double accel[3], double angrate[3], double mag[3], double orientation[9]);
00256
00258
00263 void receiveRawAccelAngrate(uint64_t *time, double accel[3], double angrate[3]);
00264
00266
00269 void setFixedOffset(double fix_off) {fixed_offset = fix_off;};
00270
00272
00277 bool getDeviceIdentifierString(id_string type, char id[17]);
00278
00279 private:
00281 int transact(void *cmd, int cmd_len, void *rep, int rep_len, int timeout = 0);
00282
00284 int send(void *cmd, int cmd_len);
00285
00287 int receive(uint8_t command, void *rep, int rep_len, int timeout = 0, uint64_t* sys_time = NULL);
00288
00290 uint64_t extractTime(uint8_t* addr);
00291
00293 uint64_t filterTime(uint64_t imu_time, uint64_t sys_time);
00294
00296 double toDouble(uint64_t time);
00297
00299 uint64_t toUint64_t(double time);
00300
00302 int fd;
00303
00305 uint32_t wraps;
00306
00308 uint32_t offset_ticks;
00309
00311 uint32_t last_ticks;
00312
00314 uint32_t diff_ticks;
00315
00317 unsigned long long start_time;
00318
00320 double time_est[2];
00321
00323 double P_time_est[2][2];
00324
00326 bool continuous;
00327
00329 unsigned int counter;
00330
00332 double fixed_offset, offset, d_offset, sum_meas;
00333
00335 bool is_gx3;
00336
00337 };
00338
00339 }
00340 #endif