mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_BLHeli: more changes for 32 bit servo mask
This commit is contained in:
parent
10d7a559d2
commit
f3ce44ef2c
@ -1377,7 +1377,7 @@ void AP_BLHeli::init(void)
|
|||||||
AP_Motors *motors = AP::motors();
|
AP_Motors *motors = AP::motors();
|
||||||
#endif
|
#endif
|
||||||
if (motors) {
|
if (motors) {
|
||||||
uint16_t motormask = motors->get_motor_mask();
|
uint32_t motormask = motors->get_motor_mask();
|
||||||
// set the rest of the digital channels
|
// set the rest of the digital channels
|
||||||
if (motors->is_digital_pwm_type()) {
|
if (motors->is_digital_pwm_type()) {
|
||||||
digital_mask |= motormask;
|
digital_mask |= motormask;
|
||||||
@ -1580,7 +1580,7 @@ void AP_BLHeli::update_telemetry(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
uint16_t mask = 1U << motor_map[idx];
|
uint32_t mask = 1U << motor_map[idx];
|
||||||
if (SRV_Channels::have_digital_outputs(mask)) {
|
if (SRV_Channels::have_digital_outputs(mask)) {
|
||||||
hal.rcout->set_telem_request_mask(mask);
|
hal.rcout->set_telem_request_mask(mask);
|
||||||
last_telem_esc = idx;
|
last_telem_esc = idx;
|
||||||
|
@ -53,7 +53,7 @@ public:
|
|||||||
return channel_bidir_dshot_mask.get() & (1U << motor_map[esc_index]);
|
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) {
|
static AP_BLHeli *get_singleton(void) {
|
||||||
return _singleton;
|
return _singleton;
|
||||||
@ -232,7 +232,7 @@ private:
|
|||||||
// have we disabled motor outputs?
|
// have we disabled motor outputs?
|
||||||
bool motors_disabled;
|
bool motors_disabled;
|
||||||
// mask of channels that should normally be disabled
|
// mask of channels that should normally be disabled
|
||||||
uint16_t motors_disabled_mask;
|
uint32_t motors_disabled_mask;
|
||||||
|
|
||||||
// have we locked the UART?
|
// have we locked the UART?
|
||||||
bool uart_locked;
|
bool uart_locked;
|
||||||
|
Loading…
Reference in New Issue
Block a user