mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_BoardConfig: Add minimum board and servo voltage parameters
This commit is contained in:
parent
be8d4e6c9d
commit
6a41f0c86a
@ -100,6 +100,10 @@
|
||||
#define BOARD_PWM_COUNT_DEFAULT 8
|
||||
#endif
|
||||
|
||||
#ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN
|
||||
#define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
|
||||
#endif
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
AP_BoardConfig *AP_BoardConfig::instance;
|
||||
|
||||
@ -226,6 +230,29 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
|
||||
// @Path: ../AP_RTC/AP_RTC.cpp
|
||||
AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC),
|
||||
|
||||
#if HAL_HAVE_BOARD_VOLTAGE
|
||||
// @Param: VBUS_MIN
|
||||
// @DisplayName: Autopilot board voltage requirement
|
||||
// @Description: Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
|
||||
// @Units: V
|
||||
// @Range: 4.0 5.5
|
||||
// Increment 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("VBUS_MIN", 15, AP_BoardConfig, _vbus_min, BOARD_CONFIG_BOARD_VOLTAGE_MIN),
|
||||
|
||||
#endif
|
||||
|
||||
#if HAL_HAVE_SERVO_VOLTAGE
|
||||
// @Param: VSERVO_MIN
|
||||
// @DisplayName: Servo voltage requirement
|
||||
// @Description: Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
|
||||
// @Units: V
|
||||
// @Range: 3.3 12.0
|
||||
// Increment 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -143,6 +143,19 @@ public:
|
||||
#endif
|
||||
}
|
||||
|
||||
#if HAL_HAVE_BOARD_VOLTAGE
|
||||
// get minimum board voltage
|
||||
static float get_minimum_board_voltage(void) {
|
||||
return instance?instance->_vbus_min.get():0;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_HAVE_SERVO_VOLTAGE
|
||||
// get minimum servo voltage
|
||||
static float get_minimum_servo_voltage(void) {
|
||||
return instance?instance->_vservo_min.get():0;
|
||||
}
|
||||
#endif
|
||||
|
||||
private:
|
||||
static AP_BoardConfig *instance;
|
||||
@ -207,4 +220,12 @@ private:
|
||||
|
||||
// real-time-clock; private because access is via the singleton
|
||||
AP_RTC rtc;
|
||||
|
||||
#if HAL_HAVE_BOARD_VOLTAGE
|
||||
AP_Float _vbus_min;
|
||||
#endif
|
||||
|
||||
#if HAL_HAVE_SERVO_VOLTAGE
|
||||
AP_Float _vservo_min;
|
||||
#endif
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user