AP_Motors: add local loging of MOTB

This commit is contained in:
Iampete1 2021-12-21 20:53:58 +00:00 committed by Andrew Tridgell
parent cf1202ae65
commit 86578d5cec
3 changed files with 22 additions and 9 deletions

View File

@ -16,6 +16,7 @@
#include "AP_MotorsMulticopter.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_BattMonitor/AP_BattMonitor.h>
#include <AP_Logger/AP_Logger.h>
extern const AP_HAL::HAL& hal;
@ -394,6 +395,21 @@ void AP_MotorsMulticopter::update_lift_max_from_batt_voltage()
_lift_max = batt_voltage_filt * (1 - thrust_curve_expo) + thrust_curve_expo * batt_voltage_filt * batt_voltage_filt;
}
// 10hz logging of voltage scaling and max trust
void AP_MotorsMulticopter::Log_Write()
{
struct log_MotBatt pkt_mot = {
LOG_PACKET_HEADER_INIT(LOG_MOTBATT_MSG),
time_us : AP_HAL::micros64(),
lift_max : _lift_max,
bat_volt : _batt_voltage_filt.get(),
th_limit : _throttle_limit,
th_average_max : _throttle_avg_max,
mot_fail_flags : (uint8_t)(_thrust_boost | (_thrust_balanced << 1U)),
};
AP::logger().WriteBlock(&pkt_mot, sizeof(pkt_mot));
}
float AP_MotorsMulticopter::get_compensation_gain() const
{
// avoid divide by zero

View File

@ -55,15 +55,6 @@ public:
// throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()
void set_throttle_passthrough_for_esc_calibration(float throttle_input);
// get_lift_max - get maximum lift ratio - for logging purposes only
float get_lift_max() const { return _lift_max; }
// get_batt_voltage_filt - get battery voltage ratio - for logging purposes only
float get_batt_voltage_filt() const { return _batt_voltage_filt.get(); }
// get throttle limit imposed by battery current limiting. This is a number from 0 ~ 1 where 0 means hover throttle, 1 means full throttle (i.e. not limited)
float get_throttle_limit() const { return _throttle_limit; }
// returns maximum thrust in the range 0 to 1
float get_throttle_thrust_max() const { return _throttle_thrust_max; }
@ -108,6 +99,9 @@ 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);
// 10hz logging of voltage scaling and max trust
void Log_Write() override;
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

View File

@ -258,6 +258,9 @@ public:
void set_frame_string(const char * str);
#endif
// write log, to be called at 10hz
virtual void Log_Write() {};
protected:
// output functions that should be overloaded by child classes
virtual void output_armed_stabilizing() = 0;