2021-10-27 05:43:28 -03: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/>.
|
|
|
|
*
|
2024-12-08 15:55:59 -04:00
|
|
|
* Code by Charles "Silvanosky" Villard, David "Buzz" Bussenschutt,
|
|
|
|
* Andrey "ARg" Romanov, and Thomas "tpw_rules" Watson
|
2021-10-27 05:43:28 -03:00
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "RCOutput.h"
|
|
|
|
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
|
|
|
|
|
|
#include "driver/rtc_io.h"
|
|
|
|
|
|
|
|
#include <stdio.h>
|
|
|
|
|
2024-10-09 15:02:42 -03:00
|
|
|
#include "esp_log.h"
|
|
|
|
|
|
|
|
#define TAG "RCOut"
|
|
|
|
|
2021-10-27 05:43:28 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
using namespace ESP32;
|
|
|
|
|
|
|
|
#ifdef HAL_ESP32_RCOUT
|
|
|
|
|
|
|
|
gpio_num_t outputs_pins[] = HAL_ESP32_RCOUT;
|
|
|
|
|
|
|
|
//If the RTC source is not required, then GPIO32/Pin12/32K_XP and GPIO33/Pin13/32K_XN can be used as digital GPIOs.
|
|
|
|
|
|
|
|
#else
|
|
|
|
gpio_num_t outputs_pins[] = {};
|
|
|
|
|
|
|
|
#endif
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
/*
|
|
|
|
* The MCPWM (motor control PWM) peripheral is used to generate PWM signals for
|
|
|
|
* RC output. It is divided up into the following blocks:
|
|
|
|
* * The chip has SOC_MCPWM_GROUPS groups
|
|
|
|
* * Each group has SOC_MCPWM_TIMERS_PER_GROUP timers and operators
|
|
|
|
* * Each operator has SOC_MCPWM_COMPARATORS_PER_OPERATOR comparators and
|
|
|
|
* generators
|
|
|
|
* * Each generator can drive one GPIO pin
|
|
|
|
* Though there is more possible, we use the following capabilities:
|
|
|
|
* * Groups have an 8 bit integer prescaler from a 160MHz peripheral clock
|
|
|
|
* (the prescaler value defaults to 2)
|
|
|
|
* * Each timer has an 8 bit integer prescaler from the group clock, a 16 bit
|
|
|
|
* period, and is connected to exactly one operator
|
|
|
|
* * Each comparator in an operator acts on the corresponding timer's value and
|
|
|
|
* is connected to exactly one generator which drives exactly one GPIO pin
|
|
|
|
*
|
|
|
|
* Each MCPWM group (on ESP32/ESP32S3) gives us 3 independent "PWM groups"
|
|
|
|
* (in the STM32 sense) which contain 2 GPIO pins. The pins are assigned
|
|
|
|
* consecutively from the HAL_ESP32_RCOUT list. The frequency of each group can
|
|
|
|
* be controlled independently by changing that timer's period.
|
|
|
|
* * Running the timer at 1MHz allows 16-1000Hz with at least 1000 ticks per
|
|
|
|
* cycle and makes assigning the compare value easy
|
|
|
|
*
|
|
|
|
* MCPWM is only capable of PWM; DMA-based modes will require using the RMT
|
|
|
|
* peripheral.
|
|
|
|
*/
|
|
|
|
|
|
|
|
// each of our PWM groups has its own timer
|
|
|
|
#define MAX_GROUPS (SOC_MCPWM_GROUPS*SOC_MCPWM_TIMERS_PER_GROUP)
|
|
|
|
// we connect one timer to one operator
|
|
|
|
static_assert(SOC_MCPWM_OPERATORS_PER_GROUP >= SOC_MCPWM_TIMERS_PER_GROUP);
|
|
|
|
// and one generator to one comparator
|
|
|
|
static_assert(SOC_MCPWM_GENERATORS_PER_OPERATOR >= SOC_MCPWM_COMPARATORS_PER_OPERATOR);
|
|
|
|
|
|
|
|
#define SERVO_TIMEBASE_RESOLUTION_HZ 1000000 // 1MHz, 1us per tick, 2x80 prescaler
|
|
|
|
|
|
|
|
#define SERVO_DEFAULT_FREQ_HZ 50 // the rest of ArduPilot assumes this!
|
|
|
|
|
2021-10-27 05:43:28 -03:00
|
|
|
#define MAX_CHANNELS ARRAY_SIZE(outputs_pins)
|
2024-12-08 16:16:00 -04:00
|
|
|
static_assert(MAX_CHANNELS < 12, "overrunning _pending and safe_pwm"); // max for current chips
|
|
|
|
static_assert(MAX_CHANNELS < 32, "overrunning bitfields");
|
2021-10-27 05:43:28 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
#define NEEDED_GROUPS ((MAX_CHANNELS+SOC_MCPWM_COMPARATORS_PER_OPERATOR-1)/SOC_MCPWM_COMPARATORS_PER_OPERATOR)
|
|
|
|
static_assert(NEEDED_GROUPS <= MAX_GROUPS, "not enough hardware PWM groups");
|
|
|
|
|
|
|
|
RCOutput::pwm_group RCOutput::pwm_group_list[NEEDED_GROUPS];
|
|
|
|
RCOutput::pwm_chan RCOutput::pwm_chan_list[MAX_CHANNELS];
|
2021-10-27 05:43:28 -03:00
|
|
|
|
|
|
|
void RCOutput::init()
|
|
|
|
{
|
2024-10-09 15:02:42 -03:00
|
|
|
#ifdef CONFIG_IDF_TARGET_ESP32
|
|
|
|
// only on plain esp32
|
|
|
|
// 32 and 33 are special as they dont default to gpio, but can be if u disable their rtc setup:
|
2021-10-27 05:43:28 -03:00
|
|
|
rtc_gpio_deinit(GPIO_NUM_32);
|
|
|
|
rtc_gpio_deinit(GPIO_NUM_33);
|
2024-10-09 15:02:42 -03:00
|
|
|
#endif
|
2021-10-27 05:43:28 -03:00
|
|
|
|
|
|
|
printf("oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo\n");
|
|
|
|
printf("RCOutput::init() - channels available: %d \n",(int)MAX_CHANNELS);
|
|
|
|
printf("oooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo\n");
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
_initialized = true; // assume we are initialized, any error will call abort()
|
2024-10-09 15:02:42 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
RCOutput::pwm_group *curr_group = &pwm_group_list[0];
|
|
|
|
RCOutput::pwm_chan *curr_ch = &pwm_chan_list[0];
|
|
|
|
int chan = 0;
|
2024-10-09 15:02:42 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
// loop through all the hardware blocks and set them up. returns when we run
|
|
|
|
// out of GPIO pins (each of which is assigned in order to a PWM channel)
|
|
|
|
for (int mcpwm_group_id=0; mcpwm_group_id<SOC_MCPWM_GROUPS; mcpwm_group_id++) {
|
|
|
|
for (int timer_num=0; timer_num<SOC_MCPWM_TIMERS_PER_GROUP; timer_num++) {
|
|
|
|
RCOutput::pwm_group &group = *curr_group++;
|
2024-10-09 15:02:42 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
// set up the group to use the default frequency
|
|
|
|
group.mcpwm_group_id = mcpwm_group_id;
|
|
|
|
group.rc_frequency = SERVO_DEFAULT_FREQ_HZ;
|
|
|
|
group.ch_mask = 0;
|
2021-10-27 05:43:28 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
// create timer with default tick rate and frequency, and configure
|
|
|
|
// it to constantly run
|
|
|
|
mcpwm_timer_config_t timer_config {
|
|
|
|
.group_id = mcpwm_group_id,
|
|
|
|
.clk_src = MCPWM_TIMER_CLK_SRC_PLL160M,
|
2024-10-09 15:02:42 -03:00
|
|
|
.resolution_hz = SERVO_TIMEBASE_RESOLUTION_HZ,
|
|
|
|
.count_mode = MCPWM_TIMER_COUNT_MODE_UP,
|
2024-12-08 15:55:59 -04:00
|
|
|
.period_ticks = SERVO_TIMEBASE_RESOLUTION_HZ/SERVO_DEFAULT_FREQ_HZ,
|
2024-10-09 15:02:42 -03:00
|
|
|
};
|
2024-12-08 15:55:59 -04:00
|
|
|
ESP_ERROR_CHECK(mcpwm_new_timer(&timer_config, &group.h_timer));
|
|
|
|
ESP_ERROR_CHECK(mcpwm_timer_enable(group.h_timer));
|
|
|
|
ESP_ERROR_CHECK(mcpwm_timer_start_stop(group.h_timer, MCPWM_TIMER_START_NO_STOP));
|
2024-10-09 15:02:42 -03:00
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
// create and connect operator
|
|
|
|
mcpwm_operator_config_t operator_config {
|
|
|
|
.group_id = mcpwm_group_id,
|
2024-10-09 15:02:42 -03:00
|
|
|
};
|
2024-12-08 15:55:59 -04:00
|
|
|
ESP_ERROR_CHECK(mcpwm_new_operator(&operator_config, &group.h_oper));
|
|
|
|
ESP_ERROR_CHECK(mcpwm_operator_connect_timer(group.h_oper, group.h_timer));
|
|
|
|
|
|
|
|
for (int comparator_num=0; comparator_num<SOC_MCPWM_COMPARATORS_PER_OPERATOR; comparator_num++) {
|
|
|
|
RCOutput::pwm_chan &ch = *curr_ch++;
|
|
|
|
|
|
|
|
// set up the output to be a part of the current group
|
|
|
|
ch.group = &group;
|
|
|
|
ch.gpio_num = outputs_pins[chan];
|
|
|
|
ch.value = 0;
|
|
|
|
group.ch_mask |= (1U << chan);
|
|
|
|
|
|
|
|
// create and connect comparator
|
|
|
|
mcpwm_comparator_config_t comparator_config {
|
|
|
|
// grab new comparator value when timer is zero
|
|
|
|
.flags { .update_cmp_on_tez = true },
|
|
|
|
};
|
|
|
|
ESP_ERROR_CHECK(mcpwm_new_comparator(group.h_oper, &comparator_config, &ch.h_cmpr));
|
|
|
|
ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(ch.h_cmpr, 0)); // zero the output
|
|
|
|
|
|
|
|
// create and connect generator
|
|
|
|
mcpwm_generator_config_t generator_config {
|
|
|
|
.gen_gpio_num = outputs_pins[chan],
|
|
|
|
};
|
|
|
|
ESP_ERROR_CHECK(mcpwm_new_generator(group.h_oper, &generator_config, &ch.h_gen));
|
|
|
|
|
|
|
|
// configure it to go low on compare threshold (takes priority over going high)
|
|
|
|
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_compare_event(ch.h_gen,
|
|
|
|
MCPWM_GEN_COMPARE_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP,
|
|
|
|
ch.h_cmpr, MCPWM_GEN_ACTION_LOW)));
|
|
|
|
// and go high on counter empty
|
|
|
|
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(ch.h_gen,
|
|
|
|
MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP,
|
|
|
|
MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));
|
|
|
|
|
|
|
|
if (++chan == MAX_CHANNELS) {
|
|
|
|
return; // finished all channels; done setting up the hardware
|
|
|
|
}
|
|
|
|
}
|
2024-10-09 15:02:42 -03:00
|
|
|
}
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz)
|
|
|
|
{
|
|
|
|
if (!_initialized) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
if ((group.ch_mask & chmask) != 0) { // group has channels to set?
|
|
|
|
// greater than 400 doesn't leave enough time for the down edge
|
|
|
|
uint16_t group_freq = constrain_value((int)freq_hz, 16, 400);
|
|
|
|
ESP_ERROR_CHECK(mcpwm_timer_set_period(group.h_timer, SERVO_TIMEBASE_RESOLUTION_HZ/group_freq));
|
|
|
|
group.rc_frequency = group_freq;
|
|
|
|
|
|
|
|
// disallow changing frequency of this group if it is greater than the default
|
|
|
|
if (group_freq > SERVO_DEFAULT_FREQ_HZ) {
|
|
|
|
fast_channel_mask |= group.ch_mask;
|
|
|
|
}
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::set_default_rate(uint16_t freq_hz)
|
|
|
|
{
|
|
|
|
if (!_initialized) {
|
|
|
|
return;
|
|
|
|
}
|
2024-12-08 15:55:59 -04:00
|
|
|
|
|
|
|
for (auto &group : pwm_group_list) {
|
|
|
|
// only set frequency of groups without fast channels
|
|
|
|
if (!(group.ch_mask & fast_channel_mask) && group.ch_mask) {
|
|
|
|
set_freq(group.ch_mask, freq_hz);
|
|
|
|
// setting a high default frequency mustn't make channels fast
|
|
|
|
fast_channel_mask &= ~group.ch_mask;
|
|
|
|
}
|
|
|
|
}
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t RCOutput::get_freq(uint8_t chan)
|
|
|
|
{
|
|
|
|
if (!_initialized || chan >= MAX_CHANNELS) {
|
2024-12-08 15:55:59 -04:00
|
|
|
return SERVO_DEFAULT_FREQ_HZ;
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
pwm_group &group = *pwm_chan_list[chan].group;
|
|
|
|
return group.rc_frequency;
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::enable_ch(uint8_t chan)
|
|
|
|
{
|
|
|
|
if (!_initialized || chan >= MAX_CHANNELS) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
pwm_chan &ch = pwm_chan_list[chan];
|
2024-12-08 17:13:20 -04:00
|
|
|
// set output to high when timer == 0 like normal
|
2024-12-08 15:55:59 -04:00
|
|
|
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(ch.h_gen,
|
2024-12-08 17:13:20 -04:00
|
|
|
MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_HIGH)));
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::disable_ch(uint8_t chan)
|
|
|
|
{
|
|
|
|
if (!_initialized || chan >= MAX_CHANNELS) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
write(chan, 0);
|
2024-12-08 15:55:59 -04:00
|
|
|
pwm_chan &ch = pwm_chan_list[chan];
|
2024-12-08 17:13:20 -04:00
|
|
|
// set output to low when timer == 0, so the output is always low (after
|
|
|
|
// this cycle). conveniently avoids pulse truncation
|
2024-12-08 15:55:59 -04:00
|
|
|
ESP_ERROR_CHECK(mcpwm_generator_set_action_on_timer_event(ch.h_gen,
|
2024-12-08 17:13:20 -04:00
|
|
|
MCPWM_GEN_TIMER_EVENT_ACTION(MCPWM_TIMER_DIRECTION_UP, MCPWM_TIMER_EVENT_EMPTY, MCPWM_GEN_ACTION_LOW)));
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::write(uint8_t chan, uint16_t period_us)
|
|
|
|
{
|
|
|
|
if (!_initialized || chan >= MAX_CHANNELS) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_corked) {
|
|
|
|
_pending[chan] = period_us;
|
|
|
|
_pending_mask |= (1U<<chan);
|
|
|
|
} else {
|
|
|
|
write_int(chan, period_us);
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t RCOutput::read(uint8_t chan)
|
|
|
|
{
|
|
|
|
if (chan >= MAX_CHANNELS || !_initialized) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
pwm_chan &ch = pwm_chan_list[chan];
|
|
|
|
return ch.value;
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::read(uint16_t *period_us, uint8_t len)
|
|
|
|
{
|
2024-12-08 15:55:59 -04:00
|
|
|
for (int i = 0; i < MIN(len, MAX_CHANNELS); i++) {
|
2021-10-27 05:43:28 -03:00
|
|
|
period_us[i] = read(i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::cork()
|
|
|
|
{
|
|
|
|
_corked = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::push()
|
|
|
|
{
|
|
|
|
if (!_corked) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
|
|
|
|
for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
|
|
|
|
if ((1U<<i) & _pending_mask) {
|
|
|
|
uint32_t period_us = _pending[i];
|
|
|
|
|
|
|
|
// If safety is on and safety mask not bypassing
|
|
|
|
if (safety_on && !(safety_mask & (1U<<(i)))) {
|
|
|
|
// safety is on, overwride pwm
|
|
|
|
period_us = safe_pwm[i];
|
|
|
|
}
|
|
|
|
write_int(i, period_us);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_corked = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::timer_tick(void)
|
|
|
|
{
|
|
|
|
safety_update();
|
|
|
|
}
|
|
|
|
|
|
|
|
void RCOutput::write_int(uint8_t chan, uint16_t period_us)
|
|
|
|
{
|
|
|
|
if (!_initialized || chan >= MAX_CHANNELS) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool safety_on = hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
if (safety_on && !(safety_mask & (1U<<(chan)))) {
|
|
|
|
// safety is on, overwride pwm
|
|
|
|
period_us = safe_pwm[chan];
|
|
|
|
}
|
|
|
|
|
2024-12-08 15:55:59 -04:00
|
|
|
pwm_chan &ch = pwm_chan_list[chan];
|
|
|
|
const uint16_t max_period_us = SERVO_TIMEBASE_RESOLUTION_HZ/SERVO_DEFAULT_FREQ_HZ;
|
|
|
|
if (period_us > max_period_us) {
|
|
|
|
period_us = max_period_us;
|
|
|
|
}
|
|
|
|
ESP_ERROR_CHECK(mcpwm_comparator_set_compare_value(ch.h_cmpr, period_us));
|
|
|
|
ch.value = period_us;
|
2021-10-27 05:43:28 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
get safety switch state for Util.cpp
|
|
|
|
*/
|
|
|
|
AP_HAL::Util::safety_state RCOutput::_safety_switch_state(void)
|
|
|
|
{
|
|
|
|
if (!hal.util->was_watchdog_reset()) {
|
|
|
|
hal.util->persistent_data.safety_state = safety_state;
|
|
|
|
}
|
|
|
|
return safety_state;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
force the safety switch on, disabling PWM output from the IO board
|
|
|
|
*/
|
|
|
|
bool RCOutput::force_safety_on(void)
|
|
|
|
{
|
|
|
|
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)
|
|
|
|
{
|
|
|
|
safety_state = AP_HAL::Util::SAFETY_ARMED;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
set PWM to send to a set of channels when the safety switch is
|
|
|
|
in the safe state
|
|
|
|
*/
|
|
|
|
void RCOutput::set_safety_pwm(uint32_t chmask, uint16_t period_us)
|
|
|
|
{
|
2024-12-08 16:16:00 -04:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(safe_pwm); i++) {
|
2021-10-27 05:43:28 -03:00
|
|
|
if (chmask & (1U<<i)) {
|
|
|
|
safe_pwm[i] = period_us;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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;
|
|
|
|
|
|
|
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
|
|
|
|
|
|
|
|
if (boardconfig) {
|
|
|
|
// remember mask of channels to allow with safety on
|
|
|
|
safety_mask = boardconfig->get_safety_mask();
|
|
|
|
}
|
|
|
|
|
|
|
|
#ifdef HAL_GPIO_PIN_SAFETY_IN
|
2023-07-29 18:00:26 -03:00
|
|
|
gpio_set_direction((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN, GPIO_MODE_INPUT);
|
|
|
|
gpio_set_pull_mode((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN, GPIO_PULLDOWN_ONLY);
|
|
|
|
bool safety_pressed = gpio_get_level((gpio_num_t)HAL_GPIO_PIN_SAFETY_IN);
|
2021-10-27 05:43:28 -03:00
|
|
|
if (safety_pressed) {
|
|
|
|
AP_BoardConfig *brdconfig = AP_BoardConfig::get_singleton();
|
2024-05-01 16:51:19 -03:00
|
|
|
if (safety_press_count < UINT8_MAX) {
|
2021-10-27 05:43:28 -03:00
|
|
|
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;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
safety_press_count = 0;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#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;
|
2023-07-29 18:00:26 -03:00
|
|
|
gpio_set_level((gpio_num_t)HAL_GPIO_PIN_LED_SAFETY, (led_pattern & (1U << led_counter))?0:1);
|
2021-10-27 05:43:28 -03:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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)
|
|
|
|
{
|
|
|
|
//RIP (not the pointer)
|
|
|
|
}
|