mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_ChibiOS: more changes for 32 bit servo mask
This commit is contained in:
parent
d33734ee85
commit
1d9abefbb1
@ -500,10 +500,10 @@ RCOutput::pwm_group *RCOutput::find_chan(uint8_t chan, uint8_t &group_idx)
|
||||
/*
|
||||
* return mask of channels that must be disabled because they share a group with a digital channel
|
||||
*/
|
||||
uint16_t RCOutput::get_disabled_channels(uint16_t digital_mask)
|
||||
uint32_t RCOutput::get_disabled_channels(uint32_t digital_mask)
|
||||
{
|
||||
uint16_t dmask = (digital_mask >> chan_offset);
|
||||
uint16_t disabled_chan_mask = 0;
|
||||
uint32_t dmask = (digital_mask >> chan_offset);
|
||||
uint32_t disabled_chan_mask = 0;
|
||||
for (auto &group : pwm_group_list) {
|
||||
bool digital_group = false;
|
||||
for (uint8_t j = 0; j < 4; j++) {
|
||||
@ -615,7 +615,7 @@ void RCOutput::push_local(void)
|
||||
if (active_fmu_channels == 0) {
|
||||
return;
|
||||
}
|
||||
uint16_t outmask = (1U<<active_fmu_channels)-1;
|
||||
uint32_t outmask = (1U<<active_fmu_channels)-1;
|
||||
outmask &= en_mask;
|
||||
|
||||
uint16_t widest_pulse = 0;
|
||||
@ -1383,7 +1383,7 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us)
|
||||
// assume that we won't be able to get the input capture lock
|
||||
group.bdshot.enabled = false;
|
||||
|
||||
uint16_t active_channels = group.ch_mask & group.en_mask;
|
||||
uint32_t active_channels = group.ch_mask & group.en_mask;
|
||||
// now grab the input capture lock if we are able, we can only enable bi-dir on a group basis
|
||||
if (((_bdshot.mask & active_channels) == active_channels) && group.has_ic()) {
|
||||
if (group.has_shared_ic_up_dma()) {
|
||||
@ -1456,7 +1456,7 @@ void RCOutput::dshot_send(pwm_group &group, uint32_t time_out_us)
|
||||
continue;
|
||||
}
|
||||
|
||||
const uint16_t chan_mask = (1U<<chan);
|
||||
const uint32_t chan_mask = (1U<<chan);
|
||||
|
||||
pwm = constrain_int16(pwm, 1000, 2000);
|
||||
uint16_t value = MIN(2 * (pwm - 1000), 1999);
|
||||
|
@ -74,7 +74,7 @@ public:
|
||||
/*
|
||||
* return mask of channels that must be disabled because they share a group with a digital channel
|
||||
*/
|
||||
uint16_t get_disabled_channels(uint16_t digital_mask) override;
|
||||
uint32_t get_disabled_channels(uint32_t digital_mask) override;
|
||||
|
||||
float scale_esc_to_unity(uint16_t pwm) override {
|
||||
return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
|
||||
|
@ -41,7 +41,7 @@ extern const AP_HAL::HAL& hal;
|
||||
* enable bi-directional telemetry request for a mask of channels. This is used
|
||||
* with DShot to get telemetry feedback
|
||||
*/
|
||||
void RCOutput::set_bidir_dshot_mask(uint16_t mask)
|
||||
void RCOutput::set_bidir_dshot_mask(uint32_t mask)
|
||||
{
|
||||
_bdshot.mask = (mask >> chan_offset);
|
||||
// we now need to reconfigure the DMA channels since they are affected by the value of the mask
|
||||
|
@ -50,7 +50,7 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha
|
||||
group.dshot_waiter = rcout_thread_ctx;
|
||||
bool bdshot_telem = false;
|
||||
#ifdef HAL_WITH_BIDIR_DSHOT
|
||||
uint16_t active_channels = group.ch_mask & group.en_mask;
|
||||
uint32_t active_channels = group.ch_mask & group.en_mask;
|
||||
// no need to get the input capture lock
|
||||
group.bdshot.enabled = false;
|
||||
if ((_bdshot.mask & active_channels) == active_channels) {
|
||||
|
Loading…
Reference in New Issue
Block a user