From bccfd98d0e3bd3584273bee325e1fa8fbccc1dfe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH] AP_Motors: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 ++ libraries/AP_Motors/AP_MotorsMulticopter.h | 2 ++ libraries/AP_Motors/AP_Motors_Class.h | 3 +++ 3 files changed, 7 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 5359ad16e7..cc7eb0fd3e 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -378,6 +378,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() return get_throttle_hover() + ((1.0 - get_throttle_hover()) * _throttle_limit); } +#if HAL_LOGGING_ENABLED // 10hz logging of voltage scaling and max trust void AP_MotorsMulticopter::Log_Write() { @@ -393,6 +394,7 @@ void AP_MotorsMulticopter::Log_Write() }; AP::logger().WriteBlock(&pkt_mot, sizeof(pkt_mot)); } +#endif // convert actuator output (0~1) range to pwm range int16_t AP_MotorsMulticopter::output_to_pwm(float actuator) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index f6e07e204a..3f97e5105a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -89,8 +89,10 @@ public: // convert values to PWM min and max if not configured void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max); +#if HAL_LOGGING_ENABLED // 10hz logging of voltage scaling and max trust void Log_Write() override; +#endif // Run arming checks bool arming_checks(size_t buflen, char *buffer) const override; diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index b8b39fbfb5..92c62bf054 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -5,6 +5,7 @@ #include // filter library #include #include +#include // offsets for motors in motor_out and _motor_filtered arrays #define AP_MOTORS_MOT_1 0U @@ -275,8 +276,10 @@ public: void set_frame_string(const char * str); #endif +#if HAL_LOGGING_ENABLED // write log, to be called at 10hz virtual void Log_Write() {}; +#endif enum MotorOptions : uint8_t { BATT_RAW_VOLTAGE = (1 << 0U)