ardupilot/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

180 lines
5.6 KiB
C++
Raw Normal View History

/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <hal.h>
#include "RCOutput.h"
#include <AP_Math/AP_Math.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include "hwdef/common/stm32_util.h"
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#if HAL_USE_PWM == TRUE
#if HAL_DSHOT_ENABLED
#if HAL_WITH_IO_MCU
#include <AP_IOMCU/AP_IOMCU.h>
extern AP_IOMCU iomcu;
#endif
using namespace ChibiOS;
extern const AP_HAL::HAL& hal;
bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t chan)
{
if (!group.can_send_dshot_pulse()) {
return false;
}
AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file
2023-09-24 10:09:23 -03:00
if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state)) {
// doing serial output or DMAR input, don't send DShot pulses
return false;
}
#ifdef HAL_GPIO_LINE_GPIO81
TOGGLE_PIN_DEBUG(81);
#endif
// first make sure we have the DMA channel before anything else
#if AP_HAL_SHARED_DMA_ENABLED
osalDbgAssert(!group.dma_handle->is_locked(), "DMA handle is already locked");
group.dma_handle->lock();
#endif
// only the timer thread releases the locks
group.dshot_waiter = rcout_thread_ctx;
bool bdshot_telem = false;
#ifdef HAL_WITH_BIDIR_DSHOT
AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file
2023-09-24 10:09:23 -03:00
bdshot_prepare_for_next_pulse(group);
bdshot_telem = group.bdshot.enabled;
#endif
memset((uint8_t *)group.dma_buffer, 0, DSHOT_BUFFER_LENGTH);
// keep the other ESCs armed rather than sending nothing
const uint16_t zero_packet = create_dshot_packet(0, false, bdshot_telem);
const uint16_t packet = create_dshot_packet(command, true, bdshot_telem);
for (uint8_t i = 0; i < 4; i++) {
if (!group.is_chan_enabled(i)) {
continue;
}
if (group.chan[i] == chan || chan == RCOutput::ALL_CHANNELS) {
fill_DMA_buffer_dshot(group.dma_buffer + i, 4, packet, group.bit_width_mul);
} else {
fill_DMA_buffer_dshot(group.dma_buffer + i, 4, zero_packet, group.bit_width_mul);
}
}
chEvtGetAndClearEvents(group.dshot_event_mask);
// start sending the pulses out
send_pulses_DMAR(group, DSHOT_BUFFER_LENGTH);
#ifdef HAL_GPIO_LINE_GPIO81
TOGGLE_PIN_DEBUG(81);
#endif
return true;
}
// Send a dshot command, if command timout is 0 then 10 commands are sent
// 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)
{
// once armed only priority commands will be accepted
if (hal.util->get_soft_armed() && !priority) {
return;
}
// not an FMU channel
if (chan < chan_offset || chan == ALL_CHANNELS) {
#if HAL_WITH_IO_MCU
if (iomcu_dshot) {
iomcu.send_dshot_command(command, chan, command_timeout_ms, repeat_count, priority);
}
#endif
if (chan != ALL_CHANNELS) {
return;
}
}
DshotCommandPacket pkt;
pkt.command = command;
AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file
2023-09-24 10:09:23 -03:00
if (chan != ALL_CHANNELS) {
pkt.chan = chan - chan_offset;
} else {
pkt.chan = ALL_CHANNELS;
}
if (command_timeout_ms == 0) {
pkt.cycle = MAX(10, repeat_count);
} else {
pkt.cycle = MAX(command_timeout_ms * 1000 / _dshot_period_us, repeat_count);
}
// prioritize anything that is not an LED or BEEP command
if (!_dshot_command_queue.push(pkt) && priority) {
_dshot_command_queue.push_force(pkt);
}
}
// Set the dshot outputs that should be reversed (as opposed to 3D)
// The chanmask passed is added (ORed) into any existing mask.
// The mask uses servo channel numbering
2021-01-11 22:01:48 -04:00
void RCOutput::set_reversed_mask(uint32_t chanmask) {
_reversed_mask |= chanmask;
}
// Set the dshot outputs that should be reversible/3D
// The chanmask passed is added (ORed) into any existing mask.
// The mask uses servo channel numbering
2021-01-11 22:01:48 -04:00
void RCOutput::set_reversible_mask(uint32_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() || _disable_channel_mask_updates) {
return;
}
#if HAL_PWM_COUNT > 0
for (uint8_t i=chan_offset; i<HAL_PWM_COUNT+chan_offset; i++) {
switch (_dshot_esc_type) {
case DSHOT_ESC_BLHELI:
case DSHOT_ESC_BLHELI_S:
case DSHOT_ESC_BLHELI_EDT:
case DSHOT_ESC_BLHELI_EDT_S:
if (_reversible_mask & (1U<<i)) {
send_dshot_command(DSHOT_3D_ON, i, 0, 10, true);
}
if (_reversed_mask & (1U<<i)) {
send_dshot_command(DSHOT_REVERSE, i, 0, 10, true);
}
break;
default:
break;
}
}
if (_dshot_esc_type == DSHOT_ESC_BLHELI_EDT || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S) {
send_dshot_command(DSHOT_EXTENDED_TELEMETRY_ENABLE, ALL_CHANNELS, 0, 10, true);
}
#endif
}
#endif // HAL_DSHOT_ENABLED
#endif // HAL_USE_PWM