mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_VideoTX: protect vtx from pitmode changes when not enabled or not armed
This commit is contained in:
parent
34702ed986
commit
e1db6e38e2
@ -335,6 +335,10 @@ void AP_VideoTX::set_freq_is_current()
|
|||||||
// periodic update
|
// periodic update
|
||||||
void AP_VideoTX::update(void)
|
void AP_VideoTX::update(void)
|
||||||
{
|
{
|
||||||
|
if (!_enabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
#if HAL_CRSF_TELEM_ENABLED
|
#if HAL_CRSF_TELEM_ENABLED
|
||||||
AP_CRSF_Telem* crsf = AP::crsf_telem();
|
AP_CRSF_Telem* crsf = AP::crsf_telem();
|
||||||
|
|
||||||
@ -503,7 +507,7 @@ void AP_VideoTX::announce_vtx_settings() const
|
|||||||
// 6-pos range is in the middle of the available range
|
// 6-pos range is in the middle of the available range
|
||||||
void AP_VideoTX::change_power(int8_t position)
|
void AP_VideoTX::change_power(int8_t position)
|
||||||
{
|
{
|
||||||
if (position < 0 || position > 5) {
|
if (!_enabled || position < 0 || position > 5) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// first find out how many possible levels there are
|
// first find out how many possible levels there are
|
||||||
@ -529,7 +533,9 @@ void AP_VideoTX::change_power(int8_t position)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (power == 0) {
|
if (power == 0) {
|
||||||
|
if (!hal.util->get_soft_armed()) { // don't allow pitmode to be entered if already armed
|
||||||
set_configured_options(get_configured_options() | uint8_t(VideoOptions::VTX_PITMODE));
|
set_configured_options(get_configured_options() | uint8_t(VideoOptions::VTX_PITMODE));
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
if (has_option(VideoOptions::VTX_PITMODE)) {
|
if (has_option(VideoOptions::VTX_PITMODE)) {
|
||||||
set_configured_options(get_configured_options() & ~uint8_t(VideoOptions::VTX_PITMODE));
|
set_configured_options(get_configured_options() & ~uint8_t(VideoOptions::VTX_PITMODE));
|
||||||
|
Loading…
Reference in New Issue
Block a user