Skip to content

Commit

Permalink
RCOutput: initialize _esc_pwm_min and _esc_pwm_max
Browse files Browse the repository at this point in the history
Further protection from potential dangerous behavior when these do not
get initialized for some reason.
  • Loading branch information
robertlong13 authored and tridge committed Sep 16, 2024
1 parent a5c8b03 commit 4a1e4eb
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_HAL/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -422,6 +422,6 @@ class AP_HAL::RCOutput {
void append_to_banner(char banner_msg[], uint8_t banner_msg_len, output_mode out_mode, uint8_t low_ch, uint8_t high_ch) const;
const char* get_output_mode_string(enum output_mode out_mode) const;

uint16_t _esc_pwm_min;
uint16_t _esc_pwm_max;
uint16_t _esc_pwm_min = 1000;
uint16_t _esc_pwm_max = 2000;
};

0 comments on commit 4a1e4eb

Please sign in to comment.