AP_HAL_ChibiOS: add 1Hz update_channel_masks()

Send dshot commands in update function
This commit is contained in:
Andy Piper 2021-06-16 10:27:23 +01:00 committed by Andrew Tridgell
parent 32b172669c
commit 9c7e2f5914
3 changed files with 22 additions and 40 deletions

View File

@ -480,18 +480,6 @@ void RCOutput::disable_ch(uint8_t chan)
}
}
bool RCOutput::prepare_for_arming()
{
// force all the ESCs to be active, in the future consider returning false
// if ESCs are not active that we require
_active_escs_mask = (en_mask << chan_offset);
#ifdef DISABLE_DSHOT
return true;
#else
return _dshot_command_queue.is_empty();
#endif
}
void RCOutput::write(uint8_t chan, uint16_t period_us)
{
if (chan >= max_channels) {
@ -1167,7 +1155,6 @@ void RCOutput::dshot_send_groups(uint32_t time_out_us)
// send a dshot command
if (!hal.util->get_soft_armed()
&& is_dshot_protocol(group.current_mode)
&& group_escs_active(group) // only send when someone is listening
&& dshot_command_is_active(group)) {
command_sent = dshot_send_command(group, _dshot_current_command.command, _dshot_current_command.chan);
// actually do a dshot send

View File

@ -215,12 +215,11 @@ public:
*/
void send_dshot_command(uint8_t command, uint8_t chan, uint32_t command_timeout_ms = 0, uint16_t repeat_count = 10, bool priority = false) override;
#endif
/*
If not already done flush any dshot commands still pending
* Update channel masks at 1Hz allowing for actions such as dshot commands to be sent
*/
bool prepare_for_arming() override;
void update_channel_masks() override;
#endif
/*
setup serial LED output for a given channel number, with

View File

@ -85,10 +85,6 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha
// chan is the servo channel to send the command to
void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t command_timeout_ms, uint16_t repeat_count, bool priority)
{
if (!_active_escs_mask && !priority) {
return;
}
DshotCommandPacket pkt;
pkt.command = command;
pkt.chan = chan;
@ -108,34 +104,34 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman
// The chanmask passed is added (ORed) into any existing mask.
void RCOutput::set_reversed_mask(uint16_t chanmask) {
_reversed_mask |= chanmask;
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
if (chanmask & (1U<<i)) {
switch (_dshot_esc_type) {
case DSHOT_ESC_BLHELI:
send_dshot_command(DSHOT_REVERSE, i, 0, 10, true);
break;
default:
break;
}
}
}
}
// Set the dshot outputs that should be reversible/3D
// The chanmask passed is added (ORed) into any existing mask.
void RCOutput::set_reversible_mask(uint16_t chanmask) {
_reversible_mask |= chanmask;
}
// Update the dshot outputs that should be reversible/3D at 1Hz
void RCOutput::update_channel_masks() {
// post arming dshot commands will not be accepted
if (hal.util->get_soft_armed()) {
return;
}
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
if (chanmask & (1U<<i)) {
switch (_dshot_esc_type) {
case DSHOT_ESC_BLHELI:
switch (_dshot_esc_type) {
case DSHOT_ESC_BLHELI:
if (_reversible_mask & (1U<<i)) {
send_dshot_command(DSHOT_3D_ON, i, 0, 10, true);
break;
default:
break;
}
}
if (_reversed_mask & (1U<<i)) {
send_dshot_command(DSHOT_REVERSE, i, 0, 10, true);
}
break;
default:
break;
}
}
}