mirror of https://github.com/ArduPilot/ardupilot
fixed deltat in quaternion
This commit is contained in:
parent
353f9e613f
commit
4a277f9871
|
@ -242,12 +242,15 @@ void AP_Quaternion::update_MARG(float deltat, Vector3f &gyro, Vector3f &accel, V
|
||||||
|
|
||||||
|
|
||||||
// Function to compute one quaternion iteration
|
// Function to compute one quaternion iteration
|
||||||
void AP_Quaternion::update(float deltat)
|
void AP_Quaternion::update(void)
|
||||||
{
|
{
|
||||||
Vector3f gyro, accel;
|
Vector3f gyro, accel;
|
||||||
|
float deltat;
|
||||||
|
|
||||||
_imu->update();
|
_imu->update();
|
||||||
|
|
||||||
|
delta_t = _imu->get_delta_time();
|
||||||
|
|
||||||
// get current IMU state
|
// get current IMU state
|
||||||
gyro = _imu->get_gyro();
|
gyro = _imu->get_gyro();
|
||||||
gyro.x = -gyro.x;
|
gyro.x = -gyro.x;
|
||||||
|
|
|
@ -43,7 +43,7 @@ public:
|
||||||
void set_compass(Compass *compass);
|
void set_compass(Compass *compass);
|
||||||
|
|
||||||
// Methods
|
// Methods
|
||||||
void update(float deltat);
|
void update(void);
|
||||||
|
|
||||||
// Euler angles (radians)
|
// Euler angles (radians)
|
||||||
float roll;
|
float roll;
|
||||||
|
|
|
@ -111,7 +111,6 @@ void loop(void)
|
||||||
static uint16_t counter;
|
static uint16_t counter;
|
||||||
static uint32_t last_t, last_print, last_compass;
|
static uint32_t last_t, last_print, last_compass;
|
||||||
uint32_t now = micros();
|
uint32_t now = micros();
|
||||||
float deltat;
|
|
||||||
static uint32_t compass_reads;
|
static uint32_t compass_reads;
|
||||||
static uint32_t compass_time;
|
static uint32_t compass_time;
|
||||||
|
|
||||||
|
@ -119,7 +118,6 @@ void loop(void)
|
||||||
last_t = now;
|
last_t = now;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
deltat = (now - last_t) * 1.0e-6;
|
|
||||||
last_t = now;
|
last_t = now;
|
||||||
|
|
||||||
if (now - last_compass > 100*1000UL) {
|
if (now - last_compass > 100*1000UL) {
|
||||||
|
@ -128,7 +126,7 @@ void loop(void)
|
||||||
last_compass = now;
|
last_compass = now;
|
||||||
}
|
}
|
||||||
|
|
||||||
quaternion.update(deltat);
|
quaternion.update();
|
||||||
counter++;
|
counter++;
|
||||||
|
|
||||||
if (now - last_print >= 0.5e6) {
|
if (now - last_print >= 0.5e6) {
|
||||||
|
|
Loading…
Reference in New Issue