ardupilot/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp

49 lines
1.7 KiB
C++
Raw Normal View History

2014-12-04 01:36:17 -04:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
2014-12-04 01:36:17 -04:00
#include "AP_BattMonitor.h"
#include "AP_BattMonitor_Backend.h"
/*
base class constructor.
This incorporates initialisation as well.
*/
AP_BattMonitor_Backend::AP_BattMonitor_Backend(AP_BattMonitor &mon, uint8_t instance, AP_BattMonitor::BattMonitor_State &mon_state) :
_mon(mon),
_state(mon_state),
_instance(instance)
2014-12-04 01:36:17 -04:00
{
}
/// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100)
uint8_t AP_BattMonitor_Backend::capacity_remaining_pct() const
{
float mah_remaining = _mon._pack_capacity[_state.instance] - _state.current_total_mah;
if ( _mon._pack_capacity[_state.instance] > 10 ) { // a very very small battery
return (100 * (mah_remaining) / _mon._pack_capacity[_state.instance]);
} else {
return 0;
}
2014-12-04 01:36:17 -04:00
}
/// set capacity for this instance
void AP_BattMonitor_Backend::set_capacity(uint32_t capacity)
{
_mon._pack_capacity[_instance] = capacity;
}