mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
Copter: log terrain altitude in CTUN message
This commit is contained in:
parent
25c676c3b4
commit
f45c69e7ad
@ -306,6 +306,7 @@ struct PACKED log_Control_Tuning {
|
|||||||
int32_t baro_alt;
|
int32_t baro_alt;
|
||||||
int16_t desired_sonar_alt;
|
int16_t desired_sonar_alt;
|
||||||
int16_t sonar_alt;
|
int16_t sonar_alt;
|
||||||
|
float terr_alt;
|
||||||
int16_t desired_climb_rate;
|
int16_t desired_climb_rate;
|
||||||
int16_t climb_rate;
|
int16_t climb_rate;
|
||||||
};
|
};
|
||||||
@ -313,6 +314,12 @@ struct PACKED log_Control_Tuning {
|
|||||||
// Write a control tuning packet
|
// Write a control tuning packet
|
||||||
void Copter::Log_Write_Control_Tuning()
|
void Copter::Log_Write_Control_Tuning()
|
||||||
{
|
{
|
||||||
|
// get terrain altitude
|
||||||
|
float terr_alt = 0.0f;
|
||||||
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
|
terrain.height_above_terrain(terr_alt, true);
|
||||||
|
#endif
|
||||||
|
|
||||||
struct log_Control_Tuning pkt = {
|
struct log_Control_Tuning pkt = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_CONTROL_TUNING_MSG),
|
||||||
time_us : AP_HAL::micros64(),
|
time_us : AP_HAL::micros64(),
|
||||||
@ -324,6 +331,7 @@ void Copter::Log_Write_Control_Tuning()
|
|||||||
baro_alt : baro_alt,
|
baro_alt : baro_alt,
|
||||||
desired_sonar_alt : (int16_t)target_sonar_alt,
|
desired_sonar_alt : (int16_t)target_sonar_alt,
|
||||||
sonar_alt : sonar_alt,
|
sonar_alt : sonar_alt,
|
||||||
|
terr_alt : terr_alt,
|
||||||
desired_climb_rate : (int16_t)pos_control.get_vel_target_z(),
|
desired_climb_rate : (int16_t)pos_control.get_vel_target_z(),
|
||||||
climb_rate : climb_rate
|
climb_rate : climb_rate
|
||||||
};
|
};
|
||||||
@ -716,7 +724,7 @@ const struct LogStructure Copter::log_structure[] = {
|
|||||||
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
||||||
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
|
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" },
|
||||||
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
|
||||||
"CTUN", "Qfffffecchh", "TimeUS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" },
|
"CTUN", "Qfffffeccfhh", "TimeUS,ThrIn,ABst,ThrOut,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" },
|
||||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||||
"PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" },
|
"PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" },
|
||||||
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt),
|
||||||
|
Loading…
Reference in New Issue
Block a user