2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* 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/>.
|
2018-03-14 03:06:30 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
2020-10-12 16:57:29 -03:00
|
|
|
* Bi-directional dshot based on Betaflight, code by Andy Piper and Siddharth Bharat Purohit
|
2022-08-25 02:36:10 -03:00
|
|
|
*
|
|
|
|
* There really is no dshot reference. For information try these resources:
|
2023-11-16 12:27:16 -04:00
|
|
|
* https://brushlesswhoop.com/dshot-and-bidirectional-dshot/
|
2022-08-25 02:36:10 -03:00
|
|
|
* https://blck.mn/2016/11/dshot-the-new-kid-on-the-block/
|
|
|
|
* https://www.swallenhardware.io/battlebots/2019/4/20/a-developers-guide-to-dshot-escs
|
2018-01-05 02:19:51 -04:00
|
|
|
*/
|
2022-02-20 23:44:56 -04:00
|
|
|
|
|
|
|
#include <hal.h>
|
2023-06-01 12:07:26 -03:00
|
|
|
|
|
|
|
#if defined(IOMCU_FW) && HAL_DSHOT_ENABLED
|
|
|
|
// need to give the little guy as much help as possible
|
|
|
|
#pragma GCC optimize("O2")
|
|
|
|
#endif
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#include "RCOutput.h"
|
|
|
|
#include <AP_Math/AP_Math.h>
|
2018-01-05 04:55:01 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-03-16 18:49:40 -03:00
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
|
|
|
#include "GPIO.h"
|
2022-02-12 17:55:17 -04:00
|
|
|
#include "Util.h"
|
2022-08-25 02:36:10 -03:00
|
|
|
#include "Scheduler.h"
|
2018-05-30 01:22:49 -03:00
|
|
|
#include "hwdef/common/stm32_util.h"
|
2019-04-19 21:28:15 -03:00
|
|
|
#include "hwdef/common/watchdog.h"
|
2020-10-12 16:57:29 -03:00
|
|
|
#include <AP_InternalError/AP_InternalError.h>
|
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2022-02-10 10:42:33 -04:00
|
|
|
#include <AP_Common/ExpandingString.h>
|
2021-03-24 15:52:39 -03:00
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
#endif
|
2021-07-14 19:39:37 -03:00
|
|
|
|
2021-11-01 04:17:10 -03:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
#include <AP_HAL/SIMState.h>
|
|
|
|
#endif
|
|
|
|
|
2018-03-01 20:46:30 -04:00
|
|
|
#if HAL_USE_PWM == TRUE
|
2021-07-14 19:39:37 -03:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
2018-03-01 20:46:30 -04:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
#include <AP_IOMCU/AP_IOMCU.h>
|
|
|
|
extern AP_IOMCU iomcu;
|
|
|
|
#endif
|
|
|
|
|
2018-04-01 03:00:52 -03:00
|
|
|
#define RCOU_SERIAL_TIMING_DEBUG 0
|
2023-02-23 08:35:34 -04:00
|
|
|
#define LED_THD_WA_SIZE 256
|
|
|
|
#ifndef HAL_NO_LED_THREAD
|
|
|
|
#if defined(HAL_NO_RCOUT_THREAD)
|
|
|
|
#define HAL_NO_LED_THREAD 1
|
|
|
|
#else
|
|
|
|
#define HAL_NO_LED_THREAD 0
|
|
|
|
#endif
|
|
|
|
#endif
|
2018-04-01 03:00:52 -03:00
|
|
|
|
2020-10-12 16:57:29 -03:00
|
|
|
#define TELEM_IC_SAMPLE 16
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS };
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIAL_ESC_COMM_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
struct RCOutput::irq_state RCOutput::irq;
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2020-10-12 16:57:29 -03:00
|
|
|
const uint8_t RCOutput::NUM_GROUPS = ARRAY_SIZE(RCOutput::pwm_group_list);
|
2018-01-07 19:40:23 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// event mask for triggering a PWM send
|
2023-10-19 09:37:43 -03:00
|
|
|
// EVT_PWM_SEND = 11
|
2021-03-17 18:02:18 -03:00
|
|
|
static const eventmask_t EVT_PWM_START = EVENT_MASK(12);
|
2023-10-19 09:37:43 -03:00
|
|
|
// EVT_PWM_SYNTHETIC_SEND = 13
|
2021-03-17 18:02:18 -03:00
|
|
|
static const eventmask_t EVT_PWM_SEND_NEXT = EVENT_MASK(14);
|
2022-01-25 05:58:35 -04:00
|
|
|
static const eventmask_t EVT_LED_SEND = EVENT_MASK(15);
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// #pragma GCC optimize("Og")
|
|
|
|
|
|
|
|
/*
|
|
|
|
initialise RC output driver
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::init()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2022-01-25 21:31:38 -04:00
|
|
|
if (_initialised) {
|
|
|
|
// cannot init RCOutput twice
|
|
|
|
return;
|
|
|
|
}
|
2022-02-17 16:58:35 -04:00
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled()) {
|
|
|
|
// with IOMCU the local (FMU) channels start at 8
|
|
|
|
chan_offset = 8;
|
2023-10-19 12:22:08 -03:00
|
|
|
iomcu_enabled = true;
|
|
|
|
}
|
|
|
|
if (AP_BoardConfig::io_dshot()) {
|
|
|
|
iomcu_dshot = true;
|
2022-02-17 16:58:35 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2020-12-05 15:16:27 -04:00
|
|
|
const uint8_t i = &group - pwm_group_list;
|
2018-01-05 02:19:51 -04:00
|
|
|
//Start Pwm groups
|
2018-03-14 03:06:30 -03:00
|
|
|
group.current_mode = MODE_PWM_NORMAL;
|
2020-12-05 15:16:27 -04:00
|
|
|
group.dshot_event_mask = EVENT_MASK(i);
|
|
|
|
|
2018-01-12 04:29:16 -04:00
|
|
|
for (uint8_t j = 0; j < 4; j++ ) {
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !defined(IOMCU_FW)
|
2018-04-06 22:31:56 -03:00
|
|
|
uint8_t chan = group.chan[j];
|
2021-07-14 19:39:37 -03:00
|
|
|
if (SRV_Channels::is_GPIO(chan+chan_offset)) {
|
2018-04-06 22:31:56 -03:00
|
|
|
group.chan[j] = CHAN_DISABLED;
|
2022-02-12 17:55:17 -04:00
|
|
|
} else if (SRV_Channels::is_alarm(chan+chan_offset)
|
|
|
|
|| SRV_Channels::is_alarm_inverted(chan+chan_offset)) {
|
|
|
|
// alarm takes the whole timer
|
|
|
|
group.ch_mask = 0;
|
|
|
|
group.current_mode = MODE_PWM_NONE;
|
|
|
|
for (uint8_t k = 0; k < 4; k++) {
|
|
|
|
group.chan[k] = CHAN_DISABLED;
|
|
|
|
group.pwm_cfg.channels[k].mode = PWM_OUTPUT_DISABLED;
|
|
|
|
}
|
|
|
|
ChibiOS::Util::from(hal.util)->toneAlarm_init(group.pwm_cfg, group.pwm_drv, j,
|
|
|
|
SRV_Channels::is_alarm(chan+chan_offset));
|
|
|
|
break;
|
2018-04-06 22:31:56 -03:00
|
|
|
}
|
2021-07-14 19:39:37 -03:00
|
|
|
#endif
|
2018-03-14 03:06:30 -03:00
|
|
|
if (group.chan[j] != CHAN_DISABLED) {
|
2018-05-05 05:54:12 -03:00
|
|
|
num_fmu_channels = MAX(num_fmu_channels, group.chan[j]+1);
|
2018-03-14 03:06:30 -03:00
|
|
|
group.ch_mask |= (1U<<group.chan[j]);
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2020-10-12 16:57:29 -03:00
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
|
|
|
group.bdshot.telem_tim_ch[j] = CHAN_DISABLED;
|
|
|
|
#endif
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
if (group.ch_mask != 0) {
|
|
|
|
pwmStart(group.pwm_drv, &group.pwm_cfg);
|
2018-03-16 18:49:40 -03:00
|
|
|
group.pwm_started = true;
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2018-08-04 02:29:22 -03:00
|
|
|
chVTObjectInit(&group.dma_timeout);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-01-05 04:55:01 -04:00
|
|
|
iomcu.init();
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
2018-01-17 06:25:02 -04:00
|
|
|
chMtxObjectInit(&trigger_mutex);
|
2021-03-02 15:02:38 -04:00
|
|
|
chVTObjectInit(&_dshot_rate_timer);
|
2018-03-16 18:49:40 -03:00
|
|
|
// setup default output rate of 50Hz
|
2018-07-28 00:44:06 -03:00
|
|
|
set_freq(0xFFFF ^ ((1U<<chan_offset)-1), 50);
|
2018-04-14 00:55:03 -03:00
|
|
|
|
|
|
|
safety_state = AP_HAL::Util::SAFETY_DISARMED;
|
2020-10-12 16:57:29 -03:00
|
|
|
|
|
|
|
#if RCOU_DSHOT_TIMING_DEBUG
|
|
|
|
hal.gpio->pinMode(54, 1);
|
|
|
|
hal.gpio->pinMode(55, 1);
|
|
|
|
hal.gpio->pinMode(56, 1);
|
|
|
|
hal.gpio->pinMode(57, 1);
|
|
|
|
#endif
|
2021-01-16 05:05:09 -04:00
|
|
|
|
2021-04-30 01:48:25 -03:00
|
|
|
hal.scheduler->register_timer_process(FUNCTOR_BIND(this, &RCOutput::safety_update, void));
|
2021-01-16 05:05:09 -04:00
|
|
|
_initialised = true;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIALLED_ENABLED
|
2023-02-23 08:35:34 -04:00
|
|
|
// start the led thread
|
|
|
|
bool RCOutput::start_led_thread(void)
|
|
|
|
{
|
|
|
|
#if HAL_NO_LED_THREAD
|
|
|
|
return false;
|
|
|
|
#else
|
|
|
|
WITH_SEMAPHORE(led_thread_sem);
|
|
|
|
|
|
|
|
if (led_thread_created) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&RCOutput::led_thread, void), "led", LED_THD_WA_SIZE, AP_HAL::Scheduler::PRIORITY_LED, 0)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
led_thread_created = true;
|
|
|
|
return true;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
thread for handling LED RCOutpu
|
|
|
|
*/
|
|
|
|
void RCOutput::led_thread()
|
|
|
|
{
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(led_thread_sem);
|
|
|
|
led_thread_ctx = chThdGetSelfX();
|
|
|
|
}
|
|
|
|
|
|
|
|
// don't start outputting until fully configured
|
|
|
|
while (!hal.scheduler->is_system_initialized()) {
|
|
|
|
hal.scheduler->delay_microseconds(1000);
|
|
|
|
}
|
|
|
|
|
|
|
|
while (true) {
|
|
|
|
chEvtWaitOne(EVT_LED_SEND);
|
|
|
|
// if DMA sharing is in effect there can be quite a delay between the request to begin the cycle and
|
|
|
|
// actually sending out data - thus we need to work out how much time we have left to collect the locks
|
|
|
|
|
|
|
|
// process any pending LED output requests
|
2023-03-23 14:13:54 -03:00
|
|
|
led_timer_tick(rcout_micros(), LED_OUTPUT_PERIOD_US);
|
2023-02-23 08:35:34 -04:00
|
|
|
}
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_SERIAL_ENABLED
|
2023-02-23 08:35:34 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
/*
|
2022-08-25 02:36:10 -03:00
|
|
|
thread for handling RCOutput send on FMU
|
2020-12-05 15:16:27 -04:00
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !defined(IOMCU_FW)
|
2020-12-05 15:16:27 -04:00
|
|
|
void RCOutput::rcout_thread()
|
|
|
|
{
|
2023-03-23 14:13:54 -03:00
|
|
|
rcout_timer_t last_thread_run_us = 0; // last time we did a 1kHz run of rcout
|
|
|
|
rcout_timer_t last_cycle_run_us = 0;
|
2020-12-05 15:16:27 -04:00
|
|
|
|
|
|
|
rcout_thread_ctx = chThdGetSelfX();
|
|
|
|
|
|
|
|
// don't start outputting until fully configured
|
|
|
|
while (!hal.scheduler->is_system_initialized()) {
|
|
|
|
hal.scheduler->delay_microseconds(1000);
|
|
|
|
}
|
|
|
|
|
2021-03-02 15:02:38 -04:00
|
|
|
// dshot is quite sensitive to timing, it's important to output pulses as
|
|
|
|
// regularly as possible at the correct bitrate
|
2020-12-05 15:16:27 -04:00
|
|
|
while (true) {
|
2023-02-23 08:35:34 -04:00
|
|
|
const auto mask = chEvtWaitOne(EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND);
|
2022-01-25 05:58:35 -04:00
|
|
|
const bool have_pwm_event = (mask & (EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND)) != 0;
|
2020-12-05 15:16:27 -04:00
|
|
|
// start the clock
|
2023-03-23 14:13:54 -03:00
|
|
|
last_thread_run_us = rcout_micros();
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2021-03-02 15:02:38 -04:00
|
|
|
// this is when the cycle is supposed to start
|
2022-01-25 05:58:35 -04:00
|
|
|
if (_dshot_cycle == 0 && have_pwm_event) {
|
2023-03-23 14:13:54 -03:00
|
|
|
last_cycle_run_us = rcout_micros();
|
2021-03-02 15:02:38 -04:00
|
|
|
// register a timer for the next tick if push() will not be providing it
|
2021-05-02 14:35:19 -03:00
|
|
|
if (_dshot_rate != 1) {
|
2021-03-02 15:02:38 -04:00
|
|
|
chVTSet(&_dshot_rate_timer, chTimeUS2I(_dshot_period_us), dshot_update_tick, this);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// if DMA sharing is in effect there can be quite a delay between the request to begin the cycle and
|
|
|
|
// actually sending out data - thus we need to work out how much time we have left to collect the locks
|
2023-03-23 14:13:54 -03:00
|
|
|
const rcout_timer_t timeout_period_us = _dshot_rate ? (_dshot_cycle + 1) * _dshot_period_us : _dshot_period_us;
|
|
|
|
// timeout is measured from the beginning of the push() that initiated it to preserve periodicity
|
|
|
|
const rcout_timer_t cycle_start_us = _dshot_rate ? last_cycle_run_us : last_thread_run_us;
|
2021-03-02 15:02:38 -04:00
|
|
|
|
|
|
|
// main thread requested a new dshot send or we timed out - if we are not running
|
|
|
|
// as a multiple of loop rate then ignore EVT_PWM_SEND events to preserve periodicity
|
2022-08-25 02:36:10 -03:00
|
|
|
if (!in_soft_serial() && have_pwm_event) {
|
2023-03-23 14:13:54 -03:00
|
|
|
dshot_send_groups(cycle_start_us, timeout_period_us);
|
2021-03-02 15:02:38 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// now unlock everything
|
2023-03-23 14:13:54 -03:00
|
|
|
dshot_collect_dma_locks(cycle_start_us, timeout_period_us);
|
2021-03-02 15:02:38 -04:00
|
|
|
|
2021-03-31 18:57:53 -03:00
|
|
|
if (_dshot_rate > 0) {
|
|
|
|
_dshot_cycle = (_dshot_cycle + 1) % _dshot_rate;
|
|
|
|
}
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// process any pending RC output requests
|
2023-03-23 14:13:54 -03:00
|
|
|
timer_tick(cycle_start_us, timeout_period_us);
|
2022-03-25 05:09:20 -03:00
|
|
|
#if RCOU_DSHOT_TIMING_DEBUG
|
|
|
|
static bool output_masks = true;
|
|
|
|
if (AP_HAL::millis() > 5000 && output_masks) {
|
|
|
|
output_masks = false;
|
2022-08-25 02:36:10 -03:00
|
|
|
hal.console->printf("bdmask 0x%lx, en_mask 0x%lx, 3dmask 0x%lx:\n", _bdshot.mask, en_mask, _reversible_mask);
|
2022-03-25 05:09:20 -03:00
|
|
|
for (auto &group : pwm_group_list) {
|
2022-08-25 02:36:10 -03:00
|
|
|
hal.console->printf(" timer %u: ch_mask 0x%lx, en_mask 0x%lx\n", group.timer_id, group.ch_mask, group.en_mask);
|
2022-03-25 05:09:20 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2022-11-10 12:49:54 -04:00
|
|
|
__RAMFUNC__ void RCOutput::dshot_update_tick(virtual_timer_t* vt, void* p)
|
2021-03-02 15:02:38 -04:00
|
|
|
{
|
|
|
|
chSysLockFromISR();
|
|
|
|
RCOutput* rcout = (RCOutput*)p;
|
|
|
|
|
2021-05-02 14:35:19 -03:00
|
|
|
if (rcout->_dshot_cycle + 1 < rcout->_dshot_rate) {
|
2021-03-02 15:02:38 -04:00
|
|
|
chVTSetI(&rcout->_dshot_rate_timer, chTimeUS2I(rcout->_dshot_period_us), dshot_update_tick, p);
|
|
|
|
}
|
2021-03-17 18:02:18 -03:00
|
|
|
chEvtSignalI(rcout->rcout_thread_ctx, EVT_PWM_SYNTHETIC_SEND);
|
2021-03-02 15:02:38 -04:00
|
|
|
chSysUnlockFromISR();
|
|
|
|
}
|
|
|
|
|
2022-07-14 04:47:42 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2023-10-19 09:37:43 -03:00
|
|
|
// calculate how much time remains in the current cycle
|
2023-03-23 14:13:54 -03:00
|
|
|
sysinterval_t RCOutput::calc_ticks_remaining(pwm_group &group, rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us, rcout_timer_t output_period_us)
|
2023-10-19 09:37:43 -03:00
|
|
|
{
|
|
|
|
// calculate how long we have left
|
2023-03-23 14:13:54 -03:00
|
|
|
rcout_timer_t now = rcout_micros();
|
2023-10-19 09:37:43 -03:00
|
|
|
// if we have time left wait for the event
|
2023-03-23 14:13:54 -03:00
|
|
|
|
|
|
|
const rcout_timer_t pulse_remaining_us
|
|
|
|
= AP_HAL::timeout_remaining(group.last_dmar_send_us, now, group.dshot_pulse_send_time_us);
|
|
|
|
const rcout_timer_t timeout_remaining_us
|
|
|
|
= AP_HAL::timeout_remaining(cycle_start_us, now, timeout_period_us);
|
|
|
|
// better to let the burst write in progress complete rather than cancelling mid way through
|
|
|
|
rcout_timer_t wait_us = MAX(pulse_remaining_us, timeout_remaining_us);
|
2023-10-19 09:37:43 -03:00
|
|
|
|
|
|
|
// waiting for a very short period of time can cause a
|
|
|
|
// timer wrap with ChibiOS timers. Use CH_CFG_ST_TIMEDELTA
|
|
|
|
// as minimum. Don't allow for a very long delay (over _dshot_period_us)
|
|
|
|
// to prevent bugs in handling timer wrap
|
2023-03-23 14:13:54 -03:00
|
|
|
const rcout_timer_t max_delay_us = output_period_us;
|
|
|
|
const rcout_timer_t min_delay_us = 10; // matches our CH_CFG_ST_TIMEDELTA
|
2023-10-19 09:37:43 -03:00
|
|
|
wait_us = constrain_uint32(wait_us, min_delay_us, max_delay_us);
|
|
|
|
|
|
|
|
return MIN(TIME_MAX_INTERVAL, chTimeUS2I(wait_us));
|
|
|
|
}
|
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// release locks on the groups that are pending in reverse order
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::dshot_collect_dma_locks(rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us, bool led_thread)
|
2020-12-05 15:16:27 -04:00
|
|
|
{
|
|
|
|
if (NUM_GROUPS == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
for (int8_t i = NUM_GROUPS - 1; i >= 0; i--) {
|
|
|
|
pwm_group &group = pwm_group_list[i];
|
2023-02-23 08:35:34 -04:00
|
|
|
|
2023-05-16 16:09:52 -03:00
|
|
|
if (led_thread != is_led_protocol(group.current_mode)) {
|
2023-02-23 08:35:34 -04:00
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
2023-09-24 10:09:23 -03:00
|
|
|
// dma handle will only be unlocked if the send was aborted
|
2020-12-05 15:16:27 -04:00
|
|
|
if (group.dma_handle != nullptr && group.dma_handle->is_locked()) {
|
2023-09-24 10:09:23 -03:00
|
|
|
// if we have time left wait for the event
|
2023-03-23 14:13:54 -03:00
|
|
|
const sysinterval_t wait_ticks = calc_ticks_remaining(group, cycle_start_us, timeout_period_us,
|
2023-10-19 09:37:43 -03:00
|
|
|
led_thread ? LED_OUTPUT_PERIOD_US : _dshot_period_us);
|
|
|
|
const eventmask_t mask = chEvtWaitOneTimeout(group.dshot_event_mask, wait_ticks);
|
2022-04-02 05:05:30 -03:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// no time left cancel and restart
|
|
|
|
if (!mask) {
|
|
|
|
dma_cancel(group);
|
|
|
|
}
|
|
|
|
group.dshot_waiter = nullptr;
|
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
|
|
|
// if using input capture DMA then clean up
|
|
|
|
if (group.bdshot.enabled) {
|
|
|
|
// only unlock if not shared
|
2023-09-24 10:09:23 -03:00
|
|
|
if (group.bdshot.curr_ic_dma_handle != nullptr
|
|
|
|
&& group.bdshot.curr_ic_dma_handle != group.dma_handle) {
|
|
|
|
group.bdshot.curr_ic_dma_handle->unlock();
|
|
|
|
group.bdshot.curr_ic_dma_handle = nullptr;
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
group.dma_handle->unlock();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2022-07-14 04:47:42 -03:00
|
|
|
#endif // AP_HAL_SHARED_DMA_ENABLED
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
setup the output frequency for a group and start pwm output
|
|
|
|
*/
|
|
|
|
void RCOutput::set_freq_group(pwm_group &group)
|
|
|
|
{
|
2018-03-25 20:48:38 -03:00
|
|
|
if (mode_requires_dma(group.current_mode)) {
|
|
|
|
// speed setup in DMA handler
|
|
|
|
return;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
uint16_t freq_set = group.rc_frequency;
|
|
|
|
uint32_t old_clock = group.pwm_cfg.frequency;
|
2018-04-03 05:13:41 -03:00
|
|
|
uint32_t old_period = group.pwm_cfg.period;
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2018-04-03 05:13:41 -03:00
|
|
|
if (freq_set > 400 || group.current_mode == MODE_PWM_ONESHOT125) {
|
|
|
|
// use a 8MHz clock for higher frequencies or for
|
|
|
|
// oneshot125. Using 8MHz for oneshot125 results in the full
|
|
|
|
// 1000 steps for smooth output
|
2018-03-16 18:49:40 -03:00
|
|
|
group.pwm_cfg.frequency = 8000000;
|
|
|
|
} else if (freq_set <= 400) {
|
|
|
|
// use a 1MHz clock
|
|
|
|
group.pwm_cfg.frequency = 1000000;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check if the frequency is possible, and keep halving
|
|
|
|
// down to 1MHz until it is OK with the hardware timer we
|
|
|
|
// are using. If we don't do this we'll hit an assert in
|
|
|
|
// the ChibiOS PWM driver on some timers
|
|
|
|
PWMDriver *pwmp = group.pwm_drv;
|
|
|
|
uint32_t psc = (pwmp->clock / pwmp->config->frequency) - 1;
|
|
|
|
while ((psc > 0xFFFF || ((psc + 1) * pwmp->config->frequency) != pwmp->clock) &&
|
|
|
|
group.pwm_cfg.frequency > 1000000) {
|
|
|
|
group.pwm_cfg.frequency /= 2;
|
|
|
|
psc = (pwmp->clock / pwmp->config->frequency) - 1;
|
|
|
|
}
|
2018-03-25 20:48:38 -03:00
|
|
|
|
2018-04-03 05:13:41 -03:00
|
|
|
if (group.current_mode == MODE_PWM_ONESHOT ||
|
|
|
|
group.current_mode == MODE_PWM_ONESHOT125) {
|
|
|
|
// force a period of 0, meaning no pulses till we trigger
|
|
|
|
group.pwm_cfg.period = 0;
|
|
|
|
} else {
|
|
|
|
group.pwm_cfg.period = group.pwm_cfg.frequency/freq_set;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-25 20:48:38 -03:00
|
|
|
bool force_reconfig = false;
|
|
|
|
for (uint8_t j=0; j<4; j++) {
|
2018-03-26 18:11:10 -03:00
|
|
|
if (group.pwm_cfg.channels[j].mode == PWM_OUTPUT_ACTIVE_LOW) {
|
2018-03-25 20:48:38 -03:00
|
|
|
group.pwm_cfg.channels[j].mode = PWM_OUTPUT_ACTIVE_HIGH;
|
|
|
|
force_reconfig = true;
|
|
|
|
}
|
2018-04-13 18:44:14 -03:00
|
|
|
if (group.pwm_cfg.channels[j].mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW) {
|
|
|
|
group.pwm_cfg.channels[j].mode = PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH;
|
|
|
|
force_reconfig = true;
|
|
|
|
}
|
|
|
|
|
2018-03-25 20:48:38 -03:00
|
|
|
}
|
2018-03-26 18:11:10 -03:00
|
|
|
|
2018-04-03 05:13:41 -03:00
|
|
|
if (old_clock != group.pwm_cfg.frequency ||
|
|
|
|
old_period != group.pwm_cfg.period ||
|
|
|
|
!group.pwm_started ||
|
|
|
|
force_reconfig) {
|
2018-03-16 18:49:40 -03:00
|
|
|
// we need to stop and start to setup the new clock
|
|
|
|
if (group.pwm_started) {
|
|
|
|
pwmStop(group.pwm_drv);
|
|
|
|
}
|
|
|
|
pwmStart(group.pwm_drv, &group.pwm_cfg);
|
|
|
|
group.pwm_started = true;
|
|
|
|
}
|
2018-03-26 18:11:10 -03:00
|
|
|
pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
set output frequency in HZ for a set of channels given by a mask
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-03-16 18:49:40 -03:00
|
|
|
// change frequency on IOMCU
|
2018-07-28 00:44:06 -03:00
|
|
|
uint16_t io_chmask = chmask & 0xFF;
|
|
|
|
if (io_chmask) {
|
2019-09-20 21:13:14 -03:00
|
|
|
// disallow changing frequency of this group if it is greater than the default
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(iomcu.ch_masks); i++) {
|
|
|
|
const uint16_t mask = io_chmask & iomcu.ch_masks[i];
|
|
|
|
if (mask != 0) {
|
|
|
|
if (freq_hz > 50) {
|
|
|
|
io_fast_channel_mask |= mask;
|
|
|
|
} else {
|
|
|
|
io_fast_channel_mask &= ~mask;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2018-07-28 00:44:06 -03:00
|
|
|
iomcu.set_freq(io_fast_channel_mask, freq_hz);
|
2018-05-11 03:30:18 -03:00
|
|
|
}
|
2018-01-05 04:55:01 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// convert to a local (FMU) channel mask
|
2018-01-05 02:19:51 -04:00
|
|
|
chmask >>= chan_offset;
|
|
|
|
if (chmask == 0) {
|
|
|
|
return;
|
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
we enable the new frequency on all groups that have one
|
|
|
|
of the requested channels. This means we may enable high
|
|
|
|
speed on some channels that aren't requested, but that
|
2019-09-20 21:13:14 -03:00
|
|
|
is needed in order to fly a vehicle such as a hex
|
2018-03-16 18:49:40 -03:00
|
|
|
multicopter properly
|
|
|
|
*/
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2018-03-14 03:06:30 -03:00
|
|
|
// greater than 400 doesn't give enough room at higher periods for
|
|
|
|
// the down pulse. This still allows for high rate with oneshot and dshot.
|
|
|
|
uint16_t group_freq = freq_hz;
|
|
|
|
if (group_freq > 400 && group.current_mode != MODE_PWM_BRUSHED) {
|
|
|
|
group_freq = 400;
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
if ((group.ch_mask & chmask) != 0) {
|
2018-03-16 18:49:40 -03:00
|
|
|
group.rc_frequency = group_freq;
|
|
|
|
set_freq_group(group);
|
2019-09-20 21:13:14 -03:00
|
|
|
// disallow changing frequency of this group if it is greater than the default
|
|
|
|
if (group_freq > 50) {
|
|
|
|
fast_channel_mask |= group.ch_mask;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-12 23:53:29 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-12 23:53:29 -04:00
|
|
|
/*
|
|
|
|
set default output rate
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::set_default_rate(uint16_t freq_hz)
|
2018-01-12 23:53:29 -04:00
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-01-12 23:53:29 -04:00
|
|
|
iomcu.set_default_rate(freq_hz);
|
|
|
|
}
|
|
|
|
#endif
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2018-03-14 03:06:30 -03:00
|
|
|
if ((group.ch_mask & fast_channel_mask) || group.ch_mask == 0) {
|
2018-01-12 23:53:29 -04:00
|
|
|
// don't change fast channels
|
|
|
|
continue;
|
|
|
|
}
|
2018-03-26 18:11:10 -03:00
|
|
|
group.pwm_cfg.period = group.pwm_cfg.frequency/freq_hz;
|
|
|
|
if (group.pwm_started) {
|
|
|
|
pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
|
|
|
|
}
|
2018-01-12 23:53:29 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-03-02 15:02:38 -04:00
|
|
|
/*
|
2021-03-31 18:57:53 -03:00
|
|
|
Set the dshot rate as a multiple of the loop rate.
|
|
|
|
This is called late after init_ardupilot() so groups will have been setup
|
2021-03-02 15:02:38 -04:00
|
|
|
*/
|
|
|
|
void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz)
|
|
|
|
{
|
|
|
|
// for low loop rates simply output at 1Khz on a timer
|
2021-03-17 18:02:18 -03:00
|
|
|
if (loop_rate_hz <= 100 || dshot_rate == 0) {
|
2021-03-02 15:02:38 -04:00
|
|
|
_dshot_period_us = 1000UL;
|
|
|
|
_dshot_rate = 0;
|
2023-08-14 04:44:08 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_dshot) {
|
2023-08-14 04:44:08 -03:00
|
|
|
iomcu.set_dshot_period(1000UL, 0);
|
|
|
|
}
|
|
|
|
#endif
|
2021-03-02 15:02:38 -04:00
|
|
|
return;
|
|
|
|
}
|
2021-03-31 18:57:53 -03:00
|
|
|
// if there are non-dshot channels then do likewise
|
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
if (group.current_mode == MODE_PWM_ONESHOT ||
|
|
|
|
group.current_mode == MODE_PWM_ONESHOT125 ||
|
|
|
|
group.current_mode == MODE_PWM_BRUSHED) {
|
|
|
|
_dshot_period_us = 1000UL;
|
|
|
|
_dshot_rate = 0;
|
2023-08-14 04:44:08 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
// this is not strictly neccessary since the iomcu could run at a different rate,
|
|
|
|
// but there is only one parameter to control this
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_dshot) {
|
2023-08-14 04:44:08 -03:00
|
|
|
iomcu.set_dshot_period(1000UL, 0);
|
|
|
|
}
|
|
|
|
#endif
|
2021-03-31 18:57:53 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2021-03-02 15:02:38 -04:00
|
|
|
|
|
|
|
uint16_t drate = dshot_rate * loop_rate_hz;
|
|
|
|
_dshot_rate = dshot_rate;
|
2021-03-17 18:02:18 -03:00
|
|
|
// BLHeli32 uses a 16 bit counter for input calibration which at 48Mhz will wrap
|
|
|
|
// at 732Hz so never allow rates below 800hz
|
|
|
|
while (drate < 800) {
|
2021-03-02 15:02:38 -04:00
|
|
|
_dshot_rate++;
|
|
|
|
drate = _dshot_rate * loop_rate_hz;
|
|
|
|
}
|
|
|
|
// prevent stupidly high rates, ideally should also prevent high rates
|
|
|
|
// with slower dshot variants
|
|
|
|
if (drate > 4000) {
|
|
|
|
_dshot_rate = 4000 / loop_rate_hz;
|
|
|
|
drate = _dshot_rate * loop_rate_hz;
|
|
|
|
}
|
|
|
|
_dshot_period_us = 1000000UL / drate;
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_dshot) {
|
2022-08-25 02:36:10 -03:00
|
|
|
iomcu.set_dshot_period(_dshot_period_us, _dshot_rate);
|
|
|
|
}
|
|
|
|
#endif
|
2021-03-02 15:02:38 -04:00
|
|
|
}
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2022-05-23 07:42:48 -03:00
|
|
|
/*
|
|
|
|
Set/get the dshot esc_type
|
|
|
|
*/
|
|
|
|
void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type)
|
|
|
|
{
|
|
|
|
_dshot_esc_type = dshot_esc_type;
|
|
|
|
switch (_dshot_esc_type) {
|
|
|
|
case DSHOT_ESC_BLHELI_S:
|
2023-05-29 16:45:47 -03:00
|
|
|
case DSHOT_ESC_BLHELI_EDT_S:
|
2022-05-23 07:42:48 -03:00
|
|
|
DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_S;
|
|
|
|
DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_S;
|
|
|
|
DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_S;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
DSHOT_BIT_WIDTH_TICKS = DSHOT_BIT_WIDTH_TICKS_DEFAULT;
|
|
|
|
DSHOT_BIT_0_TICKS = DSHOT_BIT_0_TICKS_DEFAULT;
|
|
|
|
DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_DEFAULT;
|
|
|
|
break;
|
|
|
|
}
|
2023-09-24 10:09:23 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_dshot) {
|
2023-09-24 10:09:23 -03:00
|
|
|
iomcu.set_dshot_esc_type(dshot_esc_type);
|
|
|
|
}
|
|
|
|
#endif
|
2022-05-23 07:42:48 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // #if HAL_DSHOT_ENABLED
|
2022-05-23 07:42:48 -03:00
|
|
|
|
2019-09-09 06:23:47 -03:00
|
|
|
/*
|
|
|
|
find pwm_group and index in group given a channel number
|
|
|
|
*/
|
|
|
|
RCOutput::pwm_group *RCOutput::find_chan(uint8_t chan, uint8_t &group_idx)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (chan >= max_channels) {
|
2019-09-09 06:23:47 -03:00
|
|
|
return nullptr;
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
if (chan < chan_offset) {
|
2019-09-09 06:23:47 -03:00
|
|
|
return nullptr;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
chan -= chan_offset;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
2018-03-14 03:06:30 -03:00
|
|
|
if (group.chan[j] == chan) {
|
2019-09-09 06:23:47 -03:00
|
|
|
group_idx = j;
|
|
|
|
return &group;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
return nullptr;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2022-04-19 14:16:25 -03:00
|
|
|
/*
|
|
|
|
* return mask of channels that must be disabled because they share a group with a digital channel
|
|
|
|
*/
|
2022-05-15 18:30:16 -03:00
|
|
|
uint32_t RCOutput::get_disabled_channels(uint32_t digital_mask)
|
2022-04-19 14:16:25 -03:00
|
|
|
{
|
2022-05-15 18:30:16 -03:00
|
|
|
uint32_t dmask = (digital_mask >> chan_offset);
|
|
|
|
uint32_t disabled_chan_mask = 0;
|
2022-04-19 14:16:25 -03:00
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
bool digital_group = false;
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
if ((1U << group.chan[j]) & dmask) {
|
|
|
|
digital_group = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (digital_group) {
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
if (!((1U << group.chan[j]) & dmask)) {
|
|
|
|
disabled_chan_mask |= (1U << group.chan[j]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
disabled_chan_mask <<= chan_offset;
|
|
|
|
return disabled_chan_mask;
|
|
|
|
}
|
|
|
|
|
2019-09-09 06:23:47 -03:00
|
|
|
uint16_t RCOutput::get_freq(uint8_t chan)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2019-09-09 06:23:47 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2018-01-05 02:19:51 -04:00
|
|
|
if (chan < chan_offset) {
|
2019-09-09 06:23:47 -03:00
|
|
|
return iomcu.get_freq(chan);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
#endif
|
|
|
|
uint8_t i;
|
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
if (grp) {
|
|
|
|
return grp->pwm_drv->config->frequency / grp->pwm_drv->period;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
// assume 50Hz default
|
|
|
|
return 50;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2019-09-09 06:23:47 -03:00
|
|
|
void RCOutput::enable_ch(uint8_t chan)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (chan < chan_offset && iomcu_enabled) {
|
2022-08-25 02:36:10 -03:00
|
|
|
iomcu.enable_ch(chan);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2019-09-09 06:23:47 -03:00
|
|
|
uint8_t i;
|
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
if (grp) {
|
|
|
|
en_mask |= 1U << (chan - chan_offset);
|
2021-05-21 18:28:13 -03:00
|
|
|
grp->en_mask |= 1U << (chan - chan_offset);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2019-09-09 06:23:47 -03:00
|
|
|
void RCOutput::disable_ch(uint8_t chan)
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (chan < chan_offset && iomcu_enabled) {
|
2022-08-25 02:36:10 -03:00
|
|
|
iomcu.disable_ch(chan);
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2019-09-09 06:23:47 -03:00
|
|
|
uint8_t i;
|
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
if (grp) {
|
|
|
|
pwmDisableChannel(grp->pwm_drv, i);
|
|
|
|
en_mask &= ~(1U<<(chan - chan_offset));
|
2021-05-21 18:28:13 -03:00
|
|
|
grp->en_mask &= ~(1U << (chan - chan_offset));
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2021-11-01 04:17:10 -03:00
|
|
|
|
2018-05-05 05:54:12 -03:00
|
|
|
if (chan >= max_channels) {
|
2018-01-12 04:29:16 -04:00
|
|
|
return;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
last_sent[chan] = period_us;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2021-11-01 04:17:10 -03:00
|
|
|
#if AP_SIM_ENABLED
|
|
|
|
hal.simstate->pwm_output[chan] = period_us;
|
2022-05-23 02:11:06 -03:00
|
|
|
if (!(AP::sitl()->on_hardware_output_enable_mask & (1U<<chan))) {
|
|
|
|
return;
|
|
|
|
}
|
2021-11-01 04:17:10 -03:00
|
|
|
#endif
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
// handle IO MCU channels
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2022-08-25 02:36:10 -03:00
|
|
|
iomcu.write_channel(chan, period_us);
|
2018-01-05 04:55:01 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
|
|
|
if (chan < chan_offset) {
|
|
|
|
return;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-04-14 00:55:03 -03:00
|
|
|
if (safety_state == AP_HAL::Util::SAFETY_DISARMED && !(safety_mask & (1U<<chan))) {
|
|
|
|
// implement safety pwm value
|
2021-08-29 09:15:52 -03:00
|
|
|
period_us = 0;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
chan -= chan_offset;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
period[chan] = period_us;
|
2018-05-05 05:54:12 -03:00
|
|
|
|
|
|
|
if (chan < num_fmu_channels) {
|
|
|
|
active_fmu_channels = MAX(chan+1, active_fmu_channels);
|
|
|
|
if (!corked) {
|
|
|
|
push_local();
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
push values to local channels from period[] array
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::push_local(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (active_fmu_channels == 0) {
|
2018-01-05 02:19:51 -04:00
|
|
|
return;
|
|
|
|
}
|
2022-05-15 18:30:16 -03:00
|
|
|
uint32_t outmask = (1U<<active_fmu_channels)-1;
|
2018-01-06 05:42:47 -04:00
|
|
|
outmask &= en_mask;
|
2018-01-16 03:58:58 -04:00
|
|
|
|
|
|
|
uint16_t widest_pulse = 0;
|
|
|
|
uint8_t need_trigger = 0;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2021-01-02 16:43:40 -04:00
|
|
|
bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
for (auto &group : pwm_group_list) {
|
2022-08-25 02:36:10 -03:00
|
|
|
if (in_soft_serial()) {
|
2018-03-25 07:44:31 -03:00
|
|
|
continue;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
if (!group.pwm_started) {
|
|
|
|
continue;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
2018-03-14 03:06:30 -03:00
|
|
|
uint8_t chan = group.chan[j];
|
2021-04-03 19:00:38 -03:00
|
|
|
if (!group.is_chan_enabled(j)) {
|
2018-01-12 22:33:48 -04:00
|
|
|
continue;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
if (outmask & (1UL<<chan)) {
|
|
|
|
uint32_t period_us = period[chan];
|
2018-04-14 00:55:03 -03:00
|
|
|
|
|
|
|
if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
|
|
|
|
// safety is on, overwride pwm
|
2021-08-29 09:15:52 -03:00
|
|
|
period_us = 0;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-14 03:06:30 -03:00
|
|
|
if (group.current_mode == MODE_PWM_BRUSHED) {
|
2018-01-05 02:19:51 -04:00
|
|
|
if (period_us <= _esc_pwm_min) {
|
|
|
|
period_us = 0;
|
|
|
|
} else if (period_us >= _esc_pwm_max) {
|
2018-03-14 03:06:30 -03:00
|
|
|
period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv, 1, 1);
|
2018-01-05 02:19:51 -04:00
|
|
|
} else {
|
2018-03-14 03:06:30 -03:00
|
|
|
period_us = PWM_FRACTION_TO_WIDTH(group.pwm_drv,\
|
2018-01-05 02:19:51 -04:00
|
|
|
(_esc_pwm_max - _esc_pwm_min), (period_us - _esc_pwm_min));
|
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
pwmEnableChannel(group.pwm_drv, j, period_us);
|
2018-04-03 05:13:41 -03:00
|
|
|
} else if (group.current_mode == MODE_PWM_ONESHOT125) {
|
|
|
|
// this gives us a width in 125 ns increments, giving 1000 steps over the 125 to 250 range
|
|
|
|
uint32_t width = ((group.pwm_cfg.frequency/1000000U) * period_us) / 8U;
|
2019-09-22 05:31:16 -03:00
|
|
|
pwmEnableChannel(group.pwm_drv, j, width);
|
|
|
|
// scale the period down so we don't delay for longer than we need to
|
|
|
|
period_us /= 8;
|
2019-10-20 10:31:12 -03:00
|
|
|
}
|
2018-08-29 10:14:12 -03:00
|
|
|
else if (group.current_mode < MODE_PWM_DSHOT150) {
|
2018-03-16 18:49:40 -03:00
|
|
|
uint32_t width = (group.pwm_cfg.frequency/1000000U) * period_us;
|
2018-03-14 03:06:30 -03:00
|
|
|
pwmEnableChannel(group.pwm_drv, j, width);
|
2018-08-29 10:14:12 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2023-02-23 08:35:34 -04:00
|
|
|
else if (is_dshot_protocol(group.current_mode) || is_led_protocol(group.current_mode)) {
|
2018-03-14 03:06:30 -03:00
|
|
|
// set period_us to time for pulse output, to enable very fast rates
|
2020-10-12 16:57:29 -03:00
|
|
|
period_us = group.dshot_pulse_time_us;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2018-03-14 03:06:30 -03:00
|
|
|
if (group.current_mode == MODE_PWM_ONESHOT ||
|
2018-04-03 05:13:41 -03:00
|
|
|
group.current_mode == MODE_PWM_ONESHOT125 ||
|
2019-03-29 18:45:12 -03:00
|
|
|
group.current_mode == MODE_NEOPIXEL ||
|
2023-09-28 17:49:05 -03:00
|
|
|
group.current_mode == MODE_NEOPIXELRGB ||
|
2020-02-22 19:55:47 -04:00
|
|
|
group.current_mode == MODE_PROFILED ||
|
2019-03-29 18:45:12 -03:00
|
|
|
is_dshot_protocol(group.current_mode)) {
|
2021-06-30 16:42:50 -03:00
|
|
|
// only control widest pulse for oneshot and dshot
|
|
|
|
if (period_us > widest_pulse) {
|
|
|
|
widest_pulse = period_us;
|
|
|
|
}
|
2021-01-02 16:43:40 -04:00
|
|
|
const uint8_t i = &group - pwm_group_list;
|
2018-03-14 03:06:30 -03:00
|
|
|
need_trigger |= (1U<<i);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2018-01-16 03:58:58 -04:00
|
|
|
|
2018-01-17 06:25:02 -04:00
|
|
|
if (widest_pulse > 2300) {
|
|
|
|
widest_pulse = 2300;
|
|
|
|
}
|
2023-03-23 14:13:54 -03:00
|
|
|
trigger_widest_pulse = widest_pulse + 50;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
|
|
|
trigger_groupmask = need_trigger;
|
|
|
|
|
|
|
|
if (trigger_groupmask) {
|
|
|
|
trigger_groups();
|
2018-01-16 03:58:58 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint16_t RCOutput::read(uint8_t chan)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (chan >= max_channels) {
|
2018-01-12 04:29:16 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (chan < chan_offset) {
|
2022-08-25 02:36:10 -03:00
|
|
|
return iomcu.read_channel(chan);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
chan -= chan_offset;
|
|
|
|
return period[chan];
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (len > max_channels) {
|
|
|
|
len = max_channels;
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
for (uint8_t i=0; i<MIN(len, chan_offset); i++) {
|
|
|
|
period_us[i] = iomcu.read_channel(i);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
if (len <= chan_offset) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
len -= chan_offset;
|
|
|
|
period_us += chan_offset;
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
memcpy(period_us, period, len*sizeof(uint16_t));
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
uint16_t RCOutput::read_last_sent(uint8_t chan)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (chan >= max_channels) {
|
2018-01-12 04:29:16 -04:00
|
|
|
return 0;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
return last_sent[chan];
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::read_last_sent(uint16_t* period_us, uint8_t len)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-05-05 05:54:12 -03:00
|
|
|
if (len > max_channels) {
|
|
|
|
len = max_channels;
|
2018-01-12 04:29:16 -04:00
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i=0; i<len; i++) {
|
|
|
|
period_us[i] = read_last_sent(i);
|
|
|
|
}
|
|
|
|
}
|
2018-01-17 06:25:02 -04:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
does an output mode require the use of the UP DMA channel?
|
|
|
|
*/
|
|
|
|
bool RCOutput::mode_requires_dma(enum output_mode mode) const
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !HAL_DSHOT_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
return false;
|
2019-03-29 18:45:12 -03:00
|
|
|
#else
|
2023-02-23 08:35:34 -04:00
|
|
|
return is_dshot_protocol(mode) || is_led_protocol(mode);
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif //#if !HAL_DSHOT_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
2021-03-24 15:52:39 -03:00
|
|
|
void RCOutput::print_group_setup_error(pwm_group &group, const char* error_string)
|
|
|
|
{
|
|
|
|
#ifndef HAL_NO_UARTDRIVER
|
|
|
|
uint8_t min_chan = UINT8_MAX;
|
|
|
|
uint8_t max_chan = 0;
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
uint8_t chan = group.chan[j];
|
|
|
|
if (chan == CHAN_DISABLED) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
chan += chan_offset;
|
|
|
|
min_chan = MIN(min_chan,chan);
|
|
|
|
max_chan = MAX(max_chan,chan);
|
|
|
|
}
|
|
|
|
|
|
|
|
if (min_chan == max_chan) {
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Chan %i, %s: %s",min_chan+1,get_output_mode_string(group.current_mode),error_string);
|
|
|
|
} else {
|
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Chan %i to %i, %s: %s",min_chan+1,max_chan+1,get_output_mode_string(group.current_mode),error_string);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
setup a group for DMA output at a given bitrate. The bit_width is
|
|
|
|
the value for a pulse width in the DMA buffer for a full bit.
|
|
|
|
|
|
|
|
This is used for both DShot and serial output
|
|
|
|
*/
|
2022-02-10 10:42:33 -04:00
|
|
|
bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_width, bool active_high, const uint16_t buffer_length,
|
2023-03-23 14:13:54 -03:00
|
|
|
rcout_timer_t pulse_time_us, bool at_least_freq)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
// for dshot we setup for DMAR based output
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !AP_HAL_SHARED_DMA_ENABLED
|
|
|
|
if (group.dma == nullptr) {
|
|
|
|
// we don't do dma sharing in non advanced mode
|
|
|
|
chSysLock();
|
|
|
|
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_up_irq_callback, &group);
|
|
|
|
chSysUnlock();
|
|
|
|
if (group.dma == nullptr) {
|
|
|
|
print_group_setup_error(group, "failed to allocate DMA");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#else
|
2019-02-22 18:29:16 -04:00
|
|
|
if (!group.dma_handle) {
|
2018-03-16 18:49:40 -03:00
|
|
|
group.dma_handle = new Shared_DMA(group.dma_up_stream_id, SHARED_DMA_NONE,
|
|
|
|
FUNCTOR_BIND_MEMBER(&RCOutput::dma_allocate, void, Shared_DMA *),
|
|
|
|
FUNCTOR_BIND_MEMBER(&RCOutput::dma_deallocate, void, Shared_DMA *));
|
|
|
|
if (!group.dma_handle) {
|
2021-03-24 15:52:39 -03:00
|
|
|
print_group_setup_error(group, "failed to allocate DMA");
|
2018-03-16 18:49:40 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
// hold the lock during setup, to ensure there isn't a DMA operation ongoing
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
group.dma_handle->lock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-02-06 13:59:04 -04:00
|
|
|
if (!group.dma_buffer || buffer_length != group.dma_buffer_len) {
|
|
|
|
if (group.dma_buffer) {
|
|
|
|
hal.util->free_type(group.dma_buffer, group.dma_buffer_len, AP_HAL::Util::MEM_DMA_SAFE);
|
|
|
|
group.dma_buffer_len = 0;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
group.dma_buffer = (dmar_uint_t *)hal.util->malloc_type(buffer_length, AP_HAL::Util::MEM_DMA_SAFE);
|
2021-02-06 13:59:04 -04:00
|
|
|
if (!group.dma_buffer) {
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2021-02-06 13:59:04 -04:00
|
|
|
group.dma_handle->unlock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-03-24 15:52:39 -03:00
|
|
|
print_group_setup_error(group, "failed to allocate DMA buffer");
|
2021-02-06 13:59:04 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
group.dma_buffer_len = buffer_length;
|
|
|
|
}
|
|
|
|
// reset the pulse time inside the lock
|
2021-03-02 15:02:38 -04:00
|
|
|
group.dshot_pulse_time_us = group.dshot_pulse_send_time_us = pulse_time_us;
|
2021-02-06 13:59:04 -04:00
|
|
|
|
2020-10-12 16:57:29 -03:00
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
|
|
|
// configure input capture DMA if required
|
2023-11-16 12:27:16 -04:00
|
|
|
if (is_bidir_dshot_enabled(group)) {
|
2020-10-12 16:57:29 -03:00
|
|
|
if (!bdshot_setup_group_ic_DMA(group)) {
|
2023-11-16 12:27:16 -04:00
|
|
|
_bdshot.mask &= ~group.ch_mask; // only use dshot on this group
|
|
|
|
_bdshot.disabled_mask |= group.ch_mask;
|
|
|
|
active_high = true;
|
2020-10-12 16:57:29 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
// configure timer driver for DMAR at requested rate
|
|
|
|
if (group.pwm_started) {
|
|
|
|
pwmStop(group.pwm_drv);
|
|
|
|
group.pwm_started = false;
|
|
|
|
}
|
2021-03-02 15:02:38 -04:00
|
|
|
const uint32_t target_frequency = bitrate * bit_width;
|
2023-09-17 08:30:04 -03:00
|
|
|
|
|
|
|
const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_frequency, at_least_freq);
|
2022-08-25 02:36:10 -03:00
|
|
|
if (prescaler == 0 || prescaler > 0x8000) {
|
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2021-03-02 15:02:38 -04:00
|
|
|
group.dma_handle->unlock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-03-24 15:52:39 -03:00
|
|
|
print_group_setup_error(group, "failed to match clock speed");
|
2021-03-02 15:02:38 -04:00
|
|
|
return false;
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
const uint32_t freq = group.pwm_drv->clock / (prescaler + 1);
|
|
|
|
// PSC is calculated by ChibiOS as (pwm_drv.clock / pwm_cfg.frequency) - 1;
|
2018-03-16 18:49:40 -03:00
|
|
|
group.pwm_cfg.frequency = freq;
|
|
|
|
group.pwm_cfg.dier = TIM_DIER_UDE;
|
|
|
|
group.pwm_cfg.cr2 = 0;
|
|
|
|
group.bit_width_mul = (freq + (target_frequency/2)) / target_frequency;
|
2022-08-25 02:36:10 -03:00
|
|
|
// ARR is calculated by ChibiOS as pwm_cfg.period -1
|
|
|
|
group.pwm_cfg.period = bit_width * group.bit_width_mul;
|
2023-09-17 08:30:04 -03:00
|
|
|
#if 0
|
|
|
|
hal.console->printf("CLOCK=%u BW=%u FREQ=%u BR=%u MUL=%u PRE=%u\n", unsigned(group.pwm_drv->clock), unsigned(bit_width), unsigned(group.pwm_cfg.frequency),
|
|
|
|
unsigned(bitrate), unsigned(group.bit_width_mul), unsigned(prescaler));
|
|
|
|
static char clock_setup[64];
|
|
|
|
hal.util->snprintf(clock_setup, 64, "CLOCK=%u BW=%u FREQ=%u BR=%u MUL=%u PRE=%u\n", unsigned(group.pwm_drv->clock), unsigned(bit_width), unsigned(group.pwm_cfg.frequency),
|
|
|
|
unsigned(bitrate), unsigned(group.bit_width_mul), unsigned(prescaler));
|
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
for (uint8_t j=0; j<4; j++) {
|
2018-04-13 18:44:14 -03:00
|
|
|
pwmmode_t mode = group.pwm_cfg.channels[j].mode;
|
|
|
|
if (mode != PWM_OUTPUT_DISABLED) {
|
|
|
|
if(mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW || mode == PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH) {
|
2020-10-12 16:57:29 -03:00
|
|
|
group.pwm_cfg.channels[j].mode = active_high ? PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH : PWM_COMPLEMENTARY_OUTPUT_ACTIVE_LOW;
|
2018-04-13 18:44:14 -03:00
|
|
|
} else {
|
2020-10-12 16:57:29 -03:00
|
|
|
group.pwm_cfg.channels[j].mode = active_high ? PWM_OUTPUT_ACTIVE_HIGH : PWM_OUTPUT_ACTIVE_LOW;
|
2018-04-13 18:44:14 -03:00
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
pwmStart(group.pwm_drv, &group.pwm_cfg);
|
|
|
|
group.pwm_started = true;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
for (uint8_t j=0; j<4; j++) {
|
2021-04-03 19:00:38 -03:00
|
|
|
if (group.is_chan_enabled(j)) {
|
2018-03-16 18:49:40 -03:00
|
|
|
pwmEnableChannel(group.pwm_drv, j, 0);
|
|
|
|
}
|
|
|
|
}
|
2020-10-12 16:57:29 -03:00
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
group.dma_handle->unlock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
return true;
|
2018-08-29 10:14:12 -03:00
|
|
|
#else
|
|
|
|
return false;
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2019-10-20 10:31:12 -03:00
|
|
|
setup output mode for a group, using group.current_mode. Used to restore output
|
2018-03-16 18:49:40 -03:00
|
|
|
after serial operations
|
|
|
|
*/
|
|
|
|
void RCOutput::set_group_mode(pwm_group &group)
|
|
|
|
{
|
|
|
|
if (group.pwm_started) {
|
|
|
|
pwmStop(group.pwm_drv);
|
|
|
|
group.pwm_started = false;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
2020-10-12 16:57:29 -03:00
|
|
|
memset(group.bdshot.erpm, 0, 4*sizeof(uint16_t));
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
switch (group.current_mode) {
|
|
|
|
case MODE_PWM_BRUSHED:
|
|
|
|
// force zero output initially
|
|
|
|
for (uint8_t i=0; i<4; i++) {
|
|
|
|
if (group.chan[i] == CHAN_DISABLED) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
uint8_t chan = chan_offset + group.chan[i];
|
|
|
|
write(chan, 0);
|
|
|
|
}
|
|
|
|
break;
|
2018-08-29 10:14:12 -03:00
|
|
|
|
2019-03-29 18:45:12 -03:00
|
|
|
case MODE_NEOPIXEL:
|
2023-09-28 17:49:05 -03:00
|
|
|
case MODE_NEOPIXELRGB:
|
2020-02-22 19:55:47 -04:00
|
|
|
case MODE_PROFILED:
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIALLED_ENABLED
|
2019-03-29 18:45:12 -03:00
|
|
|
{
|
2020-02-22 19:55:47 -04:00
|
|
|
uint8_t bits_per_pixel = 24;
|
2023-11-11 17:54:15 -04:00
|
|
|
uint32_t bit_width = NEOP_BIT_WIDTH_TICKS;
|
2020-02-22 19:55:47 -04:00
|
|
|
bool active_high = true;
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
if (!start_led_thread()) {
|
|
|
|
group.current_mode = MODE_PWM_NONE;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2020-02-22 19:55:47 -04:00
|
|
|
if (group.current_mode == MODE_PROFILED) {
|
|
|
|
bits_per_pixel = 25;
|
2023-11-11 17:54:15 -04:00
|
|
|
bit_width = PROFI_BIT_WIDTH_TICKS;
|
2020-02-22 19:55:47 -04:00
|
|
|
active_high = false;
|
|
|
|
}
|
|
|
|
|
2019-03-29 18:45:12 -03:00
|
|
|
const uint32_t rate = protocol_bitrate(group.current_mode);
|
|
|
|
|
|
|
|
// configure timer driver for DMAR at requested rate
|
2019-10-09 18:05:40 -03:00
|
|
|
const uint8_t pad_end_bits = 8;
|
|
|
|
const uint8_t pad_start_bits = 1;
|
2019-09-09 06:23:47 -03:00
|
|
|
const uint8_t channels_per_group = 4;
|
2021-02-06 13:59:04 -04:00
|
|
|
const uint16_t bit_length = bits_per_pixel * group.serial_nleds + pad_start_bits + pad_end_bits;
|
|
|
|
const uint16_t buffer_length = bit_length * sizeof(uint32_t) * channels_per_group;
|
|
|
|
// calculate min time between pulses taking into account the DMAR parallelism
|
|
|
|
const uint32_t pulse_time_us = 1000000UL * bit_length / rate;
|
2021-01-16 05:05:09 -04:00
|
|
|
|
2023-11-11 17:54:15 -04:00
|
|
|
if (!setup_group_DMA(group, rate, bit_width, active_high, buffer_length, pulse_time_us, false)) {
|
2019-03-29 18:45:12 -03:00
|
|
|
group.current_mode = MODE_PWM_NONE;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2019-03-29 18:45:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: {
|
2023-09-17 08:30:04 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2019-03-29 18:45:12 -03:00
|
|
|
const uint32_t rate = protocol_bitrate(group.current_mode);
|
2023-11-16 12:27:16 -04:00
|
|
|
bool active_high = is_bidir_dshot_enabled(group) ? false : true;
|
2023-09-17 08:30:04 -03:00
|
|
|
bool at_least_freq = false;
|
2021-02-06 13:59:04 -04:00
|
|
|
// calculate min time between pulses
|
|
|
|
const uint32_t pulse_send_time_us = 1000000UL * dshot_bit_length / rate;
|
2018-08-04 05:30:02 -03:00
|
|
|
|
2023-09-17 08:30:04 -03:00
|
|
|
// BLHeli_S (and BlueJay) appears to always want the frequency above the target
|
|
|
|
if (_dshot_esc_type == DSHOT_ESC_BLHELI_S || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S) {
|
|
|
|
at_least_freq = true;
|
|
|
|
}
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// configure timer driver for DMAR at requested rate
|
2022-03-08 14:03:55 -04:00
|
|
|
if (!setup_group_DMA(group, rate, DSHOT_BIT_WIDTH_TICKS, active_high,
|
2023-09-17 08:30:04 -03:00
|
|
|
MAX(DSHOT_BUFFER_LENGTH, GCR_TELEMETRY_BUFFER_LEN), pulse_send_time_us, at_least_freq)) {
|
2020-02-07 23:35:42 -04:00
|
|
|
group.current_mode = MODE_PWM_NORMAL;
|
2018-03-16 18:49:40 -03:00
|
|
|
break;
|
|
|
|
}
|
2023-11-16 12:27:16 -04:00
|
|
|
if (is_bidir_dshot_enabled(group)) {
|
2021-02-06 13:59:04 -04:00
|
|
|
group.dshot_pulse_send_time_us = pulse_send_time_us;
|
2020-10-12 16:57:29 -03:00
|
|
|
// to all intents and purposes the pulse time of send and receive are the same
|
2021-02-06 13:59:04 -04:00
|
|
|
group.dshot_pulse_time_us = pulse_send_time_us + pulse_send_time_us + 30;
|
2020-10-12 16:57:29 -03:00
|
|
|
}
|
2023-09-17 08:30:04 -03:00
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
break;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
case MODE_PWM_ONESHOT:
|
2018-04-03 05:13:41 -03:00
|
|
|
case MODE_PWM_ONESHOT125:
|
|
|
|
// for oneshot we set a period of 0, which results in no pulses till we trigger
|
|
|
|
group.pwm_cfg.period = 0;
|
2018-03-31 18:55:01 -03:00
|
|
|
group.rc_frequency = 1;
|
2018-03-26 18:11:10 -03:00
|
|
|
if (group.pwm_started) {
|
|
|
|
pwmChangePeriod(group.pwm_drv, group.pwm_cfg.period);
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MODE_PWM_NORMAL:
|
|
|
|
case MODE_PWM_NONE:
|
|
|
|
// nothing needed
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2018-04-03 05:13:41 -03:00
|
|
|
set_freq_group(group);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
if (group.current_mode != MODE_PWM_NONE &&
|
|
|
|
!group.pwm_started) {
|
|
|
|
pwmStart(group.pwm_drv, &group.pwm_cfg);
|
|
|
|
group.pwm_started = true;
|
|
|
|
for (uint8_t j=0; j<4; j++) {
|
2021-04-03 19:00:38 -03:00
|
|
|
if (group.is_chan_enabled(j)) {
|
2018-03-16 18:49:40 -03:00
|
|
|
pwmEnableChannel(group.pwm_drv, j, 0);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
setup output mode
|
|
|
|
*/
|
2021-01-11 22:01:48 -04:00
|
|
|
void RCOutput::set_output_mode(uint32_t mask, const enum output_mode mode)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2020-02-07 23:35:42 -04:00
|
|
|
enum output_mode thismode = mode;
|
2018-03-14 03:06:30 -03:00
|
|
|
if (((group.ch_mask << chan_offset) & mask) == 0) {
|
|
|
|
// this group is not affected
|
|
|
|
continue;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2020-02-07 23:35:42 -04:00
|
|
|
if (mode_requires_dma(thismode) && !group.have_up_dma) {
|
2021-03-24 15:52:39 -03:00
|
|
|
print_group_setup_error(group, "failed, no DMA");
|
2020-02-07 23:35:42 -04:00
|
|
|
thismode = MODE_PWM_NORMAL;
|
2018-01-16 03:58:58 -04:00
|
|
|
}
|
2018-05-20 21:20:46 -03:00
|
|
|
if (mode > MODE_PWM_NORMAL) {
|
|
|
|
fast_channel_mask |= group.ch_mask;
|
|
|
|
}
|
2021-02-06 13:59:04 -04:00
|
|
|
// setup of the group mode also sets up DMA which might have changed, so always
|
|
|
|
// redo it if using DMA
|
2020-02-07 23:35:42 -04:00
|
|
|
if (group.current_mode != thismode) {
|
|
|
|
group.current_mode = thismode;
|
2018-04-03 05:13:41 -03:00
|
|
|
set_group_mode(group);
|
|
|
|
}
|
2018-01-16 03:58:58 -04:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
2023-09-24 10:09:23 -03:00
|
|
|
const uint16_t iomcu_mask = (mask & ((1U<<chan_offset)-1));
|
2018-04-03 05:13:41 -03:00
|
|
|
if ((mode == MODE_PWM_ONESHOT ||
|
2022-08-25 02:36:10 -03:00
|
|
|
mode == MODE_PWM_ONESHOT125 ||
|
|
|
|
mode == MODE_PWM_BRUSHED ||
|
|
|
|
(mode >= MODE_PWM_DSHOT150 && mode <= MODE_PWM_DSHOT600)) &&
|
2023-09-24 10:09:23 -03:00
|
|
|
iomcu_mask &&
|
2023-10-19 12:22:08 -03:00
|
|
|
iomcu_enabled) {
|
2023-09-24 10:09:23 -03:00
|
|
|
iomcu.set_output_mode(iomcu_mask, mode);
|
2020-01-28 04:28:36 -04:00
|
|
|
return;
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2023-06-21 18:43:21 -03:00
|
|
|
/*
|
|
|
|
Get current non-PWM output mode for all channels
|
|
|
|
*/
|
|
|
|
RCOutput::output_mode RCOutput::get_output_mode(uint32_t& mask)
|
|
|
|
{
|
|
|
|
enum output_mode mode = MODE_PWM_NONE;
|
|
|
|
|
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
if (group.current_mode == MODE_PWM_NONE) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (group.current_mode != MODE_PWM_NORMAL) {
|
|
|
|
mode = group.current_mode;
|
|
|
|
mask |= group.en_mask;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return mode;
|
|
|
|
}
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
/*
|
|
|
|
enable telemetry request for a mask of channels. This is used
|
|
|
|
with DShot to get telemetry feedback
|
|
|
|
The mask uses servo channel numbering
|
|
|
|
*/
|
|
|
|
void RCOutput::set_telem_request_mask(uint32_t mask)
|
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_dshot && (mask & ((1U<<chan_offset)-1))) {
|
2022-08-25 02:36:10 -03:00
|
|
|
iomcu.set_telem_request_mask(mask);
|
2018-07-12 23:29:02 -03:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
#endif
|
2022-08-25 02:36:10 -03:00
|
|
|
telem_request_mask = (mask >> chan_offset);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2020-01-28 04:28:36 -04:00
|
|
|
/*
|
|
|
|
* get output mode banner to inform user of how outputs are configured
|
|
|
|
*/
|
|
|
|
bool RCOutput::get_output_mode_banner(char banner_msg[], uint8_t banner_msg_len) const
|
|
|
|
{
|
2021-08-09 17:36:09 -03:00
|
|
|
if (!hal.scheduler->is_system_initialized()) {
|
|
|
|
hal.util->snprintf(banner_msg, banner_msg_len, "RCOut: Initialising");
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2020-01-28 04:28:36 -04:00
|
|
|
// create array of each channel's mode
|
|
|
|
output_mode ch_mode[chan_offset + NUM_GROUPS * ARRAY_SIZE(pwm_group::chan)] = {};
|
|
|
|
bool have_nonzero_modes = false;
|
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
// fill in ch_mode array for IOMCU channels
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2023-06-21 18:43:21 -03:00
|
|
|
uint8_t iomcu_mask;
|
|
|
|
const output_mode iomcu_mode = iomcu.get_output_mode(iomcu_mask);
|
2020-01-28 04:28:36 -04:00
|
|
|
for (uint8_t i = 0; i < chan_offset; i++ ) {
|
2023-06-21 18:43:21 -03:00
|
|
|
if (iomcu_mask & 1U<<i) {
|
|
|
|
ch_mode[i] = iomcu_mode;
|
|
|
|
} else {
|
|
|
|
ch_mode[i] = MODE_PWM_NORMAL;
|
|
|
|
}
|
2020-01-28 04:28:36 -04:00
|
|
|
}
|
|
|
|
have_nonzero_modes = (chan_offset > 0) && (iomcu_mode != MODE_PWM_NONE);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
// fill in ch_mode array for FMU channels
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2020-01-28 04:28:36 -04:00
|
|
|
if (group.current_mode != MODE_PWM_NONE) {
|
|
|
|
for (uint8_t j = 0; j < ARRAY_SIZE(group.chan); j++) {
|
|
|
|
if (group.chan[j] != CHAN_DISABLED) {
|
|
|
|
const uint8_t chan_num = group.chan[j] + chan_offset;
|
|
|
|
if (chan_num < ARRAY_SIZE(ch_mode)) {
|
|
|
|
ch_mode[chan_num] = group.current_mode;
|
|
|
|
have_nonzero_modes = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// handle simple case
|
|
|
|
if (!have_nonzero_modes) {
|
|
|
|
hal.util->snprintf(banner_msg, banner_msg_len, "RCOut: None");
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// write banner to banner_msg
|
|
|
|
hal.util->snprintf(banner_msg, banner_msg_len, "RCOut:");
|
|
|
|
uint8_t curr_mode_lowest_ch = 0;
|
|
|
|
for (uint8_t k = 1; k < ARRAY_SIZE(ch_mode); k++) {
|
|
|
|
if (ch_mode[k-1] != ch_mode[k]) {
|
|
|
|
if (ch_mode[k-1] != MODE_PWM_NONE) {
|
|
|
|
append_to_banner(banner_msg, banner_msg_len, ch_mode[k-1], curr_mode_lowest_ch + 1, k);
|
|
|
|
}
|
|
|
|
curr_mode_lowest_ch = k;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// add final few channel's mode to banner (won't have been done by above loop)
|
|
|
|
const uint8_t final_index = ARRAY_SIZE(ch_mode)-1;
|
|
|
|
if (ch_mode[final_index] != MODE_PWM_NONE) {
|
|
|
|
append_to_banner(banner_msg, banner_msg_len, ch_mode[final_index], curr_mode_lowest_ch + 1, final_index + 1);
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
start corking output
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::cork(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
corked = true;
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-01-05 04:55:01 -04:00
|
|
|
iomcu.cork();
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
stop corking output
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void RCOutput::push(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
corked = false;
|
|
|
|
push_local();
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-01-05 04:55:01 -04:00
|
|
|
iomcu.push();
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
enable sbus output
|
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
bool RCOutput::enable_px4io_sbus_out(uint16_t rate_hz)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-01-05 04:55:01 -04:00
|
|
|
return iomcu.enable_sbus_out(rate_hz);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
2018-01-05 04:55:01 -04:00
|
|
|
return false;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-17 06:25:02 -04:00
|
|
|
|
|
|
|
/*
|
2018-03-14 03:06:30 -03:00
|
|
|
trigger output groups for oneshot or dshot modes
|
2018-01-17 06:25:02 -04:00
|
|
|
*/
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::trigger_groups()
|
2018-01-17 06:25:02 -04:00
|
|
|
{
|
|
|
|
if (!chMtxTryLock(&trigger_mutex)) {
|
|
|
|
return;
|
|
|
|
}
|
2023-03-23 14:13:54 -03:00
|
|
|
|
|
|
|
rcout_timer_t now = rcout_micros();
|
|
|
|
|
|
|
|
if (!AP_HAL::timeout_expired(last_pulse_trigger_us, now, trigger_widest_pulse)) {
|
2018-01-17 06:25:02 -04:00
|
|
|
// guarantee minimum pulse separation
|
2023-03-23 14:13:54 -03:00
|
|
|
hal.scheduler->delay_microseconds(AP_HAL::timeout_remaining(last_pulse_trigger_us, now, trigger_widest_pulse));
|
2018-01-17 06:25:02 -04:00
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2018-01-17 06:25:02 -04:00
|
|
|
osalSysLock();
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2022-08-25 02:36:10 -03:00
|
|
|
if (soft_serial_waiting()) {
|
2018-03-16 18:49:40 -03:00
|
|
|
// doing serial output, don't send pulses
|
|
|
|
continue;
|
|
|
|
}
|
2018-04-03 05:13:41 -03:00
|
|
|
if (group.current_mode == MODE_PWM_ONESHOT ||
|
|
|
|
group.current_mode == MODE_PWM_ONESHOT125) {
|
2021-01-02 16:43:40 -04:00
|
|
|
const uint8_t i = &group - pwm_group_list;
|
2018-03-14 03:06:30 -03:00
|
|
|
if (trigger_groupmask & (1U<<i)) {
|
|
|
|
// this triggers pulse output for a channel group
|
|
|
|
group.pwm_drv->tim->EGR = STM32_TIM_EGR_UG;
|
|
|
|
}
|
2018-01-17 06:25:02 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
osalSysUnlock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !defined(HAL_NO_RCOUT_THREAD) || HAL_DSHOT_ENABLED
|
2020-12-05 15:16:27 -04:00
|
|
|
// trigger a PWM send
|
2022-08-25 02:36:10 -03:00
|
|
|
if (!in_soft_serial() && hal.scheduler->in_main_thread() && rcout_thread_ctx) {
|
2020-12-05 15:16:27 -04:00
|
|
|
chEvtSignal(rcout_thread_ctx, EVT_PWM_SEND);
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
2021-02-23 11:04:25 -04:00
|
|
|
#endif
|
2018-01-17 06:25:02 -04:00
|
|
|
/*
|
|
|
|
calculate time that we are allowed to trigger next pulse
|
|
|
|
to guarantee at least a 50us gap between pulses
|
|
|
|
*/
|
2023-03-23 14:13:54 -03:00
|
|
|
last_pulse_trigger_us = rcout_micros();
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-01-17 06:25:02 -04:00
|
|
|
chMtxUnlock(&trigger_mutex);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2018-04-14 00:55:03 -03:00
|
|
|
periodic timer. This is used for oneshot and dshot modes, plus for
|
2020-10-12 16:57:29 -03:00
|
|
|
safety switch update. Runs every 1000us.
|
2018-01-17 06:25:02 -04:00
|
|
|
*/
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::timer_tick(rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us)
|
2018-01-17 06:25:02 -04:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
if (in_soft_serial()) {
|
2021-01-16 05:05:09 -04:00
|
|
|
return;
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2020-10-12 16:57:29 -03:00
|
|
|
|
2023-03-23 14:13:54 -03:00
|
|
|
if (last_pulse_trigger_us == 0) {
|
2018-01-17 06:25:02 -04:00
|
|
|
return;
|
|
|
|
}
|
2021-03-31 18:57:53 -03:00
|
|
|
|
2023-03-23 14:13:54 -03:00
|
|
|
if (AP_HAL::timeout_expired(last_pulse_trigger_us, rcout_micros(), trigger_widest_pulse + 4000U)) {
|
2018-04-03 05:13:41 -03:00
|
|
|
// trigger at a minimum of 250Hz
|
2018-03-14 03:06:30 -03:00
|
|
|
trigger_groups();
|
2018-04-03 05:13:41 -03:00
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
/*
|
|
|
|
periodic timer called from led thread. This is used for LED output
|
|
|
|
*/
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::led_timer_tick(rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us)
|
2023-02-23 08:35:34 -04:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
if (in_soft_serial()) {
|
2023-02-23 08:35:34 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// if we have enough time left send out LED data
|
2023-05-16 16:09:52 -03:00
|
|
|
if (serial_led_pending) {
|
2023-02-23 08:35:34 -04:00
|
|
|
serial_led_pending = false;
|
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
serial_led_pending |= !serial_led_send(group);
|
|
|
|
}
|
|
|
|
|
|
|
|
// release locks on the groups that are pending in reverse order
|
2023-03-23 14:13:54 -03:00
|
|
|
dshot_collect_dma_locks(cycle_start_us, timeout_period_us, true);
|
2023-02-23 08:35:34 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// send dshot for all groups that support it
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::dshot_send_groups(rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us)
|
2020-12-05 15:16:27 -04:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
|
|
|
if (in_soft_serial()) {
|
2020-12-05 15:16:27 -04:00
|
|
|
return;
|
|
|
|
}
|
2021-04-03 19:00:38 -03:00
|
|
|
|
2021-05-02 14:35:19 -03:00
|
|
|
bool command_sent = false;
|
|
|
|
// queue up a command if there is one
|
2021-07-29 17:46:15 -03:00
|
|
|
if (_dshot_current_command.cycle == 0
|
2021-05-02 14:35:19 -03:00
|
|
|
&& _dshot_command_queue.pop(_dshot_current_command)) {
|
|
|
|
// got a new command
|
|
|
|
}
|
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2023-09-24 10:09:23 -03:00
|
|
|
bool pulse_sent;
|
2021-04-03 19:00:38 -03:00
|
|
|
// send a dshot command
|
2021-07-29 17:46:15 -03:00
|
|
|
if (is_dshot_protocol(group.current_mode)
|
2021-05-02 14:35:19 -03:00
|
|
|
&& dshot_command_is_active(group)) {
|
|
|
|
command_sent = dshot_send_command(group, _dshot_current_command.command, _dshot_current_command.chan);
|
2023-09-24 10:09:23 -03:00
|
|
|
pulse_sent = true;
|
2021-04-03 19:00:38 -03:00
|
|
|
// actually do a dshot send
|
|
|
|
} else if (group.can_send_dshot_pulse()) {
|
2023-03-23 14:13:54 -03:00
|
|
|
dshot_send(group, cycle_start_us, timeout_period_us);
|
2023-09-24 10:09:23 -03:00
|
|
|
pulse_sent = true;
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
2023-10-19 12:22:08 -03:00
|
|
|
#if defined(HAL_WITH_BIDIR_DSHOT) && defined(HAL_TIM_UP_SHARED)
|
2023-09-24 10:09:23 -03:00
|
|
|
// prevent the next send going out until the previous send has released its DMA channel
|
|
|
|
if (pulse_sent && group.shared_up_dma && group.bdshot.enabled) {
|
2023-03-23 14:13:54 -03:00
|
|
|
chEvtWaitOneTimeout(DSHOT_CASCADE, calc_ticks_remaining(group, cycle_start_us, timeout_period_us, _dshot_period_us));
|
2023-09-24 10:09:23 -03:00
|
|
|
}
|
|
|
|
#else
|
|
|
|
(void)pulse_sent;
|
|
|
|
#endif
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
2021-05-02 14:35:19 -03:00
|
|
|
|
|
|
|
if (command_sent) {
|
|
|
|
_dshot_current_command.cycle--;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2020-12-05 15:16:27 -04:00
|
|
|
}
|
|
|
|
|
2021-09-04 08:59:15 -03:00
|
|
|
__RAMFUNC__ void RCOutput::dshot_send_next_group(void* p)
|
2021-03-17 18:02:18 -03:00
|
|
|
{
|
|
|
|
chSysLockFromISR();
|
|
|
|
RCOutput* rcout = (RCOutput*)p;
|
|
|
|
|
|
|
|
chEvtSignalI(rcout->rcout_thread_ctx, EVT_PWM_SEND_NEXT);
|
|
|
|
chSysUnlockFromISR();
|
|
|
|
}
|
|
|
|
|
2018-03-14 03:06:30 -03:00
|
|
|
/*
|
|
|
|
allocate DMA channel
|
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2018-03-14 03:06:30 -03:00
|
|
|
void RCOutput::dma_allocate(Shared_DMA *ctx)
|
|
|
|
{
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2019-02-10 03:31:19 -04:00
|
|
|
if (group.dma_handle == ctx && group.dma == nullptr) {
|
2023-10-19 12:22:08 -03:00
|
|
|
chSysLock();
|
2020-10-12 16:57:29 -03:00
|
|
|
group.dma = dmaStreamAllocI(group.dma_up_stream_id, 10, dma_up_irq_callback, &group);
|
2023-09-24 10:09:23 -03:00
|
|
|
#if defined(STM32F1)
|
|
|
|
if (group.pwm_started && group.dma_handle->is_shared()) {
|
|
|
|
/* Timer configured and started.*/
|
|
|
|
group.pwm_drv->tim->CR1 = STM32_TIM_CR1_ARPE | STM32_TIM_CR1_URS | STM32_TIM_CR1_CEN;
|
|
|
|
group.pwm_drv->tim->DIER = group.pwm_drv->config->dier & ~STM32_TIM_DIER_IRQ_MASK;
|
2023-06-01 12:07:26 -03:00
|
|
|
}
|
|
|
|
#endif
|
2019-02-13 16:10:55 -04:00
|
|
|
#if STM32_DMA_SUPPORTS_DMAMUX
|
2019-02-22 18:29:16 -04:00
|
|
|
if (group.dma) {
|
|
|
|
dmaSetRequestSource(group.dma, group.dma_up_channel);
|
|
|
|
}
|
2019-02-13 16:10:55 -04:00
|
|
|
#endif
|
2023-10-19 12:22:08 -03:00
|
|
|
chSysUnlock();
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2018-01-17 06:25:02 -04:00
|
|
|
}
|
|
|
|
}
|
2018-03-01 20:46:30 -04:00
|
|
|
|
2018-03-14 03:06:30 -03:00
|
|
|
/*
|
|
|
|
deallocate DMA channel
|
|
|
|
*/
|
|
|
|
void RCOutput::dma_deallocate(Shared_DMA *ctx)
|
|
|
|
{
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2019-02-22 18:29:16 -04:00
|
|
|
if (group.dma_handle == ctx && group.dma != nullptr) {
|
2023-10-19 12:22:08 -03:00
|
|
|
chSysLock();
|
2023-09-24 10:09:23 -03:00
|
|
|
#if defined(STM32F1)
|
2023-06-01 12:07:26 -03:00
|
|
|
// leaving the peripheral running on IOMCU plays havoc with the UART that is
|
2023-09-24 10:09:23 -03:00
|
|
|
// also sharing this channel, we only turn it off rather than resetting so
|
|
|
|
// that we don't have to worry about line modes etc
|
|
|
|
if (group.pwm_started && group.dma_handle->is_shared()) {
|
|
|
|
group.pwm_drv->tim->CR1 = 0;
|
|
|
|
group.pwm_drv->tim->DIER = 0;
|
2023-06-01 12:07:26 -03:00
|
|
|
}
|
|
|
|
#endif
|
2019-02-01 21:47:46 -04:00
|
|
|
dmaStreamFreeI(group.dma);
|
|
|
|
group.dma = nullptr;
|
2023-10-19 12:22:08 -03:00
|
|
|
chSysUnlock();
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // AP_HAL_SHARED_DMA_ENABLED
|
2018-03-14 03:06:30 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
create a DSHOT 16 bit packet. Based on prepareDshotPacket from betaflight
|
|
|
|
*/
|
2020-10-12 16:57:29 -03:00
|
|
|
uint16_t RCOutput::create_dshot_packet(const uint16_t value, bool telem_request, bool bidir_telem)
|
2018-03-14 03:06:30 -03:00
|
|
|
{
|
2018-04-02 01:20:58 -03:00
|
|
|
uint16_t packet = (value << 1);
|
|
|
|
|
|
|
|
if (telem_request) {
|
|
|
|
packet |= 1;
|
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
|
|
|
|
// compute checksum
|
|
|
|
uint16_t csum = 0;
|
|
|
|
uint16_t csum_data = packet;
|
|
|
|
for (uint8_t i = 0; i < 3; i++) {
|
|
|
|
csum ^= csum_data;
|
|
|
|
csum_data >>= 4;
|
|
|
|
}
|
2020-10-12 16:57:29 -03:00
|
|
|
// trigger bi-dir dshot telemetry
|
|
|
|
if (bidir_telem) {
|
|
|
|
csum = ~csum;
|
|
|
|
}
|
|
|
|
|
2018-03-14 03:06:30 -03:00
|
|
|
// append checksum
|
2020-10-12 16:57:29 -03:00
|
|
|
csum &= 0xf;
|
2018-03-14 03:06:30 -03:00
|
|
|
packet = (packet << 4) | csum;
|
|
|
|
|
|
|
|
return packet;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
fill in a DMA buffer for dshot
|
2022-08-25 02:36:10 -03:00
|
|
|
the buffer format is (stride is always 4 for 4 channels):
|
|
|
|
[ch0b0][ch1b0][ch2b0][ch3b0][ch0b1][ch1b1][ch2b1][ch3b1]...[ch0bN][ch1bN][ch2bN][ch3bN]
|
|
|
|
where N = dshot_bit_length - 1
|
|
|
|
each value is a number of beats for the DMA engine to send in burst via DMAR to the 4 CCR registers
|
2018-03-14 03:06:30 -03:00
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
void RCOutput::fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul)
|
2018-03-14 03:06:30 -03:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
const dmar_uint_t DSHOT_MOTOR_BIT_0 = DSHOT_BIT_0_TICKS * clockmul;
|
|
|
|
const dmar_uint_t DSHOT_MOTOR_BIT_1 = DSHOT_BIT_1_TICKS * clockmul;
|
2018-08-04 05:30:02 -03:00
|
|
|
uint16_t i = 0;
|
|
|
|
for (; i < dshot_pre; i++) {
|
|
|
|
buffer[i * stride] = 0;
|
|
|
|
}
|
|
|
|
for (; i < 16 + dshot_pre; i++) {
|
2018-03-14 03:06:30 -03:00
|
|
|
buffer[i * stride] = (packet & 0x8000) ? DSHOT_MOTOR_BIT_1 : DSHOT_MOTOR_BIT_0;
|
|
|
|
packet <<= 1;
|
|
|
|
}
|
2018-08-04 05:30:02 -03:00
|
|
|
for (; i<dshot_bit_length; i++) {
|
|
|
|
buffer[i * stride] = 0;
|
|
|
|
}
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
send a set of DShot packets for a channel group
|
|
|
|
This call be called in blocking mode from the timer, in which case it waits for the DMA lock.
|
|
|
|
In normal operation it doesn't wait for the DMA lock.
|
|
|
|
*/
|
2023-03-23 14:13:54 -03:00
|
|
|
void RCOutput::dshot_send(pwm_group &group, rcout_timer_t cycle_start_us, rcout_timer_t timeout_period_us)
|
2018-03-14 03:06:30 -03:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2023-09-24 10:09:23 -03:00
|
|
|
if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state)) {
|
2020-10-12 16:57:29 -03:00
|
|
|
// doing serial output or DMAR input, don't send DShot pulses
|
2018-03-16 18:49:40 -03:00
|
|
|
return;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2020-10-12 16:57:29 -03:00
|
|
|
// first make sure we have the DMA channel before anything else
|
2020-12-05 15:16:27 -04:00
|
|
|
osalDbgAssert(!group.dma_handle->is_locked(), "DMA handle is already locked");
|
|
|
|
group.dma_handle->lock();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-03-02 15:02:38 -04:00
|
|
|
// if we are sharing UP channels then it might have taken a long time to get here,
|
|
|
|
// if there's not enough time to actually send a pulse then cancel
|
2022-08-25 02:36:10 -03:00
|
|
|
#if AP_HAL_SHARED_DMA_ENABLED
|
2023-03-23 14:13:54 -03:00
|
|
|
if (AP_HAL::timeout_remaining(cycle_start_us, rcout_micros(), timeout_period_us) < group.dshot_pulse_time_us) {
|
2021-03-02 15:02:38 -04:00
|
|
|
group.dma_handle->unlock();
|
|
|
|
return;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-03-02 15:02:38 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// only the timer thread releases the locks
|
|
|
|
group.dshot_waiter = rcout_thread_ctx;
|
2020-10-12 16:57:29 -03:00
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
2023-10-19 09:37:43 -03:00
|
|
|
bdshot_prepare_for_next_pulse(group);
|
2020-10-12 16:57:29 -03:00
|
|
|
#endif
|
2018-04-14 00:55:03 -03:00
|
|
|
bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !defined(IOMCU_FW)
|
2021-07-01 18:50:40 -03:00
|
|
|
bool armed = hal.util->get_soft_armed();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2020-10-12 16:57:29 -03:00
|
|
|
memset((uint8_t *)group.dma_buffer, 0, DSHOT_BUFFER_LENGTH);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-14 03:06:30 -03:00
|
|
|
for (uint8_t i=0; i<4; i++) {
|
|
|
|
uint8_t chan = group.chan[i];
|
2021-04-03 19:00:38 -03:00
|
|
|
if (group.is_chan_enabled(i)) {
|
2021-03-01 16:40:39 -04:00
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
2023-05-29 16:45:47 -03:00
|
|
|
if (group.bdshot.enabled) {
|
|
|
|
bdshot_decode_telemetry_from_erpm(group.bdshot.erpm[i], chan);
|
2021-03-01 16:40:39 -04:00
|
|
|
}
|
|
|
|
#endif
|
2018-04-14 00:55:03 -03:00
|
|
|
if (safety_on && !(safety_mask & (1U<<(chan+chan_offset)))) {
|
2022-03-25 05:09:20 -03:00
|
|
|
// safety is on, don't output anything
|
|
|
|
continue;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2022-03-25 05:09:20 -03:00
|
|
|
uint16_t pwm = period[chan];
|
|
|
|
|
2018-11-09 06:25:58 -04:00
|
|
|
if (pwm == 0) {
|
2022-03-25 05:09:20 -03:00
|
|
|
// no pwm, don't output anything
|
2018-11-09 06:25:58 -04:00
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
2022-05-15 18:30:16 -03:00
|
|
|
const uint32_t chan_mask = (1U<<chan);
|
2022-03-25 05:09:20 -03:00
|
|
|
|
2018-11-09 06:25:58 -04:00
|
|
|
pwm = constrain_int16(pwm, 1000, 2000);
|
2021-10-03 13:44:15 -03:00
|
|
|
uint16_t value = MIN(2 * (pwm - 1000), 1999);
|
2018-11-09 06:25:58 -04:00
|
|
|
|
2022-03-22 08:05:22 -03:00
|
|
|
if ((chan_mask & _reversible_mask) != 0) {
|
2018-11-09 06:25:58 -04:00
|
|
|
// this is a DShot-3D output, map so that 1500 PWM is zero throttle reversed
|
|
|
|
if (value < 1000) {
|
2021-10-20 18:41:55 -03:00
|
|
|
value = 1999 - value;
|
2018-11-09 06:25:58 -04:00
|
|
|
} else if (value > 1000) {
|
|
|
|
value = value - 1000;
|
|
|
|
} else {
|
|
|
|
// mid-throttle is off
|
|
|
|
value = 0;
|
|
|
|
}
|
|
|
|
}
|
2021-07-29 17:46:15 -03:00
|
|
|
|
|
|
|
// dshot values are from 48 to 2047. 48 means off.
|
2018-03-14 03:06:30 -03:00
|
|
|
if (value != 0) {
|
2021-07-29 17:46:15 -03:00
|
|
|
value += DSHOT_ZERO_THROTTLE;
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#if !defined(IOMCU_FW)
|
2021-07-01 18:50:40 -03:00
|
|
|
if (!armed) {
|
|
|
|
// when disarmed we always send a zero value
|
|
|
|
value = 0;
|
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif
|
2021-03-30 06:11:22 -03:00
|
|
|
// according to sskaug requesting telemetry while trying to arm may interfere with the good frame calc
|
2021-05-04 15:10:31 -03:00
|
|
|
bool request_telemetry = telem_request_mask & chan_mask;
|
2022-08-25 02:36:10 -03:00
|
|
|
uint16_t packet = create_dshot_packet(value, request_telemetry,
|
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
|
|
|
group.bdshot.enabled
|
|
|
|
#else
|
|
|
|
false
|
|
|
|
#endif
|
|
|
|
);
|
2018-04-02 01:20:58 -03:00
|
|
|
if (request_telemetry) {
|
|
|
|
telem_request_mask &= ~chan_mask;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
fill_DMA_buffer_dshot(group.dma_buffer + i, 4, packet, group.bit_width_mul);
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-09-24 10:09:23 -03:00
|
|
|
chEvtGetAndClearEvents(group.dshot_event_mask | DSHOT_CASCADE);
|
2018-03-16 18:49:40 -03:00
|
|
|
// start sending the pulses out
|
2020-10-12 16:57:29 -03:00
|
|
|
send_pulses_DMAR(group, DSHOT_BUFFER_LENGTH);
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2019-03-29 18:45:12 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2020-02-22 19:55:47 -04:00
|
|
|
send a set of Serial LED packets for a channel group
|
2020-02-18 18:04:32 -04:00
|
|
|
return true if send was successful
|
2023-02-23 08:35:34 -04:00
|
|
|
called from led thread
|
2019-03-29 18:45:12 -03:00
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIALLED_ENABLED
|
2020-02-22 19:55:47 -04:00
|
|
|
bool RCOutput::serial_led_send(pwm_group &group)
|
2019-03-29 18:45:12 -03:00
|
|
|
{
|
2023-02-23 08:35:34 -04:00
|
|
|
if (!group.serial_led_pending || !is_led_protocol(group.current_mode)) {
|
2021-01-16 05:05:09 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2023-09-24 10:09:23 -03:00
|
|
|
if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state)
|
2023-11-11 17:54:15 -04:00
|
|
|
|| AP_HAL::micros64() - group.last_dmar_send_us < (group.dshot_pulse_time_us + 50)) {
|
2023-05-16 16:09:52 -03:00
|
|
|
// doing serial output or DMAR input, don't send DShot pulses
|
2020-02-18 18:04:32 -04:00
|
|
|
return false;
|
2019-03-29 18:45:12 -03:00
|
|
|
}
|
|
|
|
|
2023-05-16 16:09:52 -03:00
|
|
|
// first make sure we have the DMA channel before anything else
|
|
|
|
group.dma_handle->lock();
|
|
|
|
|
2021-01-16 05:05:09 -04:00
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(group.serial_led_mutex);
|
|
|
|
|
|
|
|
group.serial_led_pending = false;
|
|
|
|
group.prepared_send = false;
|
|
|
|
|
|
|
|
// fill the DMA buffer while we have the lock
|
|
|
|
fill_DMA_buffer_serial_led(group);
|
|
|
|
}
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
group.dshot_waiter = led_thread_ctx;
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2023-09-24 10:09:23 -03:00
|
|
|
chEvtGetAndClearEvents(group.dshot_event_mask | DSHOT_CASCADE);
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2019-03-29 18:45:12 -03:00
|
|
|
// start sending the pulses out
|
2019-09-09 06:23:47 -03:00
|
|
|
send_pulses_DMAR(group, group.dma_buffer_len);
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2020-02-18 18:04:32 -04:00
|
|
|
return true;
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_SERIALLED_ENABLED
|
2019-03-29 18:45:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
send a series of pulses for a group using DMAR. Pulses must have
|
|
|
|
been encoded into the group dma_buffer with interleaving for the 4
|
|
|
|
channels in the group
|
|
|
|
*/
|
|
|
|
void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2020-12-05 15:16:27 -04:00
|
|
|
osalDbgAssert(group.dma && group.dma_buffer, "DMA structures are corrupt");
|
2018-03-14 03:06:30 -03:00
|
|
|
/*
|
|
|
|
The DMA approach we are using is based on the DMAR method from
|
|
|
|
betaflight. We use the TIMn_UP DMA channel for the timer, and
|
|
|
|
setup an interleaved set of pulse durations, with a stride of 4
|
|
|
|
(for the 4 channels). We use the DMAR register to point the DMA
|
|
|
|
engine at the 4 CCR registers of the timer, so it fills in the
|
|
|
|
pulse widths for each timer in turn. This means we only use a
|
|
|
|
single DMA channel for groups of 4 timer channels. See the "DMA
|
|
|
|
address for full transfer TIMx_DMAR" section of the
|
|
|
|
datasheet. Many thanks to the betaflight developers for coming
|
|
|
|
up with this great method.
|
|
|
|
*/
|
2023-06-01 12:07:26 -03:00
|
|
|
#ifdef HAL_GPIO_LINE_GPIO54
|
2020-10-12 16:57:29 -03:00
|
|
|
TOGGLE_PIN_DEBUG(54);
|
2023-06-01 12:07:26 -03:00
|
|
|
#endif
|
2023-03-25 18:16:05 -03:00
|
|
|
#if STM32_DMA_SUPPORTS_DMAMUX
|
|
|
|
dmaSetRequestSource(group.dma, group.dma_up_channel);
|
|
|
|
#endif
|
2018-03-14 03:06:30 -03:00
|
|
|
dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
|
2019-08-02 07:57:01 -03:00
|
|
|
stm32_cacheBufferFlush(group.dma_buffer, buffer_length);
|
2018-03-14 03:06:30 -03:00
|
|
|
dmaStreamSetMemory0(group.dma, group.dma_buffer);
|
2022-08-25 02:36:10 -03:00
|
|
|
dmaStreamSetTransactionSize(group.dma, buffer_length / sizeof(dmar_uint_t));
|
2022-09-05 14:05:37 -03:00
|
|
|
#if STM32_DMA_ADVANCED
|
2018-03-14 03:06:30 -03:00
|
|
|
dmaStreamSetFIFO(group.dma, STM32_DMA_FCR_DMDIS | STM32_DMA_FCR_FTH_FULL);
|
2021-03-13 18:23:14 -04:00
|
|
|
#endif
|
2018-03-14 03:06:30 -03:00
|
|
|
dmaStreamSetMode(group.dma,
|
|
|
|
STM32_DMA_CR_CHSEL(group.dma_up_channel) |
|
2023-09-24 10:09:23 -03:00
|
|
|
STM32_DMA_CR_DIR_M2P |
|
|
|
|
#if defined(STM32F1)
|
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
|
|
|
STM32_DMA_CR_PSIZE_HWORD |
|
|
|
|
STM32_DMA_CR_MSIZE_HWORD |
|
|
|
|
#else
|
|
|
|
STM32_DMA_CR_PSIZE_WORD |
|
2022-08-25 02:36:10 -03:00
|
|
|
STM32_DMA_CR_MSIZE_BYTE |
|
2023-09-24 10:09:23 -03:00
|
|
|
#endif
|
|
|
|
|
2022-08-25 02:36:10 -03:00
|
|
|
#else
|
2023-09-24 10:09:23 -03:00
|
|
|
STM32_DMA_CR_PSIZE_WORD |
|
2022-08-25 02:36:10 -03:00
|
|
|
STM32_DMA_CR_MSIZE_WORD |
|
|
|
|
#endif
|
2018-03-14 03:06:30 -03:00
|
|
|
STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) |
|
|
|
|
STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE);
|
|
|
|
|
2021-03-13 20:03:49 -04:00
|
|
|
// setup for burst strided transfers into the timers 4 CCR registers
|
|
|
|
const uint8_t ccr_ofs = offsetof(stm32_tim_t, CCR)/4;
|
2022-08-25 02:36:10 -03:00
|
|
|
// burst address (BA) of the CCR register, burst length (BL) of 4 (0b11)
|
2021-03-13 20:03:49 -04:00
|
|
|
group.pwm_drv->tim->DCR = STM32_TIM_DCR_DBA(ccr_ofs) | STM32_TIM_DCR_DBL(3);
|
2020-10-12 16:57:29 -03:00
|
|
|
group.dshot_state = DshotState::SEND_START;
|
2023-06-01 12:07:26 -03:00
|
|
|
#ifdef HAL_GPIO_LINE_GPIO54
|
2020-10-12 16:57:29 -03:00
|
|
|
TOGGLE_PIN_DEBUG(54);
|
2023-06-01 12:07:26 -03:00
|
|
|
#endif
|
2018-03-14 03:06:30 -03:00
|
|
|
|
|
|
|
dmaStreamEnable(group.dma);
|
2020-12-05 15:16:27 -04:00
|
|
|
// record when the transaction was started
|
2023-03-23 14:13:54 -03:00
|
|
|
group.last_dmar_send_us = rcout_micros();
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_DSHOT_ENABLED
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
|
|
|
|
2018-08-04 02:29:22 -03:00
|
|
|
/*
|
2020-10-12 16:57:29 -03:00
|
|
|
unlock DMA channel after a dshot send completes and no return value is expected
|
2018-08-04 02:29:22 -03:00
|
|
|
*/
|
2022-11-10 12:49:54 -04:00
|
|
|
__RAMFUNC__ void RCOutput::dma_unlock(virtual_timer_t* vt, void *p)
|
2018-08-04 02:29:22 -03:00
|
|
|
{
|
|
|
|
chSysLockFromISR();
|
2020-10-12 16:57:29 -03:00
|
|
|
pwm_group *group = (pwm_group *)p;
|
|
|
|
|
|
|
|
group->dshot_state = DshotState::IDLE;
|
2021-02-23 21:48:39 -04:00
|
|
|
if (group->dshot_waiter != nullptr) {
|
|
|
|
// tell the waiting process we've done the DMA. Note that
|
|
|
|
// dshot_waiter can be null if we have cancelled the send
|
|
|
|
chEvtSignalI(group->dshot_waiter, group->dshot_event_mask);
|
|
|
|
}
|
2018-08-29 10:14:12 -03:00
|
|
|
chSysUnlockFromISR();
|
2018-08-04 02:29:22 -03:00
|
|
|
}
|
|
|
|
|
2020-10-12 16:57:29 -03:00
|
|
|
#ifndef HAL_WITH_BIDIR_DSHOT
|
2018-03-14 03:06:30 -03:00
|
|
|
/*
|
|
|
|
DMA interrupt handler. Used to mark DMA completed for DShot
|
|
|
|
*/
|
2021-09-04 08:59:15 -03:00
|
|
|
__RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags)
|
2018-03-14 03:06:30 -03:00
|
|
|
{
|
|
|
|
pwm_group *group = (pwm_group *)p;
|
2018-06-17 20:43:30 -03:00
|
|
|
chSysLockFromISR();
|
2018-03-14 03:06:30 -03:00
|
|
|
dmaStreamDisable(group->dma);
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIAL_ESC_COMM_ENABLED
|
|
|
|
if (group->in_serial_dma && soft_serial_waiting()) {
|
2018-03-16 18:49:40 -03:00
|
|
|
// tell the waiting process we've done the DMA
|
|
|
|
chEvtSignalI(irq.waiter, serial_event_mask);
|
2022-08-25 02:36:10 -03:00
|
|
|
} else
|
|
|
|
#endif
|
|
|
|
{
|
2018-08-04 02:29:22 -03:00
|
|
|
// this prevents us ever having two dshot pulses too close together
|
2021-02-06 13:59:04 -04:00
|
|
|
// dshot mandates a minimum pulse separation of 40us, WS2812 mandates 50us so we
|
|
|
|
// pick the higher value
|
|
|
|
chVTSetI(&group->dma_timeout, chTimeUS2I(50), dma_unlock, p);
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
2018-06-17 20:43:30 -03:00
|
|
|
chSysUnlockFromISR();
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
2020-10-12 16:57:29 -03:00
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
/*
|
|
|
|
Cancel a DMA transaction in progress
|
|
|
|
*/
|
|
|
|
void RCOutput::dma_cancel(pwm_group& group)
|
|
|
|
{
|
|
|
|
chSysLock();
|
|
|
|
dmaStreamDisable(group.dma);
|
|
|
|
#ifdef HAL_WITH_BIDIR_DSHOT
|
2023-03-25 11:53:09 -03:00
|
|
|
if (group.ic_dma_enabled() && !group.has_shared_ic_up_dma()) {
|
2020-12-05 15:16:27 -04:00
|
|
|
dmaStreamDisable(group.bdshot.ic_dma[group.bdshot.curr_telem_chan]);
|
|
|
|
}
|
2023-03-25 11:53:09 -03:00
|
|
|
#if STM32_DMA_SUPPORTS_DMAMUX
|
|
|
|
// the DMA request source has been switched by the receive path, so reinstate the correct one
|
|
|
|
if (group.dshot_state == DshotState::RECV_START && group.has_shared_ic_up_dma()) {
|
|
|
|
dmaSetRequestSource(group.dma, group.dma_up_channel);
|
|
|
|
}
|
|
|
|
#endif
|
2020-12-05 15:16:27 -04:00
|
|
|
#endif
|
2021-03-02 15:02:38 -04:00
|
|
|
// normally the CCR registers are reset by the final 0 in the DMA buffer
|
|
|
|
// since we are cancelling early they need to be reset to avoid infinite pulses
|
|
|
|
for (uint8_t i = 0; i < 4; i++) {
|
|
|
|
if (group.chan[i] != CHAN_DISABLED) {
|
|
|
|
group.pwm_drv->tim->CCR[i] = 0;
|
|
|
|
}
|
|
|
|
}
|
2020-12-05 15:16:27 -04:00
|
|
|
chVTResetI(&group.dma_timeout);
|
2023-09-24 10:09:23 -03:00
|
|
|
chEvtGetAndClearEventsI(group.dshot_event_mask | DSHOT_CASCADE);
|
2021-03-02 15:02:38 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
group.dshot_state = DshotState::IDLE;
|
|
|
|
chSysUnlock();
|
|
|
|
}
|
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
/*
|
|
|
|
setup for serial output to an ESC using the given
|
|
|
|
baudrate. Assumes 1 start bit, 1 stop bit, LSB first and 8
|
|
|
|
databits. This is used for passthrough ESC configuration and
|
|
|
|
firmware flashing
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
While serial output is active normal output to the channel group is
|
|
|
|
suspended.
|
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIAL_ESC_COMM_ENABLED
|
2021-01-11 22:01:48 -04:00
|
|
|
bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
|
|
|
// account for IOMCU channels
|
|
|
|
chan -= chan_offset;
|
2018-08-04 05:30:02 -03:00
|
|
|
chanmask >>= chan_offset;
|
2018-03-16 18:49:40 -03:00
|
|
|
pwm_group *new_serial_group = nullptr;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// find the channel group
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2018-03-25 20:48:38 -03:00
|
|
|
if (group.current_mode == MODE_PWM_BRUSHED) {
|
|
|
|
// can't do serial output with brushed motors
|
|
|
|
continue;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
if (group.ch_mask & (1U<<chan)) {
|
|
|
|
new_serial_group = &group;
|
|
|
|
for (uint8_t j=0; j<4; j++) {
|
|
|
|
if (group.chan[j] == chan) {
|
|
|
|
group.serial.chan = j;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!new_serial_group) {
|
2022-08-25 02:36:10 -03:00
|
|
|
if (in_soft_serial()) {
|
2018-03-16 18:49:40 -03:00
|
|
|
// shutdown old group
|
|
|
|
serial_end();
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2021-01-10 08:46:56 -04:00
|
|
|
// stop further dshot output before we reconfigure the DMA
|
|
|
|
serial_group = new_serial_group;
|
|
|
|
|
2018-08-04 05:30:02 -03:00
|
|
|
// setup the groups for serial output. We ask for a bit width of 1, which gets modified by the
|
|
|
|
// we setup all groups so they all are setup with the right polarity, and to make switching between
|
|
|
|
// channels in blheli pass-thru fast
|
2021-01-02 16:43:40 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2018-08-04 05:30:02 -03:00
|
|
|
if (group.ch_mask & chanmask) {
|
2022-02-10 10:42:33 -04:00
|
|
|
if (!setup_group_DMA(group, baudrate, 10, false, DSHOT_BUFFER_LENGTH, 10, false)) {
|
2018-08-04 05:30:02 -03:00
|
|
|
serial_end();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
2018-04-03 07:41:24 -03:00
|
|
|
// run the thread doing serial IO at highest priority. This is needed to ensure we don't
|
|
|
|
// lose bytes when we switch between output and input
|
|
|
|
serial_thread = chThdGetSelfX();
|
|
|
|
serial_priority = chThdGetSelfX()->realprio;
|
|
|
|
chThdSetPriority(HIGHPRIO);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// remember the bit period for serial_read_byte()
|
|
|
|
serial_group->serial.bit_time_us = 1000000UL / baudrate;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// remember the thread that set things up. This is also used to
|
|
|
|
// mark the group as doing serial output, so normal output is
|
|
|
|
// suspended
|
|
|
|
irq.waiter = chThdGetSelfX();
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
fill in a DMA buffer for a serial byte, assuming 1 start bit and 1 stop bit
|
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
void RCOutput::fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t b, uint32_t bitval)
|
2018-03-16 18:49:40 -03:00
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
const dmar_uint_t BIT_0 = bitval;
|
|
|
|
const dmar_uint_t BIT_1 = 0;
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
// start bit
|
|
|
|
buffer[0] = BIT_0;
|
|
|
|
|
|
|
|
// stop bit
|
|
|
|
buffer[9*stride] = BIT_1;
|
|
|
|
|
|
|
|
// 8 data bits
|
|
|
|
for (uint8_t i = 0; i < 8; i++) {
|
|
|
|
buffer[(1 + i) * stride] = (b & 1) ? BIT_1 : BIT_0;
|
|
|
|
b >>= 1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
send one serial byte, blocking call, should be called with the DMA lock held
|
|
|
|
*/
|
|
|
|
bool RCOutput::serial_write_byte(uint8_t b)
|
|
|
|
{
|
|
|
|
chEvtGetAndClearEvents(serial_event_mask);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
fill_DMA_buffer_byte(serial_group->dma_buffer+serial_group->serial.chan, 4, b, serial_group->bit_width_mul*10);
|
|
|
|
|
|
|
|
serial_group->in_serial_dma = true;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// start sending the pulses out
|
|
|
|
send_pulses_DMAR(*serial_group, 10*4*sizeof(uint32_t));
|
|
|
|
|
|
|
|
// wait for the event
|
2018-06-02 12:56:42 -03:00
|
|
|
eventmask_t mask = chEvtWaitAnyTimeout(serial_event_mask, chTimeMS2I(2));
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
serial_group->in_serial_dma = false;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
return (mask & serial_event_mask) != 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
send a set of serial bytes, blocking call
|
|
|
|
*/
|
|
|
|
bool RCOutput::serial_write_bytes(const uint8_t *bytes, uint16_t len)
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
|
|
|
if (!in_soft_serial()) {
|
2018-03-16 18:49:40 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
serial_group->dma_handle->lock();
|
2020-10-12 16:57:29 -03:00
|
|
|
memset(serial_group->dma_buffer, 0, DSHOT_BUFFER_LENGTH);
|
2018-03-16 18:49:40 -03:00
|
|
|
while (len--) {
|
|
|
|
if (!serial_write_byte(*bytes++)) {
|
|
|
|
serial_group->dma_handle->unlock();
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2018-05-22 03:11:45 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// add a small delay for last word of output to have completely
|
|
|
|
// finished
|
2018-05-22 03:11:45 -03:00
|
|
|
hal.scheduler->delay_microseconds(25);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-05-22 03:11:45 -03:00
|
|
|
serial_group->dma_handle->unlock();
|
2018-03-16 18:49:40 -03:00
|
|
|
return true;
|
2018-08-29 10:14:12 -03:00
|
|
|
#else
|
|
|
|
return false;
|
2020-10-12 16:57:29 -03:00
|
|
|
#endif // DISABLE_DSHOT
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
irq handler for bit transition in serial_read_byte()
|
|
|
|
This implements a one byte soft serial reader
|
|
|
|
*/
|
|
|
|
void RCOutput::serial_bit_irq(void)
|
|
|
|
{
|
2021-10-02 02:40:07 -03:00
|
|
|
uint16_t now = AP_HAL::micros16();
|
2018-03-16 18:49:40 -03:00
|
|
|
uint8_t bit = palReadLine(irq.line);
|
|
|
|
bool send_signal = false;
|
2018-04-01 03:00:52 -03:00
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO55, bit);
|
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
if (irq.nbits == 0 || bit == irq.last_bit) {
|
|
|
|
// start of byte, should be low
|
|
|
|
if (bit != 0) {
|
|
|
|
irq.byteval = 0x200;
|
|
|
|
send_signal = true;
|
|
|
|
} else {
|
|
|
|
irq.nbits = 1;
|
2018-04-15 02:33:40 -03:00
|
|
|
irq.byte_start_tick = now;
|
2018-03-16 18:49:40 -03:00
|
|
|
irq.bitmask = 0;
|
|
|
|
}
|
|
|
|
} else {
|
2021-10-02 02:40:07 -03:00
|
|
|
uint16_t dt = now - irq.byte_start_tick;
|
2018-04-15 02:33:40 -03:00
|
|
|
uint8_t bitnum = (dt+(irq.bit_time_tick/2)) / irq.bit_time_tick;
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
if (bitnum > 10) {
|
|
|
|
bitnum = 10;
|
|
|
|
}
|
|
|
|
if (!bit) {
|
|
|
|
// set the bits that we've processed
|
|
|
|
irq.bitmask |= ((1U<<bitnum)-1) & ~((1U<<irq.nbits)-1);
|
|
|
|
}
|
|
|
|
irq.nbits = bitnum;
|
|
|
|
|
|
|
|
if (irq.nbits == 10) {
|
|
|
|
send_signal = true;
|
|
|
|
irq.byteval = irq.bitmask & 0x3FF;
|
|
|
|
irq.bitmask = 0;
|
|
|
|
irq.nbits = 1;
|
2018-04-15 02:33:40 -03:00
|
|
|
irq.byte_start_tick = now;
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
irq.last_bit = bit;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
if (send_signal) {
|
|
|
|
chSysLockFromISR();
|
2018-08-04 00:34:00 -03:00
|
|
|
chVTResetI(&irq.serial_timeout);
|
2018-03-16 18:49:40 -03:00
|
|
|
chEvtSignalI(irq.waiter, serial_event_mask);
|
|
|
|
chSysUnlockFromISR();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-08-04 00:34:00 -03:00
|
|
|
/*
|
|
|
|
timeout a byte read
|
|
|
|
*/
|
2022-11-10 12:49:54 -04:00
|
|
|
void RCOutput::serial_byte_timeout(virtual_timer_t* vt, void *ctx)
|
2018-08-04 00:34:00 -03:00
|
|
|
{
|
|
|
|
chSysLockFromISR();
|
|
|
|
irq.timed_out = true;
|
|
|
|
chEvtSignalI((thread_t *)ctx, serial_event_mask);
|
|
|
|
chSysUnlockFromISR();
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
read a byte from a port, using serial parameters from serial_setup_output()
|
|
|
|
*/
|
|
|
|
bool RCOutput::serial_read_byte(uint8_t &b)
|
|
|
|
{
|
2018-08-04 00:34:00 -03:00
|
|
|
irq.timed_out = false;
|
|
|
|
chVTSet(&irq.serial_timeout, chTimeMS2I(10), serial_byte_timeout, irq.waiter);
|
|
|
|
bool timed_out = ((chEvtWaitAny(serial_event_mask) & serial_event_mask) == 0) || irq.timed_out;
|
2018-03-16 18:49:40 -03:00
|
|
|
|
|
|
|
uint16_t byteval = irq.byteval;
|
|
|
|
|
|
|
|
if (timed_out) {
|
|
|
|
// we can accept a byte with a timeout if the last bit was 1
|
|
|
|
// and the start bit is set correctly
|
|
|
|
if (irq.last_bit == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
byteval = irq.bitmask | 0x200;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
if ((byteval & 0x201) != 0x200) {
|
|
|
|
// wrong start/stop bits
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
b = uint8_t(byteval>>1);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
read a byte from a port, using serial parameters from serial_setup_output()
|
|
|
|
*/
|
|
|
|
uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
if (!in_soft_serial()) {
|
2018-03-25 20:48:38 -03:00
|
|
|
return 0;
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
pwm_group &group = *serial_group;
|
2018-04-06 20:58:57 -03:00
|
|
|
const ioline_t line = group.pal_lines[group.serial.chan];
|
2021-04-18 10:34:12 -03:00
|
|
|
// keep speed low to avoid noise when switching between input and output
|
2021-10-11 04:32:37 -03:00
|
|
|
#ifndef PAL_STM32_OSPEED_LOWEST
|
|
|
|
// for GPIOv3
|
|
|
|
uint32_t gpio_mode = PAL_STM32_MODE_INPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | PAL_STM32_OSPEED_LOW;
|
|
|
|
#else
|
2021-04-18 10:34:12 -03:00
|
|
|
uint32_t gpio_mode = PAL_STM32_MODE_INPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | PAL_STM32_OSPEED_LOWEST;
|
2021-10-11 04:32:37 -03:00
|
|
|
#endif
|
2021-04-18 10:34:12 -03:00
|
|
|
// restore the line to what it was before
|
|
|
|
iomode_t restore_mode = palReadLineMode(line);
|
2018-03-16 18:49:40 -03:00
|
|
|
uint16_t i = 0;
|
|
|
|
|
2018-04-01 03:00:52 -03:00
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG
|
|
|
|
hal.gpio->pinMode(54, 1);
|
|
|
|
hal.gpio->pinMode(55, 1);
|
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
// assume GPIO mappings for PWM outputs start at 50
|
2018-04-06 20:58:57 -03:00
|
|
|
palSetLineMode(line, gpio_mode);
|
2018-03-16 18:49:40 -03:00
|
|
|
|
2018-08-04 00:34:00 -03:00
|
|
|
chVTObjectInit(&irq.serial_timeout);
|
2018-03-16 18:49:40 -03:00
|
|
|
chEvtGetAndClearEvents(serial_event_mask);
|
|
|
|
|
|
|
|
irq.line = group.pal_lines[group.serial.chan];
|
|
|
|
irq.nbits = 0;
|
|
|
|
irq.bitmask = 0;
|
|
|
|
irq.byteval = 0;
|
2018-04-15 02:33:40 -03:00
|
|
|
irq.bit_time_tick = serial_group->serial.bit_time_us;
|
2018-03-16 18:49:40 -03:00
|
|
|
irq.last_bit = 0;
|
|
|
|
irq.waiter = chThdGetSelfX();
|
2018-04-01 03:00:52 -03:00
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 1);
|
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-08-06 01:18:52 -03:00
|
|
|
if (!((GPIO *)hal.gpio)->_attach_interrupt(line, serial_bit_irq, AP_HAL::GPIO::INTERRUPT_BOTH)) {
|
2018-04-01 03:00:52 -03:00
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
|
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
return false;
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-03-16 18:49:40 -03:00
|
|
|
for (i=0; i<len; i++) {
|
|
|
|
if (!serial_read_byte(buf[i])) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-06 20:58:57 -03:00
|
|
|
((GPIO *)hal.gpio)->_attach_interrupt(line, nullptr, 0);
|
2018-03-16 18:49:40 -03:00
|
|
|
irq.waiter = nullptr;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-04-06 20:58:57 -03:00
|
|
|
palSetLineMode(line, restore_mode);
|
2018-04-01 03:00:52 -03:00
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 0);
|
|
|
|
#endif
|
2018-03-16 18:49:40 -03:00
|
|
|
return i;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
end serial output
|
|
|
|
*/
|
|
|
|
void RCOutput::serial_end(void)
|
|
|
|
{
|
2022-08-25 02:36:10 -03:00
|
|
|
if (in_soft_serial()) {
|
2018-04-03 07:41:24 -03:00
|
|
|
if (serial_thread == chThdGetSelfX()) {
|
|
|
|
chThdSetPriority(serial_priority);
|
|
|
|
serial_thread = nullptr;
|
|
|
|
}
|
2018-08-04 05:30:02 -03:00
|
|
|
irq.waiter = nullptr;
|
|
|
|
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
|
|
|
|
pwm_group &group = pwm_group_list[i];
|
|
|
|
set_group_mode(group);
|
|
|
|
set_freq_group(group);
|
|
|
|
}
|
2018-03-16 18:49:40 -03:00
|
|
|
}
|
|
|
|
serial_group = nullptr;
|
2018-03-14 03:06:30 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_SERIAL_ESC_COMM_ENABLED
|
2018-03-14 03:06:30 -03:00
|
|
|
|
2018-04-14 00:55:03 -03:00
|
|
|
/*
|
|
|
|
get safety switch state for Util.cpp
|
|
|
|
*/
|
|
|
|
AP_HAL::Util::safety_state RCOutput::_safety_switch_state(void)
|
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2019-04-19 21:28:15 -03:00
|
|
|
safety_state = iomcu.get_safety_switch_state();
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
|
|
|
#endif
|
2019-05-09 04:49:32 -03:00
|
|
|
if (!hal.util->was_watchdog_reset()) {
|
|
|
|
hal.util->persistent_data.safety_state = safety_state;
|
2019-04-19 21:28:15 -03:00
|
|
|
}
|
2018-04-14 00:55:03 -03:00
|
|
|
return safety_state;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
force the safety switch on, disabling PWM output from the IO board
|
|
|
|
*/
|
|
|
|
bool RCOutput::force_safety_on(void)
|
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-04-14 00:55:03 -03:00
|
|
|
return iomcu.force_safety_on();
|
|
|
|
}
|
2022-08-13 08:22:18 -03:00
|
|
|
#endif
|
2018-04-14 00:55:03 -03:00
|
|
|
safety_state = AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
force the safety switch off, enabling PWM output from the IO board
|
|
|
|
*/
|
|
|
|
void RCOutput::force_safety_off(void)
|
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-04-14 00:55:03 -03:00
|
|
|
iomcu.force_safety_off();
|
2022-08-13 08:22:18 -03:00
|
|
|
return;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
|
|
|
#endif
|
2022-08-13 08:22:18 -03:00
|
|
|
safety_state = AP_HAL::Util::SAFETY_ARMED;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
update safety state
|
|
|
|
*/
|
|
|
|
void RCOutput::safety_update(void)
|
|
|
|
{
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - safety_update_ms < 100) {
|
|
|
|
// update safety at 10Hz
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
safety_update_ms = now;
|
|
|
|
|
2019-02-10 14:53:21 -04:00
|
|
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
|
2018-04-14 00:55:03 -03:00
|
|
|
|
|
|
|
if (boardconfig) {
|
|
|
|
// remember mask of channels to allow with safety on
|
|
|
|
safety_mask = boardconfig->get_safety_mask();
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-04-14 00:55:03 -03:00
|
|
|
#ifdef HAL_GPIO_PIN_SAFETY_IN
|
|
|
|
// handle safety button
|
|
|
|
bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_IN);
|
|
|
|
if (safety_pressed) {
|
2019-09-02 23:24:34 -03:00
|
|
|
AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
|
|
|
|
if (safety_press_count < 255) {
|
|
|
|
safety_press_count++;
|
|
|
|
}
|
|
|
|
if (brdconfig && brdconfig->safety_button_handle_pressed(safety_press_count)) {
|
|
|
|
if (safety_state ==AP_HAL::Util::SAFETY_ARMED) {
|
|
|
|
safety_state = AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
} else {
|
|
|
|
safety_state = AP_HAL::Util::SAFETY_ARMED;
|
|
|
|
}
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
2019-09-02 23:24:34 -03:00
|
|
|
} else {
|
|
|
|
safety_press_count = 0;
|
2018-04-14 00:55:03 -03:00
|
|
|
}
|
|
|
|
#elif HAL_WITH_IO_MCU
|
|
|
|
safety_state = _safety_switch_state();
|
|
|
|
#endif
|
|
|
|
|
2022-11-03 02:33:38 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
// regardless of if we have a FMU safety pin, if we have an IOMCU we need
|
|
|
|
// to pass the BRD_SAFETY_MASK to the IOMCU
|
|
|
|
iomcu.set_safety_mask(safety_mask);
|
|
|
|
#endif
|
|
|
|
|
2018-04-14 00:55:03 -03:00
|
|
|
#ifdef HAL_GPIO_PIN_LED_SAFETY
|
|
|
|
led_counter = (led_counter+1) % 16;
|
|
|
|
const uint16_t led_pattern = safety_state==AP_HAL::Util::SAFETY_DISARMED?0x5500:0xFFFF;
|
|
|
|
palWriteLine(HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-09-12 17:23:01 -03:00
|
|
|
/*
|
|
|
|
set PWM to send to a set of channels if the FMU firmware dies
|
|
|
|
*/
|
|
|
|
void RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
|
|
|
|
{
|
|
|
|
#if HAL_WITH_IO_MCU
|
2023-10-19 12:22:08 -03:00
|
|
|
if (iomcu_enabled) {
|
2018-09-12 17:23:01 -03:00
|
|
|
iomcu.set_failsafe_pwm(chmask, period_us);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2019-03-29 18:45:12 -03:00
|
|
|
/*
|
|
|
|
returns the bitrate in Hz of the given output_mode
|
|
|
|
*/
|
2020-10-12 16:57:29 -03:00
|
|
|
uint32_t RCOutput::protocol_bitrate(const enum output_mode mode)
|
2019-03-29 18:45:12 -03:00
|
|
|
{
|
|
|
|
switch (mode) {
|
|
|
|
case MODE_PWM_DSHOT150:
|
|
|
|
return 150000;
|
|
|
|
case MODE_PWM_DSHOT300:
|
|
|
|
return 300000;
|
|
|
|
case MODE_PWM_DSHOT600:
|
|
|
|
return 600000;
|
|
|
|
case MODE_PWM_DSHOT1200:
|
|
|
|
return 1200000;
|
|
|
|
case MODE_NEOPIXEL:
|
2023-09-28 17:49:05 -03:00
|
|
|
case MODE_NEOPIXELRGB:
|
2019-03-29 18:45:12 -03:00
|
|
|
return 800000;
|
2020-02-22 19:55:47 -04:00
|
|
|
case MODE_PROFILED:
|
|
|
|
return 1500000; // experiment winding this up 3000000 max from data sheet
|
2019-03-29 18:45:12 -03:00
|
|
|
default:
|
|
|
|
// use 1 to prevent a possible divide-by-zero
|
|
|
|
return 1;
|
|
|
|
}
|
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
|
|
|
|
/*
|
2020-02-22 19:55:47 -04:00
|
|
|
setup serial led output for a given channel number, with
|
2019-09-09 06:23:47 -03:00
|
|
|
the given max number of LEDs in the chain.
|
|
|
|
*/
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIALLED_ENABLED
|
2021-01-11 22:01:48 -04:00
|
|
|
bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode, uint32_t clock_mask)
|
2019-09-09 06:23:47 -03:00
|
|
|
{
|
2021-03-21 22:27:17 -03:00
|
|
|
if (!_initialised || num_leds == 0) {
|
2021-01-16 05:05:09 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t i = 0;
|
2019-09-09 06:23:47 -03:00
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
if (!grp) {
|
|
|
|
return false;
|
|
|
|
}
|
2020-02-22 19:55:47 -04:00
|
|
|
|
2021-01-16 05:05:09 -04:00
|
|
|
WITH_SEMAPHORE(grp->serial_led_mutex);
|
2021-03-21 22:27:17 -03:00
|
|
|
|
|
|
|
// group is already setup correctly
|
|
|
|
if ((grp->serial_nleds >= num_leds) && (mode == grp->current_mode)) {
|
|
|
|
return true;
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
2021-03-21 22:27:17 -03:00
|
|
|
|
|
|
|
// we cant add more or change the type after the first setup
|
2023-02-23 08:35:34 -04:00
|
|
|
if (is_led_protocol(grp->current_mode)) {
|
2021-03-13 10:18:37 -04:00
|
|
|
return false;
|
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
|
2020-02-22 19:55:47 -04:00
|
|
|
switch (mode) {
|
2023-09-28 17:49:05 -03:00
|
|
|
|
|
|
|
case MODE_NEOPIXEL:
|
|
|
|
case MODE_NEOPIXELRGB: {
|
2021-03-21 22:27:17 -03:00
|
|
|
grp->serial_nleds = MAX(num_leds, grp->serial_nleds);
|
2023-09-28 17:49:05 -03:00
|
|
|
grp->led_mode = mode;
|
2021-03-21 22:27:17 -03:00
|
|
|
return true;
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
|
|
|
case MODE_PROFILED: {
|
|
|
|
// ProfiLED requires two dummy LED's to mark end of transmission
|
2021-03-21 22:27:17 -03:00
|
|
|
grp->serial_nleds = MAX(num_leds + 2, grp->serial_nleds);
|
|
|
|
grp->led_mode = MODE_PROFILED;
|
2020-02-22 19:55:47 -04:00
|
|
|
|
|
|
|
// Enable any clock channels in the same group
|
|
|
|
grp->clock_mask = 0;
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
if ((clock_mask & (1U<<(grp->chan[j] + chan_offset))) != 0) {
|
|
|
|
grp->clock_mask |= 1U<<j;
|
|
|
|
}
|
|
|
|
}
|
2021-03-21 22:27:17 -03:00
|
|
|
return true;
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
default:
|
2021-03-21 22:27:17 -03:00
|
|
|
grp->serial_nleds = 0;
|
|
|
|
grp->led_mode = MODE_PWM_NONE;
|
2020-02-22 19:55:47 -04:00
|
|
|
return false;
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
|
|
|
|
2021-03-21 22:27:17 -03:00
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
|
|
|
|
#pragma GCC push_options
|
|
|
|
#pragma GCC optimize("O2")
|
|
|
|
// Fill the group DMA buffer with data to be output
|
|
|
|
void RCOutput::fill_DMA_buffer_serial_led(pwm_group& group)
|
|
|
|
{
|
|
|
|
memset(group.dma_buffer, 0, group.dma_buffer_len);
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
if (group.serial_led_data[j] == nullptr) {
|
2021-03-21 22:27:17 -03:00
|
|
|
// something very bad has happended
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (group.current_mode == MODE_PROFILED && (group.clock_mask & 1U<<j) != 0) {
|
|
|
|
// output clock channel
|
|
|
|
for (uint8_t i = 0; i < group.serial_nleds; i++) {
|
|
|
|
_set_profiled_clock(&group, j, i);
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
for (uint8_t i = 0; i < group.serial_nleds; i++) {
|
|
|
|
const SerialLed& led = group.serial_led_data[j][i];
|
|
|
|
switch (group.current_mode) {
|
|
|
|
case MODE_NEOPIXEL:
|
|
|
|
_set_neopixel_rgb_data(&group, j, i, led.red, led.green, led.blue);
|
|
|
|
break;
|
2023-09-28 17:49:05 -03:00
|
|
|
case MODE_NEOPIXELRGB:
|
|
|
|
_set_neopixel_rgb_data(&group, j, i, led.green, led.red, led.blue);
|
|
|
|
break;
|
2021-01-16 05:05:09 -04:00
|
|
|
case MODE_PROFILED: {
|
|
|
|
if (i < group.serial_nleds - 2) {
|
|
|
|
_set_profiled_rgb_data(&group, j, i, led.red, led.green, led.blue);
|
|
|
|
} else {
|
|
|
|
_set_profiled_blank_frame(&group, j, i);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-09-09 06:23:47 -03:00
|
|
|
/*
|
|
|
|
setup neopixel (WS2812B) output data for a given output channel
|
2020-02-09 06:34:46 -04:00
|
|
|
and a LED number. LED -1 is all LEDs
|
2019-09-09 06:23:47 -03:00
|
|
|
*/
|
2020-02-09 06:34:46 -04:00
|
|
|
void RCOutput::_set_neopixel_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
|
|
|
{
|
|
|
|
const uint8_t pad_start_bits = 1;
|
|
|
|
const uint8_t neopixel_bit_length = 24;
|
|
|
|
const uint8_t stride = 4;
|
2022-08-25 02:36:10 -03:00
|
|
|
dmar_uint_t *buf = grp->dma_buffer + (led * neopixel_bit_length + pad_start_bits) * stride + idx;
|
2020-02-09 06:34:46 -04:00
|
|
|
uint32_t bits = (green<<16) | (red<<8) | blue;
|
2022-03-08 14:03:55 -04:00
|
|
|
const uint32_t BIT_0 = NEOP_BIT_0_TICKS * grp->bit_width_mul;
|
|
|
|
const uint32_t BIT_1 = NEOP_BIT_1_TICKS * grp->bit_width_mul;
|
2020-02-09 06:34:46 -04:00
|
|
|
for (uint16_t b=0; b < 24; b++) {
|
|
|
|
buf[b * stride] = (bits & 0x800000) ? BIT_1 : BIT_0;
|
|
|
|
bits <<= 1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2020-02-22 19:55:47 -04:00
|
|
|
ProfiLED frame for a given output channel
|
|
|
|
channel is active high and bits inverted to get clock rising edge away from data rising edge
|
|
|
|
*/
|
|
|
|
void RCOutput::_set_profiled_rgb_data(pwm_group *grp, uint8_t idx, uint8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
|
|
|
{
|
|
|
|
const uint8_t pad_start_bits = 1;
|
|
|
|
const uint8_t bit_length = 25;
|
|
|
|
const uint8_t stride = 4;
|
2022-08-25 02:36:10 -03:00
|
|
|
dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
|
2020-02-22 19:55:47 -04:00
|
|
|
uint32_t bits = 0x1000000 | (blue<<16) | (red<<8) | green;
|
2022-03-08 14:03:55 -04:00
|
|
|
const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul;
|
2020-02-22 19:55:47 -04:00
|
|
|
for (uint16_t b=0; b < bit_length; b++) {
|
|
|
|
buf[b * stride] = (bits & 0x1000000) ? 0 : BIT_1;
|
|
|
|
bits <<= 1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
ProfiLED blank frame for a given output channel
|
|
|
|
channel is active high and bits inverted to get clock rising edge away from data rising edge
|
|
|
|
*/
|
|
|
|
void RCOutput::_set_profiled_blank_frame(pwm_group *grp, uint8_t idx, uint8_t led)
|
|
|
|
{
|
|
|
|
const uint8_t pad_start_bits = 1;
|
|
|
|
const uint8_t bit_length = 25;
|
|
|
|
const uint8_t stride = 4;
|
2022-08-25 02:36:10 -03:00
|
|
|
dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
|
2022-03-08 14:03:55 -04:00
|
|
|
const uint32_t BIT_1 = PROFI_BIT_1_TICKS * grp->bit_width_mul;
|
2020-02-22 19:55:47 -04:00
|
|
|
for (uint16_t b=0; b < bit_length; b++) {
|
|
|
|
buf[b * stride] = BIT_1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup ProfiLED clock frame for a given output channel
|
|
|
|
*/
|
|
|
|
void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led)
|
|
|
|
{
|
|
|
|
const uint8_t pad_start_bits = 1;
|
|
|
|
const uint8_t bit_length = 25;
|
|
|
|
const uint8_t stride = 4;
|
2022-08-25 02:36:10 -03:00
|
|
|
dmar_uint_t *buf = grp->dma_buffer + (led * bit_length + pad_start_bits) * stride + idx;
|
2022-03-08 14:03:55 -04:00
|
|
|
const uint32_t BIT_1 = PROFI_BIT_0_TICKS * grp->bit_width_mul;
|
2020-02-22 19:55:47 -04:00
|
|
|
for (uint16_t b=0; b < bit_length; b++) {
|
|
|
|
buf[b * stride] = BIT_1;
|
|
|
|
}
|
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
#pragma GCC pop_options
|
2020-02-22 19:55:47 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
setup serial LED output data for a given output channel
|
2020-02-09 06:34:46 -04:00
|
|
|
and a LED number. LED -1 is all LEDs
|
|
|
|
*/
|
2023-11-17 13:32:01 -04:00
|
|
|
bool RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
2019-09-09 06:23:47 -03:00
|
|
|
{
|
2021-01-16 05:05:09 -04:00
|
|
|
if (!_initialised) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2019-09-09 06:23:47 -03:00
|
|
|
}
|
2020-02-22 19:55:47 -04:00
|
|
|
|
2021-01-16 05:05:09 -04:00
|
|
|
uint8_t i = 0;
|
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
|
2021-02-06 13:59:04 -04:00
|
|
|
if (!grp) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2019-09-09 06:23:47 -03:00
|
|
|
}
|
2020-02-09 06:34:46 -04:00
|
|
|
|
2021-03-21 22:27:17 -03:00
|
|
|
if (grp->serial_led_pending) {
|
|
|
|
// dont allow setting new data if a send is pending
|
|
|
|
// would result in a fight over the mutex
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
2021-03-21 22:27:17 -03:00
|
|
|
|
2021-02-12 18:36:04 -04:00
|
|
|
WITH_SEMAPHORE(grp->serial_led_mutex);
|
|
|
|
|
2021-03-21 22:27:17 -03:00
|
|
|
if (grp->serial_nleds == 0 || led >= grp->serial_nleds) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2021-03-21 22:27:17 -03:00
|
|
|
}
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
if ((grp->current_mode != grp->led_mode) && is_led_protocol(grp->led_mode)) {
|
2021-03-21 22:27:17 -03:00
|
|
|
// Arrays have not yet been setup, do it now
|
|
|
|
for (uint8_t j = 0; j < 4; j++) {
|
|
|
|
delete[] grp->serial_led_data[j];
|
|
|
|
grp->serial_led_data[j] = nullptr;
|
|
|
|
grp->serial_led_data[j] = new SerialLed[grp->serial_nleds];
|
|
|
|
if (grp->serial_led_data[j] == nullptr) {
|
|
|
|
// if allocation failed clear all memory
|
|
|
|
for (uint8_t k = 0; k < 4; k++) {
|
|
|
|
delete[] grp->serial_led_data[k];
|
|
|
|
grp->serial_led_data[k] = nullptr;
|
|
|
|
}
|
|
|
|
grp->led_mode = MODE_PWM_NONE;
|
|
|
|
grp->serial_nleds = 0;
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2021-03-21 22:27:17 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// at this point the group led data is all setup but the dma buffer still needs to be resized
|
|
|
|
set_output_mode(1U<<chan, grp->led_mode);
|
|
|
|
|
|
|
|
if (grp->current_mode != grp->led_mode) {
|
|
|
|
// Failed to set output mode
|
|
|
|
grp->led_mode = MODE_PWM_NONE;
|
|
|
|
grp->serial_nleds = 0;
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2021-03-21 22:27:17 -03:00
|
|
|
}
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
} else if (!is_led_protocol(grp->current_mode)) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2021-02-06 13:59:04 -04:00
|
|
|
}
|
|
|
|
|
2020-02-22 19:55:47 -04:00
|
|
|
if (led == -1) {
|
|
|
|
grp->prepared_send = true;
|
|
|
|
for (uint8_t n=0; n<grp->serial_nleds; n++) {
|
2021-01-16 05:05:09 -04:00
|
|
|
serial_led_set_single_rgb_data(*grp, i, n, red, green, blue);
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2023-11-17 13:32:01 -04:00
|
|
|
return true;
|
2020-02-09 06:34:46 -04:00
|
|
|
}
|
|
|
|
|
2021-01-16 05:05:09 -04:00
|
|
|
// if not ouput clock and trailing frames, run through all LED's to do it now
|
|
|
|
if (!grp->prepared_send) {
|
2021-02-06 13:59:04 -04:00
|
|
|
grp->prepared_send = true;
|
2021-01-16 05:05:09 -04:00
|
|
|
for (uint8_t n=0; n<grp->serial_nleds; n++) {
|
|
|
|
serial_led_set_single_rgb_data(*grp, i, n, 0, 0, 0);
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
|
|
|
serial_led_set_single_rgb_data(*grp, i, uint8_t(led), red, green, blue);
|
2023-11-17 13:32:01 -04:00
|
|
|
|
|
|
|
return true;
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
2020-02-22 19:55:47 -04:00
|
|
|
|
2021-01-16 05:05:09 -04:00
|
|
|
/*
|
|
|
|
setup serial LED output data for a given output channel
|
|
|
|
and a LED number. LED -1 is all LEDs
|
|
|
|
*/
|
|
|
|
void RCOutput::serial_led_set_single_rgb_data(pwm_group& group, uint8_t idx, uint8_t led, uint8_t red, uint8_t green, uint8_t blue)
|
|
|
|
{
|
|
|
|
switch (group.current_mode) {
|
|
|
|
case MODE_PROFILED:
|
|
|
|
case MODE_NEOPIXEL:
|
2023-09-28 17:49:05 -03:00
|
|
|
case MODE_NEOPIXELRGB:
|
2021-01-16 05:05:09 -04:00
|
|
|
group.serial_led_data[idx][led].red = red;
|
|
|
|
group.serial_led_data[idx][led].green = green;
|
|
|
|
group.serial_led_data[idx][led].blue = blue;
|
|
|
|
break;
|
|
|
|
default:
|
2020-02-22 19:55:47 -04:00
|
|
|
break;
|
|
|
|
}
|
2019-09-09 06:23:47 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2020-02-22 19:55:47 -04:00
|
|
|
trigger send of serial led data for one group
|
2019-09-09 06:23:47 -03:00
|
|
|
*/
|
2023-11-17 13:32:01 -04:00
|
|
|
bool RCOutput::serial_led_send(const uint16_t chan)
|
2019-09-09 06:23:47 -03:00
|
|
|
{
|
2021-01-16 05:05:09 -04:00
|
|
|
if (!_initialised) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2021-01-16 05:05:09 -04:00
|
|
|
}
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
if (led_thread_ctx == nullptr) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2023-02-23 08:35:34 -04:00
|
|
|
}
|
|
|
|
|
2020-02-22 19:55:47 -04:00
|
|
|
uint8_t i;
|
|
|
|
pwm_group *grp = find_chan(chan, i);
|
|
|
|
if (!grp) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
|
|
|
|
WITH_SEMAPHORE(grp->serial_led_mutex);
|
|
|
|
|
2023-02-23 08:35:34 -04:00
|
|
|
if (grp->serial_nleds == 0 || !is_led_protocol(grp->current_mode)) {
|
2023-11-17 13:32:01 -04:00
|
|
|
return false;
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2021-01-16 05:05:09 -04:00
|
|
|
|
2020-02-22 19:55:47 -04:00
|
|
|
if (grp->prepared_send) {
|
|
|
|
grp->serial_led_pending = true;
|
2021-01-16 05:05:09 -04:00
|
|
|
serial_led_pending = true;
|
2023-11-17 13:31:21 -04:00
|
|
|
chEvtSignal(led_thread_ctx, EVT_LED_SEND);
|
2020-02-22 19:55:47 -04:00
|
|
|
}
|
2023-11-17 13:32:01 -04:00
|
|
|
|
|
|
|
return true;
|
2019-09-09 06:23:47 -03:00
|
|
|
}
|
2022-08-25 02:36:10 -03:00
|
|
|
#endif // HAL_SERIALLED_ENABLED
|
2019-09-09 06:23:47 -03:00
|
|
|
|
2022-02-10 10:42:33 -04:00
|
|
|
void RCOutput::timer_info(ExpandingString &str)
|
|
|
|
{
|
|
|
|
// a header to allow for machine parsers to determine format
|
|
|
|
str.printf("TIMERV1\n");
|
2023-10-16 12:54:22 -03:00
|
|
|
#if HAL_DSHOT_ENABLED
|
2022-02-10 10:42:33 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
2022-03-08 14:03:55 -04:00
|
|
|
uint32_t target_freq;
|
2023-10-16 12:54:22 -03:00
|
|
|
bool at_least_freq;
|
2022-08-25 02:36:10 -03:00
|
|
|
#if HAL_SERIAL_ESC_COMM_ENABLED
|
2022-03-08 14:03:55 -04:00
|
|
|
if (&group == serial_group) {
|
|
|
|
target_freq = 19200 * 10;
|
2022-08-25 02:36:10 -03:00
|
|
|
} else
|
|
|
|
#endif // HAL_SERIAL_ESC_COMM_ENABLED
|
|
|
|
if (is_dshot_protocol(group.current_mode)) {
|
2022-03-08 14:03:55 -04:00
|
|
|
target_freq = protocol_bitrate(group.current_mode) * DSHOT_BIT_WIDTH_TICKS;
|
2023-10-16 12:54:22 -03:00
|
|
|
if (_dshot_esc_type == DSHOT_ESC_BLHELI_S || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S) {
|
|
|
|
at_least_freq = true;
|
|
|
|
}
|
2022-03-08 14:03:55 -04:00
|
|
|
} else {
|
|
|
|
target_freq = protocol_bitrate(group.current_mode) * NEOP_BIT_WIDTH_TICKS;
|
|
|
|
}
|
2023-10-16 12:54:22 -03:00
|
|
|
const uint32_t prescaler = calculate_bitrate_prescaler(group.pwm_drv->clock, target_freq, at_least_freq);
|
2022-02-10 10:42:33 -04:00
|
|
|
str.printf("TIM%-2u CLK=%4uMhz MODE=%5s FREQ=%8u TGT=%8u\n", group.timer_id, unsigned(group.pwm_drv->clock / 1000000),
|
|
|
|
get_output_mode_string(group.current_mode),
|
2023-10-16 12:54:22 -03:00
|
|
|
unsigned(group.pwm_drv->clock / (prescaler + 1)), unsigned(target_freq));
|
2022-02-10 10:42:33 -04:00
|
|
|
}
|
2023-10-16 12:54:22 -03:00
|
|
|
#endif
|
2022-02-10 10:42:33 -04:00
|
|
|
}
|
|
|
|
|
2018-03-01 20:46:30 -04:00
|
|
|
#endif // HAL_USE_PWM
|