Browse Source

AP_BattMonitor: support Disco battery monitoring

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
39dac57b56
  1. 4
      libraries/AP_BattMonitor/AP_BattMonitor.cpp
  2. 7
      libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp

4
libraries/AP_BattMonitor/AP_BattMonitor.cpp

@ -155,7 +155,7 @@ AP_BattMonitor::init() @@ -155,7 +155,7 @@ AP_BattMonitor::init()
return;
}
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
// force monitor for bebop
_monitoring[0] = BattMonitor_TYPE_BEBOP;
#endif
@ -180,7 +180,7 @@ AP_BattMonitor::init() @@ -180,7 +180,7 @@ AP_BattMonitor::init()
_num_instances++;
break;
case BattMonitor_TYPE_BEBOP:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
state[instance].instance = instance;
drivers[instance] = new AP_BattMonitor_Bebop(*this, instance, state[instance]);
_num_instances++;

7
libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp

@ -18,10 +18,11 @@ @@ -18,10 +18,11 @@
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX && \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
(CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO)
#include "AP_BattMonitor_Bebop.h"
#include <AP_HAL_Linux/RCOutput_Bebop.h>
#include <AP_HAL_Linux/RCOutput_Disco.h>
extern const AP_HAL::HAL& hal;
@ -143,7 +144,11 @@ void AP_BattMonitor_Bebop::read(void) @@ -143,7 +144,11 @@ void AP_BattMonitor_Bebop::read(void)
BebopBLDC_ObsData data;
float remaining, vbat, vbat_raw;
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
auto rcout = Linux::RCOutput_Bebop::from(hal.rcout);
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
auto rcout = Linux::RCOutput_Disco::from(hal.rcout);
#endif
tnow = AP_HAL::micros();
ret = rcout->read_obs_data(data);

Loading…
Cancel
Save