mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BattMonitor: convert APM_BUILD_COPTER_OR_HELI() to APM_BUILD_COPTER_OR_HELI
This commit is contained in:
parent
0d9b677586
commit
70b02aeadf
@ -449,7 +449,7 @@ void AP_BattMonitor::convert_params(void) {
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
||||
info.old_key = 166;
|
||||
#elif APM_BUILD_COPTER_OR_HELI()
|
||||
#elif APM_BUILD_COPTER_OR_HELI
|
||||
info.old_key = 36;
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
|
||||
info.old_key = 33;
|
||||
|
@ -3,11 +3,11 @@
|
||||
#include "AP_BattMonitor_Params.h"
|
||||
#include "AP_BattMonitor.h"
|
||||
|
||||
#if APM_BUILD_COPTER_OR_HELI()
|
||||
#if APM_BUILD_COPTER_OR_HELI
|
||||
#define DEFAULT_LOW_BATTERY_VOLTAGE 10.5f
|
||||
#else
|
||||
#define DEFAULT_LOW_BATTERY_VOLTAGE 0.0f
|
||||
#endif // APM_BUILD_COPTER_OR_HELI()
|
||||
#endif // APM_BUILD_COPTER_OR_HELI
|
||||
|
||||
const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = {
|
||||
// @Param: MONITOR
|
||||
|
Loading…
Reference in New Issue
Block a user