mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ESP32: RCOutput: appropriately assert PWM array size
Avoid over-running the pending PWM and safe value PWM arrays in case future chip revisions come out with more channels.
This commit is contained in:
parent
f6e01dbee9
commit
b2df646b86
@ -50,6 +50,8 @@ gpio_num_t outputs_pins[] = {};
|
||||
#endif
|
||||
|
||||
#define MAX_CHANNELS ARRAY_SIZE(outputs_pins)
|
||||
static_assert(MAX_CHANNELS < 12, "overrunning _pending and safe_pwm"); // max for current chips
|
||||
static_assert(MAX_CHANNELS < 32, "overrunning bitfields");
|
||||
|
||||
struct RCOutput::pwm_out RCOutput::pwm_group_list[MAX_CHANNELS];
|
||||
|
||||
@ -324,7 +326,7 @@ void RCOutput::force_safety_off(void)
|
||||
*/
|
||||
void RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
|
||||
{
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(safe_pwm); i++) {
|
||||
if (chmask & (1U<<i)) {
|
||||
safe_pwm[i] = period_us;
|
||||
}
|
||||
|
@ -118,10 +118,9 @@ private:
|
||||
static pwm_out pwm_group_list[];
|
||||
|
||||
bool _corked;
|
||||
uint16_t _pending[12]; //Max channel with 2 unit MCPWM
|
||||
uint32_t _pending_mask;
|
||||
|
||||
uint16_t safe_pwm[16]; // pwm to use when safety is on
|
||||
uint16_t _pending[12];
|
||||
uint16_t safe_pwm[12]; // pwm to use when safety is on
|
||||
|
||||
uint16_t _max_channels;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user