Browse Source

DataFlash: added imu_mask to Log_Write_IMUDT

master
Andrew Tridgell 9 years ago
parent
commit
202eb3af35
  1. 2
      libraries/DataFlash/DataFlash.cpp
  2. 2
      libraries/DataFlash/DataFlash.h
  3. 14
      libraries/DataFlash/LogFile.cpp

2
libraries/DataFlash/DataFlash.cpp

@ -28,7 +28,7 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = { @@ -28,7 +28,7 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
// @Param: _REPLAY
// @DisplayName: Enable logging of information needed for Replay
// @Description: If LOG_REPLAY is set to 1 then the EKF2 state estimator will log detailed information needed for diagnosing problems with the Kalman filter. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost
// @Values:0:Disabled,1:EnabledIMU1,3:EnabledIMU1andIMU2
// @Values:0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_REPLAY", 3, DataFlash_Class, _params.log_replay, 0),

2
libraries/DataFlash/DataFlash.h

@ -108,7 +108,7 @@ public: @@ -108,7 +108,7 @@ public:
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, uint64_t time_us=0);
void Log_Write_RFND(const RangeFinder &rangefinder);
void Log_Write_IMU(const AP_InertialSensor &ins);
void Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t time_us);
void Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t time_us, uint8_t imu_mask);
void Log_Write_Vibration(const AP_InertialSensor &ins);
void Log_Write_RCIN(void);
void Log_Write_RCOUT(void);

14
libraries/DataFlash/LogFile.cpp

@ -932,7 +932,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins) @@ -932,7 +932,7 @@ void DataFlash_Class::Log_Write_IMU(const AP_InertialSensor &ins)
}
// Write an accel/gyro delta time data packet
void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t time_us)
void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t time_us, uint8_t imu_mask)
{
float delta_t = ins.get_delta_time();
float delta_vel_t = ins.get_delta_velocity_dt(0);
@ -954,7 +954,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim @@ -954,7 +954,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim
delta_vel_y : delta_velocity.y,
delta_vel_z : delta_velocity.z
};
WriteBlock(&pkt, sizeof(pkt));
if (imu_mask & 1) {
WriteBlock(&pkt, sizeof(pkt));
}
if ((ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) || !ins.use_gyro(1)) {
return;
}
@ -980,7 +982,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim @@ -980,7 +982,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim
delta_vel_y : delta_velocity.y,
delta_vel_z : delta_velocity.z
};
WriteBlock(&pkt2, sizeof(pkt2));
if (imu_mask & 2) {
WriteBlock(&pkt2, sizeof(pkt2));
}
if ((ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) || !ins.use_gyro(2)) {
return;
@ -1006,7 +1010,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim @@ -1006,7 +1010,9 @@ void DataFlash_Class::Log_Write_IMUDT(const AP_InertialSensor &ins, uint64_t tim
delta_vel_y : delta_velocity.y,
delta_vel_z : delta_velocity.z
};
WriteBlock(&pkt3, sizeof(pkt3));
if (imu_mask & 4) {
WriteBlock(&pkt3, sizeof(pkt3));
}
}
void DataFlash_Class::Log_Write_Vibration(const AP_InertialSensor &ins)

Loading…
Cancel
Save