3 #if LOGGING_ENABLED == ENABLED 8 #if AUTOTUNE_ENABLED == ENABLED 39 copter.DataFlash.WriteBlock(&pkt,
sizeof(pkt));
58 copter.DataFlash.WriteBlock(&pkt,
sizeof(pkt));
75 #if OPTFLOW == ENABLED 77 if (!optflow.enabled()) {
80 const Vector2f &flowRate = optflow.flowRate();
81 const Vector2f &bodyRate = optflow.bodyRate();
92 #endif // OPTFLOW == ENABLED 116 float terr_alt = 0.0f;
117 #if AP_TERRAIN_AVAILABLE && AC_TERRAIN 118 if (!terrain.height_above_terrain(terr_alt,
true)) {
130 desired_alt : pos_control->get_alt_target() / 100.0f,
131 inav_alt : inertial_nav.get_altitude() / 100.0f,
145 Vector3f targets = attitude_control->get_att_target_euler_cd();
162 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL 180 #if FRAME_CONFIG != HELI_FRAME 368 if (sensor_health.baro != barometer.healthy()) {
369 sensor_health.baro = barometer.healthy();
393 #if FRAME_CONFIG == HELI_FRAME 395 void Copter::Log_Write_Heli()
422 #if PRECISION_LANDING == ENABLED 424 if (!precland.enabled()) {
430 precland.get_target_position_relative_cm(target_pos_rel);
431 precland.get_target_velocity_relative_cms(target_vel_rel);
444 #endif // PRECISION_LANDING == ENABLED 482 #if AUTOTUNE_ENABLED == ENABLED 484 "ATUN",
"QBBfffffff",
"TimeUS,Axis,TuneStep,Targ,Min,Max,RP,RD,SP,ddt",
"s--ddd---o",
"F--BBB---0" },
486 "ATDE",
"Qff",
"TimeUS,Angle,Rate",
"sdk",
"FBB" },
489 "PTUN",
"QBfHHH",
"TimeUS,Param,TunVal,CtrlIn,TunLo,TunHi",
"s-----",
"F-----" },
492 "OF",
"QBffff",
"TimeUS,Qual,flowX,flowY,bodyX,bodyY",
"s-EEEE",
"F-0000" },
495 "CTUN",
"Qffffffeccfhh",
"TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt",
"s----mmmmmmnn",
"F----00BBBBBB" },
497 "MOTB",
"Qffff",
"TimeUS,LiftMax,BatVolt,BatRes,ThLimit",
"s-vw-",
"F-00-" },
499 "EV",
"QB",
"TimeUS,Id",
"s-",
"F-" },
501 "D16",
"QBh",
"TimeUS,Id,Value",
"s--",
"F--" },
503 "DU16",
"QBH",
"TimeUS,Id,Value",
"s--",
"F--" },
505 "D32",
"QBi",
"TimeUS,Id,Value",
"s--",
"F--" },
507 "DU32",
"QBI",
"TimeUS,Id,Value",
"s--",
"F--" },
509 "DFLT",
"QBf",
"TimeUS,Id,Value",
"s--",
"F--" },
511 "ERR",
"QBB",
"TimeUS,Subsys,ECode",
"s--",
"F--" },
514 "HELI",
"Qff",
"TimeUS,DRRPM,ERRPM",
"s--",
"F--" },
518 "PL",
"QBBffff",
"TimeUS,Heal,TAcq,pX,pY,vX,vY",
"s--ddmm",
"F--00BB" },
521 "GUID",
"QBffffff",
"TimeUS,Type,pX,pY,pZ,vX,vY,vZ",
"s-mmmnnn",
"F-000000" },
542 #else // LOGGING_ENABLED 562 #if FRAME_CONFIG == HELI_FRAME 563 void Copter::Log_Write_Heli() {}
566 #if OPTFLOW == ENABLED 572 #endif // LOGGING_ENABLED #define ERROR_CODE_UNHEALTHY
void Log_Write_MessageF(const char *fmt,...)
void Log_Write_Control_Tuning()
float desired_rotor_speed
void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt)
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds)
void Log_Write_Mode(uint8_t mode, uint8_t reason)
void Log_Write_SIMSTATE(DataFlash_Class *dataflash)
void Log_Write_Rate(const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control)
void WriteBlock(const void *pBuffer, uint16_t size)
#define ERROR_SUBSYSTEM_COMPASS
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f &pos_target, const Vector3f &vel_target)
void Log_Write_Home_And_Origin()
void Log_Write_Vehicle_Startup_Messages()
void Log_Write_Precland()
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
AP_MotorsMatrix motors(400)
void Log_Write_Performance()
void Log_Write_Error(uint8_t sub_system, uint8_t error_code)
void Init(const struct LogStructure *structure, uint8_t num_types)
void Log_Write_Rally(const AP_Rally &rally)
virtual float get_throttle_hover() const
int16_t desired_rangefinder_alt
void Log_Write_POS(AP_AHRS &ahrs)
#define ERROR_SUBSYSTEM_BARO
void Log_Write_Attitude()
void Log_Write_Event(uint8_t id)
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
bool healthy[COMPASS_MAX_INSTANCES]
void Log_Write_AHRS2(AP_AHRS &ahrs)
int16_t target_climb_rate
void WriteCriticalBlock(const void *pBuffer, uint16_t size)
float get_batt_voltage_filt() const
AP_BattMonitor & battery()
DataFlash_Class DataFlash
AP_HAL_MAIN_CALLBACKS & copter
uint8_t primary_sensor(void) const
#define PRECISION_LANDING
#define ERROR_CODE_ERROR_RESOLVED
float get_throttle() const
float get_resistance() const
#define LOG_PACKET_HEADER_INIT(id)
#define DATA_GPS_PRIMARY_CHANGED
float get_throttle_limit() const
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, int16_t control_in, int16_t tune_low, int16_t tune_high)
void Log_Write_Data(uint8_t id, int32_t value)
void Write_DataFlash_Log_Startup_messages()