ArduPlane: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:09 +10:00 committed by Andrew Tridgell
parent 7377b3f8f2
commit 6ee5ab41fd
18 changed files with 70 additions and 38 deletions

View File

@ -397,7 +397,9 @@ void AP_Arming_Plane::update_soft_armed()
#endif
hal.util->set_soft_armed(_armed);
#if HAL_LOGGING_ENABLED
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());
#endif
// update delay_arming oneshot
if (delay_arming &&

View File

@ -104,11 +104,15 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
#if AP_CAMERA_ENABLED
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108),
#endif // CAMERA == ENABLED
#if HAL_LOGGING_ENABLED
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111),
#endif
SCHED_TASK(compass_save, 0.1, 200, 114),
#if HAL_LOGGING_ENABLED
SCHED_TASK(Log_Write_FullRate, 400, 300, 117),
SCHED_TASK(update_logging10, 10, 300, 120),
SCHED_TASK(update_logging25, 25, 300, 123),
#endif
#if HAL_SOARING_ENABLED
SCHED_TASK(update_soaring, 50, 400, 126),
#endif
@ -117,7 +121,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_Terrain, &plane.terrain, update, 10, 200, 132),
#endif // AP_TERRAIN_AVAILABLE
SCHED_TASK(update_is_flying_5Hz, 5, 100, 135),
#if LOGGING_ENABLED == ENABLED
#if HAL_LOGGING_ENABLED
SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400, 138),
#endif
SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50, 141),
@ -161,9 +165,11 @@ void Plane::ahrs_update()
ahrs.update();
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_IMU)) {
AP::ins().Write_IMU();
}
#endif
// calculate a scaled roll limit based on current pitch
roll_limit_cd = aparm.roll_limit_cd;
@ -194,9 +200,11 @@ void Plane::ahrs_update()
quadplane.inertial_nav.update();
#endif
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
ahrs.write_video_stabilisation();
}
#endif
}
/*
@ -234,6 +242,7 @@ void Plane::update_compass(void)
compass.read();
}
#if HAL_LOGGING_ENABLED
/*
do 10Hz logging
*/
@ -286,7 +295,7 @@ void Plane::update_logging25(void)
if (should_log(MASK_LOG_IMU))
AP::ins().Write_Vibration();
}
#endif // HAL_LOGGING_ENABLED
/*
check for AFS failsafe check
@ -333,7 +342,7 @@ void Plane::one_second_loop()
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
#if AP_TERRAIN_AVAILABLE
#if AP_TERRAIN_AVAILABLE && HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_GPS)) {
terrain.log_terrain_data();
}
@ -528,7 +537,9 @@ void Plane::set_flight_stage(AP_FixedWing::FlightStage fs)
}
flight_stage = fs;
#if HAL_LOGGING_ENABLED
Log_Write_Status();
#endif
}
void Plane::update_alt()

View File

@ -1230,7 +1230,11 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_RADIO:
case MAVLINK_MSG_ID_RADIO_STATUS:
{
#if HAL_LOGGING_ENABLED
handle_radio_status(msg, plane.should_log(MASK_LOG_PM));
#else
handle_radio_status(msg, false);
#endif
break;
}

View File

@ -48,7 +48,7 @@ protected:
private:
void send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);
void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);
void handleMessage(const mavlink_message_t &msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;

View File

@ -1,6 +1,6 @@
#include "Plane.h"
#if LOGGING_ENABLED == ENABLED
#if HAL_LOGGING_ENABLED
// Write an attitude packet
void Plane::Log_Write_Attitude(void)
@ -500,18 +500,4 @@ void Plane::log_init(void)
logger.Init(log_structure, ARRAY_SIZE(log_structure));
}
#else // LOGGING_ENABLED
void Plane::Log_Write_Attitude(void) {}
void Plane::Log_Write_Fast(void) {}
void Plane::Log_Write_Control_Tuning() {}
void Plane::Log_Write_OFG_Guided() {}
void Plane::Log_Write_Nav_Tuning() {}
void Plane::Log_Write_Status() {}
void Plane::Log_Write_Guided(void) {}
void Plane::Log_Write_RC(void) {}
void Plane::Log_Write_Vehicle_Startup_Messages() {}
void Plane::log_init(void) {}
#endif // LOGGING_ENABLED
#endif // HAL_LOGGING_ENABLED

View File

@ -909,9 +909,11 @@ const AP_Param::Info Plane::var_info[] = {
GOBJECT(camera_mount, "MNT", AP_Mount),
#endif
#if HAL_LOGGING_ENABLED
// @Group: LOG
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT(logger, "LOG", AP_Logger),
#endif
// @Group: BATT
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp

View File

@ -24,7 +24,9 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Plane class
*/
Plane::Plane(void)
#if HAL_LOGGING_ENABLED
: logger(g.log_bitmask)
#endif
{
// C++11 doesn't allow in-class initialisation of bitfields
auto_state.takeoff_complete = true;

View File

@ -193,7 +193,9 @@ private:
RC_Channel *channel_flap;
RC_Channel *channel_airbrake;
#if HAL_LOGGING_ENABLED
AP_Logger logger;
#endif
// scaled roll limit based on pitch
int32_t roll_limit_cd;

View File

@ -12,10 +12,12 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
plane.target_altitude.terrain_following_pending = false;
#endif
#if HAL_LOGGING_ENABLED
// log when new commands start
if (should_log(MASK_LOG_CMD)) {
logger.Write_Mission_Cmd(mission, cmd);
}
#endif
// special handling for nav vs non-nav commands
if (AP_Mission::is_nav_cmd(cmd)) {
@ -359,7 +361,9 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
setup_glide_slope();
setup_turn_angle();
#if HAL_LOGGING_ENABLED
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
#endif
}
Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const

View File

@ -186,10 +186,6 @@
// Logging control
//
#ifndef LOGGING_ENABLED
# define LOGGING_ENABLED ENABLED
#endif
#define DEFAULT_LOG_BITMASK 0xffff

View File

@ -74,7 +74,7 @@ void Plane::ekf_check()
// limit count from climbing too high
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
ekf_check_state.bad_variance = true;
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE);
// send message to gcs
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance");
@ -91,7 +91,7 @@ void Plane::ekf_check()
// if compass is flagged as bad and the counter reaches zero then clear flag
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
ekf_check_state.bad_variance = false;
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
// clear failsafe
failsafe_ekf_off_event();
}
@ -155,7 +155,7 @@ void Plane::failsafe_ekf_event()
// EKF failsafe event has occurred
ekf_check_state.failsafe_on = true;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED);
// if not in a VTOL mode requiring position, then nothing needs to be done
#if HAL_QUADPLANE_ENABLED
@ -182,5 +182,5 @@ void Plane::failsafe_ekf_off_event(void)
}
ekf_check_state.failsafe_on = false;
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED);
}

