Browse Source

AP_BLHeli: more changes for 32 bit servo mask

apm_2208
Andrew Tridgell 3 years ago
parent
commit
f3ce44ef2c
  1. 4
      libraries/AP_BLHeli/AP_BLHeli.cpp
  2. 4
      libraries/AP_BLHeli/AP_BLHeli.h

4
libraries/AP_BLHeli/AP_BLHeli.cpp

@ -1377,7 +1377,7 @@ void AP_BLHeli::init(void) @@ -1377,7 +1377,7 @@ void AP_BLHeli::init(void)
AP_Motors *motors = AP::motors();
#endif
if (motors) {
uint16_t motormask = motors->get_motor_mask();
uint32_t motormask = motors->get_motor_mask();
// set the rest of the digital channels
if (motors->is_digital_pwm_type()) {
digital_mask |= motormask;
@ -1580,7 +1580,7 @@ void AP_BLHeli::update_telemetry(void) @@ -1580,7 +1580,7 @@ void AP_BLHeli::update_telemetry(void)
break;
}
}
uint16_t mask = 1U << motor_map[idx];
uint32_t mask = 1U << motor_map[idx];
if (SRV_Channels::have_digital_outputs(mask)) {
hal.rcout->set_telem_request_mask(mask);
last_telem_esc = idx;

4
libraries/AP_BLHeli/AP_BLHeli.h

@ -53,7 +53,7 @@ public: @@ -53,7 +53,7 @@ public:
return channel_bidir_dshot_mask.get() & (1U << motor_map[esc_index]);
}
uint16_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }
uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); }
static AP_BLHeli *get_singleton(void) {
return _singleton;
@ -232,7 +232,7 @@ private: @@ -232,7 +232,7 @@ private:
// have we disabled motor outputs?
bool motors_disabled;
// mask of channels that should normally be disabled
uint16_t motors_disabled_mask;
uint32_t motors_disabled_mask;
// have we locked the UART?
bool uart_locked;

Loading…
Cancel
Save