5 changed files with 67 additions and 0 deletions
@ -0,0 +1,38 @@ |
|||||||
|
#include <AP_HAL/AP_HAL.h> |
||||||
|
#include <AP_Common/AP_Common.h> |
||||||
|
#include <AP_Math/AP_Math.h> |
||||||
|
#include "AP_BattMonitor.h" |
||||||
|
#include "AP_BattMonitor_Generator.h" |
||||||
|
|
||||||
|
extern const AP_HAL::HAL& hal; |
||||||
|
|
||||||
|
// read - read the voltage and current
|
||||||
|
void AP_BattMonitor_Generator::read() |
||||||
|
{ |
||||||
|
_state.healthy = false; |
||||||
|
|
||||||
|
#if GENERATOR_ENABLED |
||||||
|
AP_Generator_RichenPower *generator = AP::generator(); |
||||||
|
|
||||||
|
// healthy if we can find a generator
|
||||||
|
if (generator == nullptr) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
// get voltage
|
||||||
|
if (!generator->voltage(_state.voltage)) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
// get current
|
||||||
|
if (!generator->current(_state.current_amps)) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
if (!generator->healthy()) { |
||||||
|
return; |
||||||
|
} |
||||||
|
|
||||||
|
_state.healthy = true; |
||||||
|
#endif |
||||||
|
} |
@ -0,0 +1,22 @@ |
|||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "AP_BattMonitor.h" |
||||||
|
#include "AP_BattMonitor_Backend.h" |
||||||
|
|
||||||
|
#include <AP_Generator/AP_Generator_RichenPower.h> |
||||||
|
|
||||||
|
class AP_BattMonitor_Generator : public AP_BattMonitor_Backend |
||||||
|
{ |
||||||
|
public: |
||||||
|
|
||||||
|
using AP_BattMonitor_Backend::AP_BattMonitor_Backend; |
||||||
|
|
||||||
|
/// Read the battery voltage and current. Should be called at 10hz
|
||||||
|
void read() override; |
||||||
|
|
||||||
|
/// returns true if battery monitor provides current info
|
||||||
|
bool has_current() const override { return true; } |
||||||
|
|
||||||
|
void init(void) override {} |
||||||
|
|
||||||
|
}; |
Loading…
Reference in new issue