Copter: replace NTUN with PSC logging

This commit is contained in:
Randy Mackay 2018-03-01 14:43:13 +09:00
parent 13007e2a07
commit 4a74b1b5e5
4 changed files with 1 additions and 53 deletions

View File

@ -342,7 +342,7 @@ void Copter::ten_hz_logging_loop()
DataFlash.Log_Write_RCOUT();
}
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
Log_Write_Nav_Tuning();
pos_control->write_log();
}
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
DataFlash.Log_Write_Vibration(ins);

View File

@ -783,7 +783,6 @@ private:
// Log.cpp
void Log_Write_Optflow();
void Log_Write_Nav_Tuning();
void Log_Write_Control_Tuning();
void Log_Write_Performance();
void Log_Write_Attitude();

View File

@ -92,53 +92,6 @@ void Copter::Log_Write_Optflow()
#endif // OPTFLOW == ENABLED
}
struct PACKED log_Nav_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
float desired_pos_x;
float desired_pos_y;
float pos_x;
float pos_y;
float desired_vel_x;
float desired_vel_y;
float vel_x;
float vel_y;
float desired_accel_x;
float desired_accel_y;
float accel_x;
float accel_y;
};
// Write an Nav Tuning packet
void Copter::Log_Write_Nav_Tuning()
{
const Vector3f &pos_target = pos_control->get_pos_target();
const Vector3f &vel_target = pos_control->get_vel_target();
const Vector3f &accel_target = pos_control->get_accel_target();
const Vector3f &position = inertial_nav.get_position();
const Vector3f &velocity = inertial_nav.get_velocity();
float accel_x, accel_y;
pos_control->lean_angles_to_accel(accel_x, accel_y);
struct log_Nav_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_NAV_TUNING_MSG),
time_us : AP_HAL::micros64(),
desired_pos_x : pos_target.x,
desired_pos_y : pos_target.y,
pos_x : position.x,
pos_y : position.y,
desired_vel_x : vel_target.x,
desired_vel_y : vel_target.y,
vel_x : velocity.x,
vel_y : velocity.y,
desired_accel_x : accel_target.x,
desired_accel_y : accel_target.y,
accel_x : accel_x,
accel_y : accel_y
};
DataFlash.WriteBlock(&pkt, sizeof(pkt));
}
struct PACKED log_Control_Tuning {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -595,8 +548,6 @@ const struct LogStructure Copter::log_structure[] = {
"PTUN", "QBfHHH", "TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi", "s-----", "F-----" },
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY", "s-EEEE", "F-0000" },
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
"NTUN", "Qffffffffffff", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY", "smmmmnnnnoooo", "FBBBBBBBBBBBB" },
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qffffffeccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt", "s----mmmmmmnn", "F----00BBBBBB" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
@ -647,7 +598,6 @@ void Copter::log_init(void)
#else // LOGGING_ENABLED
void Copter::Log_Write_Nav_Tuning() {}
void Copter::Log_Write_Control_Tuning() {}
void Copter::Log_Write_Performance() {}
void Copter::Log_Write_Attitude(void) {}

View File

@ -309,7 +309,6 @@ enum LoggingParameters {
TYPE_AIRSTART_MSG,
TYPE_GROUNDSTART_MSG,
LOG_CONTROL_TUNING_MSG,
LOG_NAV_TUNING_MSG,
LOG_OPTFLOW_MSG,
LOG_EVENT_MSG,
LOG_ERROR_MSG,