33 #define DEF_EXCEPTION(name, parent) \ 34 class name : public parent { \ 36 name(const char* msg) : parent(msg) {} \ 94 #if __cplusplus > 199711L 95 #define const constexpr 107 static const double KF_K_2 = 0.0000497506;
112 static const double G = 9.80665;
113 #if __cplusplus > 199711L 163 void openPort(
const char *port_name);
188 void initGyros(
double* bias_x = 0,
double* bias_y = 0,
double* bias_z = 0);
236 void receiveEuler(uint64_t *time,
double *roll,
double *pitch,
double *yaw);
281 int transact(
void *
cmd,
int cmd_len,
void *rep,
int rep_len,
int timeout = 0);
284 int send(
void *cmd,
int cmd_len);
287 int receive(uint8_t
command,
void *rep,
int rep_len,
int timeout = 0, uint64_t* sys_time = NULL);
293 uint64_t
filterTime(uint64_t imu_time, uint64_t sys_time);
int fd
The file descriptor.
static const int TICKS_PER_SEC_GX3
void initGyros(double *bias_x=0, double *bias_y=0, double *bias_z=0)
Initial gyros.
unsigned long long start_time
The time at which the imu was started.
static const int MAX_BYTES_SKIPPED
Maximum bytes allowed to be skipped when seeking a message.
static const int TICKS_PER_SEC_GX2
IMU internal ticks/second.
void openPort(const char *port_name)
Open the port.
void closePort()
Close the port.
int send(void *cmd, int cmd_len)
Send a single packet frmo the IMU.
void receiveDelvelDelang(uint64_t *time, double delvel[3], double delang[3])
Read a message of type "DELVEL_DELANG".
double fixed_offset
Variables used by the kalman computation.
void receiveAccelAngrate(uint64_t *time, double accel[3], double angrate[3])
Read a message of type "ACCEL_ANGRATE".
int transact(void *cmd, int cmd_len, void *rep, int rep_len, int timeout=0)
Send a command to the IMU and wait for a reply.
void initTime(double fix_off)
Initialize timing variables.
bool continuous
Whether continuous mode is enabled.
static const unsigned int KF_NUM_SUM
Number of KF samples to sum over.
void receiveRawAccelAngrate(uint64_t *time, double accel[3], double angrate[3])
Read a message of type "CMD_RAW".
void setFixedOffset(double fix_off)
Set the fixed time offset.
A class for interfacing to the microstrain 3dmgx2 and inertialink IMUs.
cmd
Enumeration of possible IMU commands.
uint32_t wraps
The number of times the imu has wrapped.
void stopContinuous()
Take the device out of continous mode.
void receiveAccelAngrateOrientation(uint64_t *time, double accel[3], double angrate[3], double orientation[9])
Read a message of type "ACCEL_ANGRATE_ORIENTATION".
uint32_t last_ticks
The last number of ticks for computing wraparound.
void receiveEuler(uint64_t *time, double *roll, double *pitch, double *yaw)
Read a message of type "EULER".
uint32_t offset_ticks
The number of ticks the initial offset is off by.
ROSLIB_DECL std::string command(const std::string &cmd)
uint32_t diff_ticks
The different in the number of ticks.
DEF_EXCEPTION(Exception, std::runtime_error)
bool setContinuous(cmd command)
Put the device in continuous mode.
uint64_t extractTime(uint8_t *addr)
Extract time from a pointer into an imu buffer.
int receive(uint8_t command, void *rep, int rep_len, int timeout=0, uint64_t *sys_time=NULL)
Receive a particular message from the IMU.
uint64_t filterTime(uint64_t imu_time, uint64_t sys_time)
Run the filter on the imu time and system times.
id_string
Enumeration of possible identifier strings for the getDeviceIdentifierString command.
double time_est[2]
The estimate of time offset and driftrate.
static const double G
Gravity (m/sec^2)
double toDouble(uint64_t time)
Convert the uint64_t time to a double for numerical computations.
bool is_gx3
Is the IMU a GX3?
uint64_t toUint64_t(double time)
Convert the double time back to a uint64_t.
bool getDeviceIdentifierString(id_string type, char id[17])
Read one of the device identifier strings.
static const double KF_K_2
Second KF term.
static const double KF_K_1
First KF term.
void receiveAccelAngrateMagOrientation(uint64_t *time, double accel[3], double angrate[3], double mag[3], double orientation[9])
Read a message of type "ACCEL_ANGRATE_MAG_ORIENT".
unsigned int counter
A counter used by the filter.
void receiveAccelAngrateMag(uint64_t *time, double accel[3], double angrate[3], double mag[3])
Read a message of type "ACCEL_ANGRATE_MAG".
double P_time_est[2][2]
The covariances on time offset and driftrate.