mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Plane: log the throttle mix for quadplane copter control
This commit is contained in:
parent
fe3e7e8153
commit
88e02c7b35
@ -502,7 +502,7 @@ const struct LogStructure Plane::log_structure[] = {
|
|||||||
{ LOG_STATUS_MSG, sizeof(log_Status),
|
{ LOG_STATUS_MSG, sizeof(log_Status),
|
||||||
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit" },
|
"STAT", "QBfBBBBBB", "TimeUS,isFlying,isFlyProb,Armed,Safety,Crash,Still,Stage,Hit" },
|
||||||
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
||||||
"QTUN", "Qffffehhffff", "TimeUS,AngBst,ThrOut,DAlt,Alt,BarAlt,DCRt,CRt,DVx,DVy,DAx,DAy" },
|
"QTUN", "Qffffhhfffff", "TimeUS,AngBst,ThrOut,DAlt,Alt,DCRt,CRt,DVx,DVy,DAx,DAy,TMix" },
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
|
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
|
||||||
|
@ -2101,13 +2101,13 @@ void QuadPlane::Log_Write_QControl_Tuning()
|
|||||||
throttle_out : motors->get_throttle(),
|
throttle_out : motors->get_throttle(),
|
||||||
desired_alt : pos_control->get_alt_target() / 100.0f,
|
desired_alt : pos_control->get_alt_target() / 100.0f,
|
||||||
inav_alt : inertial_nav.get_altitude() / 100.0f,
|
inav_alt : inertial_nav.get_altitude() / 100.0f,
|
||||||
baro_alt : (int32_t)plane.barometer.get_altitude() * 100,
|
|
||||||
desired_climb_rate : (int16_t)pos_control->get_vel_target_z(),
|
desired_climb_rate : (int16_t)pos_control->get_vel_target_z(),
|
||||||
climb_rate : (int16_t)inertial_nav.get_velocity_z(),
|
climb_rate : (int16_t)inertial_nav.get_velocity_z(),
|
||||||
dvx : desired_velocity.x*0.01f,
|
dvx : desired_velocity.x*0.01f,
|
||||||
dvy : desired_velocity.y*0.01f,
|
dvy : desired_velocity.y*0.01f,
|
||||||
dax : accel_target.x*0.01f,
|
dax : accel_target.x*0.01f,
|
||||||
day : accel_target.y*0.01f,
|
day : accel_target.y*0.01f,
|
||||||
|
throttle_mix : attitude_control->get_throttle_mix(),
|
||||||
};
|
};
|
||||||
plane.DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
plane.DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
@ -96,13 +96,13 @@ public:
|
|||||||
float throttle_out;
|
float throttle_out;
|
||||||
float desired_alt;
|
float desired_alt;
|
||||||
float inav_alt;
|
float inav_alt;
|
||||||
int32_t baro_alt;
|
|
||||||
int16_t desired_climb_rate;
|
int16_t desired_climb_rate;
|
||||||
int16_t climb_rate;
|
int16_t climb_rate;
|
||||||
float dvx;
|
float dvx;
|
||||||
float dvy;
|
float dvy;
|
||||||
float dax;
|
float dax;
|
||||||
float day;
|
float day;
|
||||||
|
float throttle_mix;
|
||||||
};
|
};
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
Loading…
Reference in New Issue
Block a user