mirror of https://github.com/ArduPilot/ardupilot
AP_VideoTX: Restore use of the VTX_MAX_POWER parameter
This functionality was lost when a significant rewrite of this code was done in commit 0658f06030
This commit is contained in:
parent
c53d3ae09b
commit
0a5407a1a7
|
@ -515,7 +515,7 @@ void AP_VideoTX::change_power(int8_t position)
|
|||
// first find out how many possible levels there are
|
||||
uint8_t num_active_levels = 0;
|
||||
for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) {
|
||||
if (_power_levels[i].active != PowerActive::Inactive) {
|
||||
if (_power_levels[i].active != PowerActive::Inactive && _power_levels[i].mw <= _max_power_mw) {
|
||||
num_active_levels++;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue