AP_Motors: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:07 +10:00 committed by Andrew Tridgell
parent f930c38712
commit bccfd98d0e
3 changed files with 7 additions and 0 deletions

View File

@ -378,6 +378,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle()
return get_throttle_hover() + ((1.0 - get_throttle_hover()) * _throttle_limit); return get_throttle_hover() + ((1.0 - get_throttle_hover()) * _throttle_limit);
} }
#if HAL_LOGGING_ENABLED
// 10hz logging of voltage scaling and max trust // 10hz logging of voltage scaling and max trust
void AP_MotorsMulticopter::Log_Write() void AP_MotorsMulticopter::Log_Write()
{ {
@ -393,6 +394,7 @@ void AP_MotorsMulticopter::Log_Write()
}; };
AP::logger().WriteBlock(&pkt_mot, sizeof(pkt_mot)); AP::logger().WriteBlock(&pkt_mot, sizeof(pkt_mot));
} }
#endif
// convert actuator output (0~1) range to pwm range // convert actuator output (0~1) range to pwm range
int16_t AP_MotorsMulticopter::output_to_pwm(float actuator) int16_t AP_MotorsMulticopter::output_to_pwm(float actuator)

View File

@ -89,8 +89,10 @@ public:
// convert values to PWM min and max if not configured // convert values to PWM min and max if not configured
void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max); 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 // 10hz logging of voltage scaling and max trust
void Log_Write() override; void Log_Write() override;
#endif
// Run arming checks // Run arming checks
bool arming_checks(size_t buflen, char *buffer) const override; bool arming_checks(size_t buflen, char *buffer) const override;

View File

@ -5,6 +5,7 @@
#include <Filter/Filter.h> // filter library #include <Filter/Filter.h> // filter library
#include <Filter/DerivativeFilter.h> #include <Filter/DerivativeFilter.h>
#include <GCS_MAVLink/GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Logger/AP_Logger_config.h>
// offsets for motors in motor_out and _motor_filtered arrays // offsets for motors in motor_out and _motor_filtered arrays
#define AP_MOTORS_MOT_1 0U #define AP_MOTORS_MOT_1 0U
@ -275,8 +276,10 @@ public:
void set_frame_string(const char * str); void set_frame_string(const char * str);
#endif #endif
#if HAL_LOGGING_ENABLED
// write log, to be called at 10hz // write log, to be called at 10hz
virtual void Log_Write() {}; virtual void Log_Write() {};
#endif
enum MotorOptions : uint8_t { enum MotorOptions : uint8_t {
BATT_RAW_VOLTAGE = (1 << 0U) BATT_RAW_VOLTAGE = (1 << 0U)