Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_Generator.h
9642 views
#pragma once12#include <AP_Generator/AP_Generator.h>34#if HAL_GENERATOR_ENABLED56#include "AP_BattMonitor.h"7#include "AP_BattMonitor_Backend.h"89// Sub class for generator electrical10class AP_BattMonitor_Generator_Elec : public AP_BattMonitor_Backend11{12public:1314// Inherit constructor15using AP_BattMonitor_Backend::AP_BattMonitor_Backend;1617void init(void) override {};1819// Read the battery voltage and current20void read(void) override;2122bool has_current(void) const override;2324bool has_consumed_energy(void) const override;2526// Override backend update_failsafes27AP_BattMonitor::Failsafe update_failsafes() override;28};2930// Sub class for generator fuel31class AP_BattMonitor_Generator_FuelLevel : public AP_BattMonitor_Backend32{33public:3435// Inherit constructor36using AP_BattMonitor_Backend::AP_BattMonitor_Backend;3738void init(void) override;3940// Read the fuel level41void read(void) override;4243// This is where we tell the battery monitor 'we have current' if we want to report a fuel level remaining44bool has_current(void) const override;4546// This is where we tell the battery monitor 'we have consumed energy' if we want to report a fuel level remaining47bool has_consumed_energy(void) const override;4849// reset remaining percentage to given value50bool reset_remaining(float percentage) override;5152// capacity_remaining_ml - returns true if the capacity remaining in (mL) is valid and writes to capacity_ml53bool capacity_remaining_ml(float &capacity_ml) const;5455// capacity_remaining_pct - returns true if the percentage is valid and writes to percentage argument56bool capacity_remaining_pct(uint8_t &percentage) const override;5758// Override backend update_failsafes59AP_BattMonitor::Failsafe update_failsafes() override;6061// by default we asume 100% full tank, we can use MAV_CMD_BATTERY_RESET mavlink command to specify otherwise62// this is only used in case the generator doesn't provide a fuel percentage on its own. This variable63// is needed to support tank refills or different than 100% initial fuel level64uint8_t _initial_fuel_pct = 100.0f;65};66#endif676869