View File

@ -114,10 +114,10 @@ void Plane::fence_check()
break;
}
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
} else if (orig_breaches) {
// record clearing of breach
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
}
}

View File

@ -170,7 +170,9 @@ void Plane::update_is_flying_5Hz(void)
crash_detection_update();
#if HAL_LOGGING_ENABLED
Log_Write_Status();
#endif
// tell AHRS flying state
set_likely_flying(new_is_flying);

View File

@ -51,6 +51,7 @@ void QAutoTune::init_z_limits()
}
#if HAL_LOGGING_ENABLED
// log VTOL PIDs for during twitch
void QAutoTune::log_pids(void)
{
@ -58,6 +59,7 @@ void QAutoTune::log_pids(void)
AP::logger().Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
AP::logger().Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
}
#endif
#endif // QAUTOTUNE_ENABLED

View File

@ -26,7 +26,9 @@ protected:
float get_pilot_desired_climb_rate_cms(void) const override;
void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override;
void init_z_limits() override;
#if HAL_LOGGING_ENABLED
void log_pids() override;
#endif
};
#endif // QAUTOTUNE_ENABLED

View File

@ -1053,7 +1053,7 @@ void QuadPlane::check_yaw_reset(void)
if (new_ekfYawReset_ms != ekfYawReset_ms) {
attitude_control->inertial_frame_reset();
ekfYawReset_ms = new_ekfYawReset_ms;
AP::logger().Write_Event(LogEvent::EKF_YAW_RESET);
LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET);
}
}
@ -1866,6 +1866,7 @@ void QuadPlane::update(void)
tiltrotor.update();
#if HAL_LOGGING_ENABLED
// motors logging
if (motors->armed()) {
const bool motors_active = in_vtol_mode() || assisted_flight;
@ -1886,7 +1887,9 @@ void QuadPlane::update(void)
Log_Write_QControl_Tuning();
}
}
#else
(void)now;
#endif // HAL_LOGGING_ENABLED
}
/*
@ -2296,6 +2299,7 @@ void QuadPlane::poscontrol_init_approach(void)
poscontrol.slow_descent = false;
}
#if HAL_LOGGING_ENABLED
/*
log the QPOS message
*/
@ -2309,6 +2313,7 @@ void QuadPlane::log_QPOS(void)
poscontrol.target_accel,
poscontrol.overshoot);
}
#endif
/*
change position control state
@ -2346,9 +2351,13 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s)
qp.landing_detect.lower_limit_start_ms = 0;
}
// double log to capture the state change
#if HAL_LOGGING_ENABLED
qp.log_QPOS();
#endif
state = s;
#if HAL_LOGGING_ENABLED
qp.log_QPOS();
#endif
last_log_ms = now;
overshoot = false;
}
@ -2926,11 +2935,13 @@ void QuadPlane::vtol_position_controller(void)
run_z_controller();
}
#if HAL_LOGGING_ENABLED
if (now_ms - poscontrol.last_log_ms >= 40) {
// log poscontrol at 25Hz
poscontrol.last_log_ms = now_ms;
log_QPOS();
}
#endif
}
/*
@ -3025,6 +3036,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
// acceleration capability.
const float nav_pitch_lower_limit_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + q_fwd_pitch_lim_cd * fwd_thr_scaler);
#if HAL_LOGGING_ENABLED
// Diagnostics logging - remove when feature is fully flight tested.
AP::logger().WriteStreaming("FWDT",
"TimeUS,fts,qfplcd,npllcd,npcd,qft", // labels
@ -3035,6 +3047,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
(double)nav_pitch_lower_limit_cd,
(double)plane.nav_pitch_cd,
(double)q_fwd_throttle);
#endif
plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd);
}
@ -3640,6 +3653,7 @@ bool QuadPlane::verify_vtol_land(void)
return false;
}
#if HAL_LOGGING_ENABLED
// Write a control tuning packet
void QuadPlane::Log_Write_QControl_Tuning()
{
@ -3671,6 +3685,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
// write multicopter position control message
pos_control->write_log();
}
#endif
/*

View File

@ -76,7 +76,7 @@ void Plane::init_ardupilot()
osd.init();
#endif
#if LOGGING_ENABLED == ENABLED
#if HAL_LOGGING_ENABLED
log_init();
#endif
@ -182,7 +182,7 @@ void Plane::startup_ground(void)
mission.init();
// initialise AP_Logger library
#if LOGGING_ENABLED == ENABLED
#if HAL_LOGGING_ENABLED
logger.setVehicle_Startup_Writer(
FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void)
);
@ -341,7 +341,9 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason)
old_mode.exit();
// log and notify mode change
#if HAL_LOGGING_ENABLED
logger.Write_Mode(control_mode->mode_number(), control_mode_reason);
#endif
notify_mode(*control_mode);
gcs().send_message(MSG_HEARTBEAT);
@ -466,17 +468,15 @@ void Plane::notify_mode(const Mode& mode)
notify.set_flight_mode_str(mode.name4());
}
#if HAL_LOGGING_ENABLED
/*
should we log a message type now?
*/
bool Plane::should_log(uint32_t mask)
{
#if LOGGING_ENABLED == ENABLED
return logger.should_log(mask);
#else
return false;
#endif
}
#endif
/*
return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust

View File

@ -783,6 +783,7 @@ void Tailsitter::speed_scaling(void)
}
#if HAL_LOGGING_ENABLED
// Write tailsitter specific log
void Tailsitter::write_log()
{
@ -799,6 +800,7 @@ void Tailsitter::write_log()
};
plane.logger.WriteBlock(&pkt, sizeof(pkt));
}
#endif // HAL_LOGGING_ENABLED
// return true if pitch control should be relaxed
// on vectored belly sitters the pitch control is not relaxed in order to keep motors pointing and avoid risk of props hitting the ground