2017-12-26 19:03:21 -04:00
|
|
|
/*
|
|
|
|
implement protocol for controlling an IO microcontroller
|
|
|
|
|
|
|
|
For bootstrapping this will initially implement the px4io protocol,
|
|
|
|
but will later move to an ArduPilot specific protocol
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "AP_IOMCU.h"
|
2018-01-02 01:47:42 -04:00
|
|
|
|
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Math/crc.h>
|
2018-04-13 03:17:08 -03:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-04-14 08:09:11 -03:00
|
|
|
#include <AP_ROMFS/AP_ROMFS.h>
|
|
|
|
#include <AP_Math/crc.h>
|
2018-10-30 21:07:47 -03:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
|
|
|
#include <RC_Channel/RC_Channel.h>
|
2018-11-05 01:44:20 -04:00
|
|
|
#include <AP_RCProtocol/AP_RCProtocol.h>
|
2017-12-26 19:03:21 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL &hal;
|
|
|
|
|
2018-05-11 03:31:04 -03:00
|
|
|
// pending IO events to send, used as an event mask
|
|
|
|
enum ioevents {
|
|
|
|
IOEVENT_INIT=1,
|
|
|
|
IOEVENT_SEND_PWM_OUT,
|
|
|
|
IOEVENT_FORCE_SAFETY_OFF,
|
|
|
|
IOEVENT_FORCE_SAFETY_ON,
|
|
|
|
IOEVENT_SET_ONESHOT_ON,
|
2018-07-12 23:28:43 -03:00
|
|
|
IOEVENT_SET_BRUSHED_ON,
|
2018-05-11 03:31:04 -03:00
|
|
|
IOEVENT_SET_RATES,
|
|
|
|
IOEVENT_ENABLE_SBUS,
|
|
|
|
IOEVENT_SET_HEATER_TARGET,
|
|
|
|
IOEVENT_SET_DEFAULT_RATE,
|
|
|
|
IOEVENT_SET_SAFETY_MASK,
|
2018-10-30 21:07:47 -03:00
|
|
|
IOEVENT_MIXING
|
2018-05-11 03:31:04 -03:00
|
|
|
};
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) :
|
|
|
|
uart(_uart)
|
|
|
|
{}
|
|
|
|
|
2018-10-30 21:07:47 -03:00
|
|
|
#if 0
|
|
|
|
#define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
|
|
|
|
#else
|
|
|
|
#define debug(fmt, args ...)
|
|
|
|
#endif
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
initialise library, starting thread
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::init(void)
|
|
|
|
{
|
2018-04-14 08:09:11 -03:00
|
|
|
// uart runs at 1.5MBit
|
|
|
|
uart.begin(1500*1000, 256, 256);
|
|
|
|
uart.set_blocking_writes(false);
|
|
|
|
uart.set_unbuffered_writes(true);
|
|
|
|
|
|
|
|
// check IO firmware CRC
|
|
|
|
hal.scheduler->delay(2000);
|
|
|
|
|
2018-05-15 23:53:23 -03:00
|
|
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_instance();
|
|
|
|
if (!boardconfig || boardconfig->io_enabled() == 1) {
|
|
|
|
check_crc();
|
2018-10-30 21:07:47 -03:00
|
|
|
} else {
|
|
|
|
crc_is_ok = true;
|
2018-05-15 23:53:23 -03:00
|
|
|
}
|
2018-07-06 21:39:24 -03:00
|
|
|
|
|
|
|
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU",
|
|
|
|
1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
|
2017-12-27 03:24:15 -04:00
|
|
|
AP_HAL::panic("Unable to allocate IOMCU thread");
|
|
|
|
}
|
2018-10-30 21:07:47 -03:00
|
|
|
initialised = true;
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
2018-01-02 02:59:20 -04:00
|
|
|
/*
|
|
|
|
handle event failure
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::event_failed(uint8_t event)
|
|
|
|
{
|
|
|
|
// wait 0.5ms then retry
|
|
|
|
hal.scheduler->delay_microseconds(500);
|
|
|
|
trigger_event(event);
|
|
|
|
}
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
main IO thread loop
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::thread_main(void)
|
2017-12-26 19:03:21 -04:00
|
|
|
{
|
2018-01-07 23:52:11 -04:00
|
|
|
thread_ctx = chThdGetSelfX();
|
2018-11-03 03:27:10 -03:00
|
|
|
chEvtSignal(thread_ctx, initial_event_mask);
|
2018-04-14 08:09:11 -03:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
uart.begin(1500*1000, 256, 256);
|
2017-12-31 22:28:59 -04:00
|
|
|
uart.set_blocking_writes(false);
|
2018-01-21 16:29:15 -04:00
|
|
|
uart.set_unbuffered_writes(true);
|
2018-04-14 08:09:11 -03:00
|
|
|
|
2018-01-02 02:59:20 -04:00
|
|
|
trigger_event(IOEVENT_INIT);
|
|
|
|
|
2018-10-29 18:50:59 -03:00
|
|
|
while (!do_shutdown) {
|
2018-06-02 12:59:33 -03:00
|
|
|
eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10));
|
2017-12-27 03:24:15 -04:00
|
|
|
|
|
|
|
// check for pending IO events
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_SEND_PWM_OUT)) {
|
|
|
|
send_servo_out();
|
|
|
|
}
|
|
|
|
|
2018-01-02 02:59:20 -04:00
|
|
|
if (mask & EVENT_MASK(IOEVENT_INIT)) {
|
2018-10-30 21:07:47 -03:00
|
|
|
// get protocol version
|
2018-11-01 03:39:24 -03:00
|
|
|
if (!read_registers(PAGE_CONFIG, 0, sizeof(config)/2, (uint16_t *)&config)) {
|
2018-10-30 21:07:47 -03:00
|
|
|
event_failed(IOEVENT_INIT);
|
|
|
|
continue;
|
|
|
|
}
|
2018-11-01 03:39:24 -03:00
|
|
|
is_chibios_backend = (config.protocol_version == IOMCU_PROTOCOL_VERSION &&
|
|
|
|
config.protocol_version2 == IOMCU_PROTOCOL_VERSION2);
|
2018-10-30 21:07:47 -03:00
|
|
|
|
2018-01-02 02:59:20 -04:00
|
|
|
// set IO_ARM_OK and FMU_ARMED
|
|
|
|
if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, 0,
|
|
|
|
P_SETUP_ARMING_IO_ARM_OK |
|
|
|
|
P_SETUP_ARMING_FMU_ARMED |
|
|
|
|
P_SETUP_ARMING_RC_HANDLING_DISABLED)) {
|
|
|
|
event_failed(IOEVENT_INIT);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-10-30 21:07:47 -03:00
|
|
|
if (mask & EVENT_MASK(IOEVENT_MIXING)) {
|
|
|
|
if (!write_registers(PAGE_MIXING, 0, sizeof(mixing)/2, (const uint16_t *)&mixing)) {
|
|
|
|
event_failed(IOEVENT_MIXING);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_OFF)) {
|
2018-01-02 02:59:20 -04:00
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_OFF, FORCE_SAFETY_MAGIC)) {
|
|
|
|
event_failed(IOEVENT_FORCE_SAFETY_OFF);
|
|
|
|
continue;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_FORCE_SAFETY_ON)) {
|
2018-01-02 02:59:20 -04:00
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_FORCE_SAFETY_ON, FORCE_SAFETY_MAGIC)) {
|
|
|
|
event_failed(IOEVENT_FORCE_SAFETY_ON);
|
|
|
|
continue;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
2017-12-27 05:15:55 -04:00
|
|
|
|
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_RATES)) {
|
2018-01-02 02:59:20 -04:00
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_ALTRATE, rate.freq) ||
|
|
|
|
!write_register(PAGE_SETUP, PAGE_REG_SETUP_PWM_RATE_MASK, rate.chmask)) {
|
|
|
|
event_failed(IOEVENT_SET_RATES);
|
|
|
|
continue;
|
|
|
|
}
|
2017-12-27 05:15:55 -04:00
|
|
|
}
|
2017-12-31 22:28:59 -04:00
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_ENABLE_SBUS)) {
|
2018-01-02 02:59:20 -04:00
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_SBUS_RATE, rate.sbus_rate_hz) ||
|
|
|
|
!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0,
|
|
|
|
P_SETUP_FEATURES_SBUS1_OUT)) {
|
|
|
|
event_failed(IOEVENT_ENABLE_SBUS);
|
|
|
|
continue;
|
|
|
|
}
|
2017-12-31 22:28:59 -04:00
|
|
|
}
|
2018-01-03 02:25:30 -04:00
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_HEATER_TARGET)) {
|
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_HEATER_DUTY_CYCLE, heater_duty_cycle)) {
|
|
|
|
event_failed(IOEVENT_SET_HEATER_TARGET);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
2018-01-12 23:52:29 -04:00
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_DEFAULT_RATE)) {
|
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_DEFAULTRATE, rate.default_freq)) {
|
|
|
|
event_failed(IOEVENT_SET_DEFAULT_RATE);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
2018-01-16 01:37:14 -04:00
|
|
|
|
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_ONESHOT_ON)) {
|
|
|
|
if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_ONESHOT)) {
|
|
|
|
event_failed(IOEVENT_SET_ONESHOT_ON);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
2018-04-14 00:54:04 -03:00
|
|
|
|
2018-07-12 23:28:43 -03:00
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_BRUSHED_ON)) {
|
|
|
|
if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_FEATURES, 0, P_SETUP_FEATURES_BRUSHED)) {
|
|
|
|
event_failed(IOEVENT_SET_BRUSHED_ON);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-14 00:54:04 -03:00
|
|
|
if (mask & EVENT_MASK(IOEVENT_SET_SAFETY_MASK)) {
|
|
|
|
if (!write_register(PAGE_SETUP, PAGE_REG_SETUP_IGNORE_SAFETY, pwm_out.safety_mask)) {
|
|
|
|
event_failed(IOEVENT_SET_SAFETY_MASK);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
}
|
2018-10-30 21:07:47 -03:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
// check for regular timed events
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - last_rc_read_ms > 20) {
|
|
|
|
// read RC input at 50Hz
|
|
|
|
read_rc_input();
|
|
|
|
last_rc_read_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
if (now - last_status_read_ms > 50) {
|
|
|
|
// read status at 20Hz
|
|
|
|
read_status();
|
|
|
|
last_status_read_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
|
|
|
if (now - last_servo_read_ms > 50) {
|
|
|
|
// read servo out at 20Hz
|
|
|
|
read_servo();
|
|
|
|
last_servo_read_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
2018-04-13 18:00:26 -03:00
|
|
|
#ifdef IOMCU_DEBUG
|
2017-12-27 03:24:15 -04:00
|
|
|
if (now - last_debug_ms > 1000) {
|
|
|
|
print_debug();
|
|
|
|
last_debug_ms = AP_HAL::millis();
|
|
|
|
}
|
2018-04-13 18:00:26 -03:00
|
|
|
#endif // IOMCU_DEBUG
|
2018-04-13 03:17:08 -03:00
|
|
|
|
|
|
|
if (now - last_safety_option_check_ms > 1000) {
|
|
|
|
update_safety_options();
|
|
|
|
last_safety_option_check_ms = now;
|
|
|
|
}
|
2018-04-14 00:54:04 -03:00
|
|
|
|
|
|
|
// update safety pwm
|
|
|
|
if (pwm_out.safety_pwm_set != pwm_out.safety_pwm_sent) {
|
|
|
|
uint8_t set = pwm_out.safety_pwm_set;
|
2018-10-30 23:10:51 -03:00
|
|
|
if (write_registers(PAGE_SAFETY_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.safety_pwm)) {
|
2018-09-12 17:22:26 -03:00
|
|
|
pwm_out.safety_pwm_sent = set;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// update failsafe pwm
|
|
|
|
if (pwm_out.failsafe_pwm_set != pwm_out.failsafe_pwm_sent) {
|
|
|
|
uint8_t set = pwm_out.failsafe_pwm_set;
|
|
|
|
if (write_registers(PAGE_FAILSAFE_PWM, 0, IOMCU_MAX_CHANNELS, pwm_out.failsafe_pwm)) {
|
|
|
|
pwm_out.failsafe_pwm_sent = set;
|
|
|
|
}
|
2018-04-14 00:54:04 -03:00
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
2018-10-29 18:50:59 -03:00
|
|
|
done_shutdown = true;
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
send servo output data
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::send_servo_out()
|
|
|
|
{
|
2018-09-12 17:22:26 -03:00
|
|
|
#if 0
|
|
|
|
// simple method to test IO failsafe
|
|
|
|
if (AP_HAL::millis() > 30000) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2017-12-27 03:24:15 -04:00
|
|
|
if (pwm_out.num_channels > 0) {
|
2018-01-16 06:21:59 -04:00
|
|
|
uint8_t n = pwm_out.num_channels;
|
|
|
|
if (rate.sbus_rate_hz == 0) {
|
|
|
|
n = MIN(n, 8);
|
2018-10-30 21:07:47 -03:00
|
|
|
} else {
|
|
|
|
n = MIN(n, IOMCU_MAX_CHANNELS);
|
2018-01-16 06:21:59 -04:00
|
|
|
}
|
|
|
|
uint32_t now = AP_HAL::micros();
|
|
|
|
if (now - last_servo_out_us >= 2000) {
|
|
|
|
// don't send data at more than 500Hz
|
2018-09-12 17:22:26 -03:00
|
|
|
if (write_registers(PAGE_DIRECT_PWM, 0, n, pwm_out.pwm)) {
|
|
|
|
last_servo_out_us = now;
|
|
|
|
}
|
2018-01-16 06:21:59 -04:00
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
read RC input
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::read_rc_input()
|
|
|
|
{
|
2018-01-16 06:21:59 -04:00
|
|
|
// read a min of 9 channels and max of IOMCU_MAX_CHANNELS
|
|
|
|
uint8_t n = MIN(MAX(9, rc_input.count), IOMCU_MAX_CHANNELS);
|
2017-12-27 18:26:11 -04:00
|
|
|
read_registers(PAGE_RAW_RCIN, 0, 6+n, (uint16_t *)&rc_input);
|
2018-07-18 16:57:22 -03:00
|
|
|
if (rc_input.flags_rc_ok && !rc_input.flags_failsafe) {
|
2018-11-01 21:03:33 -03:00
|
|
|
rc_input.last_input_ms = AP_HAL::millis();
|
2017-12-31 22:28:59 -04:00
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
read status registers
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::read_status()
|
2017-12-26 19:03:21 -04:00
|
|
|
{
|
2017-12-31 22:28:59 -04:00
|
|
|
uint16_t *r = (uint16_t *)®_status;
|
|
|
|
read_registers(PAGE_STATUS, 0, sizeof(reg_status)/2, r);
|
2018-09-03 23:16:19 -03:00
|
|
|
|
|
|
|
if (reg_status.flag_safety_off == 0) {
|
|
|
|
// if the IOMCU is indicating that safety is on, then force a
|
|
|
|
// re-check of the safety options. This copes with a IOMCU reset
|
|
|
|
last_safety_options = 0xFFFF;
|
|
|
|
|
|
|
|
// also check if the safety should be definately off.
|
|
|
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_instance();
|
|
|
|
if (!boardconfig) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint16_t options = boardconfig->get_safety_button_options();
|
|
|
|
if (safety_forced_off && (options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON) == 0) {
|
|
|
|
// the safety has been forced off, and the user has asked
|
|
|
|
// that the button can never be used, so there should be
|
|
|
|
// no way for the safety to be on except a IOMCU
|
|
|
|
// reboot. Force safety off again
|
|
|
|
force_safety_off();
|
|
|
|
}
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
/*
|
|
|
|
read servo output values
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::read_servo()
|
|
|
|
{
|
|
|
|
if (pwm_out.num_channels > 0) {
|
|
|
|
read_registers(PAGE_SERVOS, 0, pwm_out.num_channels, pwm_in.pwm);
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
discard any pending input
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::discard_input(void)
|
|
|
|
{
|
2018-01-22 18:04:01 -04:00
|
|
|
uint32_t n = uart.available();
|
2017-12-27 03:24:15 -04:00
|
|
|
while (n--) {
|
|
|
|
uart.read();
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
read count 16 bit registers
|
|
|
|
*/
|
|
|
|
bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint16_t *regs)
|
|
|
|
{
|
2018-10-30 21:07:47 -03:00
|
|
|
while (count > PKT_MAX_REGS) {
|
|
|
|
if (!read_registers(page, offset, PKT_MAX_REGS, regs)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
offset += PKT_MAX_REGS;
|
|
|
|
count -= PKT_MAX_REGS;
|
|
|
|
regs += PKT_MAX_REGS;
|
|
|
|
}
|
|
|
|
|
2017-12-26 19:03:21 -04:00
|
|
|
IOPacket pkt;
|
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
discard_input();
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
memset(&pkt.regs[0], 0, count*2);
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
pkt.code = CODE_READ;
|
|
|
|
pkt.count = count;
|
|
|
|
pkt.page = page;
|
|
|
|
pkt.offset = offset;
|
|
|
|
pkt.crc = 0;
|
2018-10-30 21:24:51 -03:00
|
|
|
|
|
|
|
uint8_t pkt_size = pkt.get_size();
|
2018-11-01 03:39:24 -03:00
|
|
|
if (is_chibios_backend) {
|
2018-10-30 21:24:51 -03:00
|
|
|
// save bandwidth on reads
|
|
|
|
pkt_size = 4;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
the protocol is a bit strange, as it unnecessarily sends the
|
|
|
|
same size packet that it expects to receive. This means reading
|
|
|
|
a large number of registers wastes a lot of serial bandwidth
|
|
|
|
*/
|
2018-10-30 21:24:51 -03:00
|
|
|
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size);
|
|
|
|
if (uart.write((uint8_t *)&pkt, pkt_size) != pkt_size) {
|
2018-10-30 21:07:47 -03:00
|
|
|
protocol_fail_count++;
|
2018-01-22 15:18:28 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
|
|
|
|
// wait for the expected number of reply bytes or timeout
|
|
|
|
if (!uart.wait_timeout(count*2+4, 10)) {
|
|
|
|
return false;
|
|
|
|
}
|
2017-12-26 19:03:21 -04:00
|
|
|
|
2017-12-27 03:24:15 -04:00
|
|
|
uint8_t *b = (uint8_t *)&pkt;
|
2017-12-26 19:03:21 -04:00
|
|
|
uint8_t n = uart.available();
|
2017-12-27 03:24:15 -04:00
|
|
|
for (uint8_t i=0; i<n; i++) {
|
|
|
|
if (i < sizeof(pkt)) {
|
2017-12-26 19:03:21 -04:00
|
|
|
b[i] = uart.read();
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t got_crc = pkt.crc;
|
|
|
|
pkt.crc = 0;
|
|
|
|
uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
|
|
|
|
if (got_crc != expected_crc) {
|
2018-10-30 21:07:47 -03:00
|
|
|
debug("bad crc %02x should be %02x n=%u %u/%u/%u\n",
|
|
|
|
got_crc, expected_crc,
|
|
|
|
n, page, offset, count);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (pkt.code != CODE_SUCCESS) {
|
2018-10-30 21:07:47 -03:00
|
|
|
debug("bad code %02x read %u/%u/%u\n", pkt.code, page, offset, count);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (pkt.count < count) {
|
2018-10-30 21:07:47 -03:00
|
|
|
debug("bad count %u read %u/%u/%u n=%u\n", pkt.count, page, offset, count, n);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
memcpy(regs, pkt.regs, count*2);
|
2018-10-30 21:07:47 -03:00
|
|
|
protocol_fail_count = 0;
|
2017-12-27 03:24:15 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
write count 16 bit registers
|
|
|
|
*/
|
|
|
|
bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs)
|
|
|
|
{
|
2018-10-30 21:07:47 -03:00
|
|
|
while (count > PKT_MAX_REGS) {
|
|
|
|
if (!write_registers(page, offset, PKT_MAX_REGS, regs)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
offset += PKT_MAX_REGS;
|
|
|
|
count -= PKT_MAX_REGS;
|
|
|
|
regs += PKT_MAX_REGS;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
IOPacket pkt;
|
|
|
|
|
|
|
|
discard_input();
|
|
|
|
|
|
|
|
memset(&pkt.regs[0], 0, count*2);
|
|
|
|
|
|
|
|
pkt.code = CODE_WRITE;
|
|
|
|
pkt.count = count;
|
|
|
|
pkt.page = page;
|
|
|
|
pkt.offset = offset;
|
|
|
|
pkt.crc = 0;
|
|
|
|
memcpy(pkt.regs, regs, 2*count);
|
|
|
|
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
|
2018-01-22 15:18:28 -04:00
|
|
|
if (uart.write((uint8_t *)&pkt, pkt.get_size()) != pkt.get_size()) {
|
2018-10-30 21:07:47 -03:00
|
|
|
protocol_fail_count++;
|
2018-01-22 15:18:28 -04:00
|
|
|
return false;
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
|
|
|
|
// wait for the expected number of reply bytes or timeout
|
|
|
|
if (!uart.wait_timeout(4, 10)) {
|
2018-10-30 21:07:47 -03:00
|
|
|
//debug("no reply for %u/%u/%u\n", page, offset, count);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t *b = (uint8_t *)&pkt;
|
|
|
|
uint8_t n = uart.available();
|
|
|
|
for (uint8_t i=0; i<n; i++) {
|
|
|
|
if (i < sizeof(pkt)) {
|
|
|
|
b[i] = uart.read();
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
|
|
|
|
if (pkt.code != CODE_SUCCESS) {
|
2018-10-30 21:07:47 -03:00
|
|
|
debug("bad code %02x write %u/%u/%u %02x/%02x n=%u\n",
|
|
|
|
pkt.code, page, offset, count,
|
|
|
|
pkt.page, pkt.offset, n);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
uint8_t got_crc = pkt.crc;
|
|
|
|
pkt.crc = 0;
|
|
|
|
uint8_t expected_crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
|
|
|
|
if (got_crc != expected_crc) {
|
2018-10-30 21:07:47 -03:00
|
|
|
debug("bad crc %02x should be %02x\n", got_crc, expected_crc);
|
|
|
|
protocol_fail_count++;
|
2017-12-27 03:24:15 -04:00
|
|
|
return false;
|
|
|
|
}
|
2018-10-30 21:07:47 -03:00
|
|
|
protocol_fail_count = 0;
|
2017-12-27 03:24:15 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// modify a single register
|
|
|
|
bool AP_IOMCU::modify_register(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t setbits)
|
|
|
|
{
|
|
|
|
uint16_t v = 0;
|
|
|
|
if (!read_registers(page, offset, 1, &v)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
uint16_t v2 = (v & ~clearbits) | setbits;
|
|
|
|
if (v2 == v) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return write_registers(page, offset, 1, &v2);
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm)
|
|
|
|
{
|
2018-01-16 06:21:59 -04:00
|
|
|
if (chan >= IOMCU_MAX_CHANNELS) {
|
2017-12-27 03:24:15 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (chan >= pwm_out.num_channels) {
|
|
|
|
pwm_out.num_channels = chan+1;
|
|
|
|
}
|
|
|
|
pwm_out.pwm[chan] = pwm;
|
|
|
|
if (!corked) {
|
|
|
|
push();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_IOMCU::print_debug(void)
|
|
|
|
{
|
2018-04-13 18:00:26 -03:00
|
|
|
#ifdef IOMCU_DEBUG
|
2017-12-27 03:24:15 -04:00
|
|
|
const uint16_t *r = (const uint16_t *)®_status;
|
|
|
|
for (uint8_t i=0; i<sizeof(reg_status)/2; i++) {
|
|
|
|
hal.console->printf("%04x ", r[i]);
|
|
|
|
}
|
|
|
|
hal.console->printf("\n");
|
2018-04-13 18:00:26 -03:00
|
|
|
#endif // IOMCU_DEBUG
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// trigger an ioevent
|
|
|
|
void AP_IOMCU::trigger_event(uint8_t event)
|
|
|
|
{
|
2018-01-12 22:33:28 -04:00
|
|
|
if (thread_ctx != nullptr) {
|
|
|
|
chEvtSignal(thread_ctx, EVENT_MASK(event));
|
2018-11-03 03:27:10 -03:00
|
|
|
} else {
|
|
|
|
// thread isn't started yet, trigger this event once it is started
|
|
|
|
initial_event_mask |= EVENT_MASK(event);
|
2018-01-12 22:33:28 -04:00
|
|
|
}
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// get state of safety switch
|
|
|
|
AP_HAL::Util::safety_state AP_IOMCU::get_safety_switch_state(void) const
|
|
|
|
{
|
|
|
|
return reg_status.flag_safety_off?AP_HAL::Util::SAFETY_ARMED:AP_HAL::Util::SAFETY_DISARMED;
|
|
|
|
}
|
|
|
|
|
|
|
|
// force safety on
|
|
|
|
bool AP_IOMCU::force_safety_on(void)
|
|
|
|
{
|
|
|
|
trigger_event(IOEVENT_FORCE_SAFETY_ON);
|
2018-09-03 23:16:19 -03:00
|
|
|
safety_forced_off = false;
|
2017-12-27 03:24:15 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// force safety off
|
|
|
|
void AP_IOMCU::force_safety_off(void)
|
|
|
|
{
|
|
|
|
trigger_event(IOEVENT_FORCE_SAFETY_OFF);
|
2018-09-03 23:16:19 -03:00
|
|
|
safety_forced_off = true;
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// read from one channel
|
|
|
|
uint16_t AP_IOMCU::read_channel(uint8_t chan)
|
|
|
|
{
|
|
|
|
return pwm_in.pwm[chan];
|
|
|
|
}
|
|
|
|
|
|
|
|
// cork output
|
|
|
|
void AP_IOMCU::cork(void)
|
|
|
|
{
|
|
|
|
corked = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// push output
|
|
|
|
void AP_IOMCU::push(void)
|
|
|
|
{
|
|
|
|
trigger_event(IOEVENT_SEND_PWM_OUT);
|
|
|
|
corked = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// set output frequency
|
|
|
|
void AP_IOMCU::set_freq(uint16_t chmask, uint16_t freq)
|
|
|
|
{
|
2018-07-28 00:44:49 -03:00
|
|
|
const uint8_t masks[] = { 0x03,0x0C,0xF0 };
|
|
|
|
// ensure mask is legal for the timer layout
|
2018-08-02 20:27:17 -03:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(masks); i++) {
|
2018-07-28 00:44:49 -03:00
|
|
|
if (chmask & masks[i]) {
|
|
|
|
chmask |= masks[i];
|
|
|
|
}
|
|
|
|
}
|
2017-12-27 05:15:55 -04:00
|
|
|
rate.freq = freq;
|
2018-07-28 00:44:49 -03:00
|
|
|
rate.chmask |= chmask;
|
2017-12-27 05:15:55 -04:00
|
|
|
trigger_event(IOEVENT_SET_RATES);
|
2017-12-27 03:24:15 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// get output frequency
|
|
|
|
uint16_t AP_IOMCU::get_freq(uint16_t chan)
|
|
|
|
{
|
2017-12-27 05:15:55 -04:00
|
|
|
if ((1U<<chan) & rate.chmask) {
|
|
|
|
return rate.freq;
|
|
|
|
}
|
|
|
|
return rate.default_freq;
|
2017-12-26 19:03:21 -04:00
|
|
|
}
|
2017-12-31 22:28:59 -04:00
|
|
|
|
|
|
|
// enable SBUS out
|
|
|
|
bool AP_IOMCU::enable_sbus_out(uint16_t rate_hz)
|
|
|
|
{
|
|
|
|
rate.sbus_rate_hz = rate_hz;
|
|
|
|
trigger_event(IOEVENT_ENABLE_SBUS);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
check for new RC input
|
|
|
|
*/
|
|
|
|
bool AP_IOMCU::check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_chan)
|
|
|
|
{
|
2018-11-01 21:03:33 -03:00
|
|
|
if (last_frame_us != uint32_t(rc_input.last_input_ms * 1000U)) {
|
2018-01-16 06:21:59 -04:00
|
|
|
num_channels = MIN(MIN(rc_input.count, IOMCU_MAX_CHANNELS), max_chan);
|
2017-12-31 22:28:59 -04:00
|
|
|
memcpy(channels, rc_input.pwm, num_channels*2);
|
2018-11-01 21:03:33 -03:00
|
|
|
last_frame_us = uint32_t(rc_input.last_input_ms * 1000U);
|
2017-12-31 22:28:59 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2018-01-02 01:47:42 -04:00
|
|
|
|
2018-01-03 02:25:30 -04:00
|
|
|
// set IMU heater target
|
|
|
|
void AP_IOMCU::set_heater_duty_cycle(uint8_t duty_cycle)
|
|
|
|
{
|
|
|
|
heater_duty_cycle = duty_cycle;
|
|
|
|
trigger_event(IOEVENT_SET_HEATER_TARGET);
|
|
|
|
}
|
|
|
|
|
2018-01-12 23:52:29 -04:00
|
|
|
// set default output rate
|
|
|
|
void AP_IOMCU::set_default_rate(uint16_t rate_hz)
|
|
|
|
{
|
2018-01-22 15:18:28 -04:00
|
|
|
if (rate.default_freq != rate_hz) {
|
|
|
|
rate.default_freq = rate_hz;
|
|
|
|
trigger_event(IOEVENT_SET_DEFAULT_RATE);
|
|
|
|
}
|
2018-01-12 23:52:29 -04:00
|
|
|
}
|
|
|
|
|
2018-01-16 01:37:14 -04:00
|
|
|
// setup for oneshot mode
|
|
|
|
void AP_IOMCU::set_oneshot_mode(void)
|
|
|
|
{
|
|
|
|
trigger_event(IOEVENT_SET_ONESHOT_ON);
|
|
|
|
}
|
|
|
|
|
2018-07-12 23:28:43 -03:00
|
|
|
// setup for brushed mode
|
|
|
|
void AP_IOMCU::set_brushed_mode(void)
|
|
|
|
{
|
|
|
|
trigger_event(IOEVENT_SET_BRUSHED_ON);
|
|
|
|
}
|
|
|
|
|
2018-04-13 03:17:08 -03:00
|
|
|
// handling of BRD_SAFETYOPTION parameter
|
|
|
|
void AP_IOMCU::update_safety_options(void)
|
|
|
|
{
|
|
|
|
AP_BoardConfig *boardconfig = AP_BoardConfig::get_instance();
|
|
|
|
if (!boardconfig) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint16_t desired_options = 0;
|
|
|
|
uint16_t options = boardconfig->get_safety_button_options();
|
|
|
|
if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {
|
|
|
|
desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_OFF;
|
|
|
|
}
|
|
|
|
if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {
|
|
|
|
desired_options |= P_SETUP_ARMING_SAFETY_DISABLE_ON;
|
|
|
|
}
|
|
|
|
if (!(options & AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) && hal.util->get_soft_armed()) {
|
|
|
|
desired_options |= (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
|
|
|
|
}
|
|
|
|
if (last_safety_options != desired_options) {
|
|
|
|
uint16_t mask = (P_SETUP_ARMING_SAFETY_DISABLE_ON | P_SETUP_ARMING_SAFETY_DISABLE_OFF);
|
2018-04-13 18:00:26 -03:00
|
|
|
uint32_t bits_to_set = desired_options & mask;
|
|
|
|
uint32_t bits_to_clear = (~desired_options) & mask;
|
2018-04-13 03:17:08 -03:00
|
|
|
if (modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, bits_to_clear, bits_to_set)) {
|
|
|
|
last_safety_options = desired_options;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-14 08:09:11 -03:00
|
|
|
/*
|
|
|
|
check ROMFS firmware against CRC on IOMCU, and if incorrect then upload new firmware
|
|
|
|
*/
|
|
|
|
bool AP_IOMCU::check_crc(void)
|
|
|
|
{
|
|
|
|
// flash size minus 4k bootloader
|
|
|
|
const uint32_t flash_size = 0x10000 - 0x1000;
|
|
|
|
|
2018-07-09 03:47:35 -03:00
|
|
|
fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
2018-04-14 08:09:11 -03:00
|
|
|
if (!fw) {
|
|
|
|
hal.console->printf("failed to find %s\n", fw_name);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
uint32_t crc = crc_crc32(0, fw, fw_size);
|
|
|
|
|
2018-07-10 20:51:43 -03:00
|
|
|
// pad CRC to max size
|
|
|
|
for (uint32_t i=0; i<flash_size-fw_size; i++) {
|
2018-04-14 08:09:11 -03:00
|
|
|
uint8_t b = 0xff;
|
|
|
|
crc = crc_crc32(crc, &b, 1);
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t io_crc = 0;
|
2018-10-29 18:50:59 -03:00
|
|
|
uint8_t tries = 32;
|
|
|
|
while (tries--) {
|
|
|
|
if (read_registers(PAGE_SETUP, PAGE_REG_SETUP_CRC, 2, (uint16_t *)&io_crc)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (io_crc == crc) {
|
2018-04-14 08:09:11 -03:00
|
|
|
hal.console->printf("IOMCU: CRC ok\n");
|
2018-04-16 19:04:33 -03:00
|
|
|
crc_is_ok = true;
|
2018-07-09 03:47:35 -03:00
|
|
|
free(fw);
|
|
|
|
fw = nullptr;
|
2018-04-14 08:09:11 -03:00
|
|
|
return true;
|
2018-05-05 15:16:52 -03:00
|
|
|
} else {
|
2018-09-14 07:00:43 -03:00
|
|
|
hal.console->printf("IOMCU: CRC mismatch expected: 0x%X got: 0x%X\n", (unsigned)crc, (unsigned)io_crc);
|
2018-04-14 08:09:11 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
const uint16_t magic = REBOOT_BL_MAGIC;
|
|
|
|
write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
|
|
|
|
|
2018-07-09 03:47:35 -03:00
|
|
|
if (!upload_fw()) {
|
|
|
|
free(fw);
|
|
|
|
fw = nullptr;
|
2018-05-15 23:53:23 -03:00
|
|
|
AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
|
|
|
|
}
|
|
|
|
|
2018-07-09 03:47:35 -03:00
|
|
|
free(fw);
|
|
|
|
fw = nullptr;
|
2018-04-14 08:09:11 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-04-14 00:54:04 -03:00
|
|
|
/*
|
|
|
|
set the pwm to use when safety is on
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::set_safety_pwm(uint16_t chmask, uint16_t period_us)
|
|
|
|
{
|
|
|
|
bool changed = false;
|
|
|
|
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
|
|
|
|
if (chmask & (1U<<i)) {
|
|
|
|
if (pwm_out.safety_pwm[i] != period_us) {
|
|
|
|
pwm_out.safety_pwm[i] = period_us;
|
|
|
|
changed = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (changed) {
|
|
|
|
pwm_out.safety_pwm_set++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-09-12 17:22:26 -03:00
|
|
|
/*
|
|
|
|
set the pwm to use when in FMU failsafe
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::set_failsafe_pwm(uint16_t chmask, uint16_t period_us)
|
|
|
|
{
|
|
|
|
bool changed = false;
|
|
|
|
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
|
|
|
|
if (chmask & (1U<<i)) {
|
|
|
|
if (pwm_out.failsafe_pwm[i] != period_us) {
|
|
|
|
pwm_out.failsafe_pwm[i] = period_us;
|
|
|
|
changed = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (changed) {
|
|
|
|
pwm_out.failsafe_pwm_set++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-14 00:54:04 -03:00
|
|
|
|
|
|
|
// set mask of channels that ignore safety state
|
|
|
|
void AP_IOMCU::set_safety_mask(uint16_t chmask)
|
|
|
|
{
|
|
|
|
if (pwm_out.safety_mask != chmask) {
|
|
|
|
pwm_out.safety_mask = chmask;
|
|
|
|
trigger_event(IOEVENT_SET_SAFETY_MASK);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-16 19:04:33 -03:00
|
|
|
/*
|
|
|
|
check that IO is healthy. This should be used in arming checks
|
|
|
|
*/
|
|
|
|
bool AP_IOMCU::healthy(void)
|
|
|
|
{
|
2018-10-30 21:07:47 -03:00
|
|
|
return crc_is_ok && protocol_fail_count == 0;
|
2018-04-16 19:04:33 -03:00
|
|
|
}
|
|
|
|
|
2018-10-29 18:50:59 -03:00
|
|
|
/*
|
|
|
|
shutdown protocol, ready for reboot
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::shutdown(void)
|
|
|
|
{
|
|
|
|
do_shutdown = true;
|
|
|
|
while (!done_shutdown) {
|
|
|
|
hal.scheduler->delay(1);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-08-26 12:06:10 -03:00
|
|
|
/*
|
|
|
|
request bind on a DSM radio
|
|
|
|
*/
|
|
|
|
void AP_IOMCU::bind_dsm(uint8_t mode)
|
|
|
|
{
|
2018-11-01 03:39:24 -03:00
|
|
|
if (!is_chibios_backend || hal.util->get_soft_armed()) {
|
2018-08-26 12:06:10 -03:00
|
|
|
// only with ChibiOS IO firmware, and disarmed
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint16_t reg = mode;
|
2018-10-31 19:18:13 -03:00
|
|
|
write_registers(PAGE_SETUP, PAGE_REG_SETUP_DSM_BIND, 1, ®);
|
2018-08-26 12:06:10 -03:00
|
|
|
}
|
|
|
|
|
2018-10-30 21:07:47 -03:00
|
|
|
/*
|
|
|
|
setup for mixing. This allows fixed wing aircraft to fly in manual
|
|
|
|
mode if the FMU dies
|
|
|
|
*/
|
2018-10-31 01:09:49 -03:00
|
|
|
bool AP_IOMCU::setup_mixing(RCMapper *rcmap, int8_t override_chan,
|
|
|
|
float mixing_gain, uint16_t manual_rc_mask)
|
2018-10-30 21:07:47 -03:00
|
|
|
{
|
2018-11-01 03:39:24 -03:00
|
|
|
if (!is_chibios_backend) {
|
2018-10-30 21:07:47 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
bool changed = false;
|
|
|
|
#define MIX_UPDATE(a,b) do { if ((a) != (b)) { a = b; changed = true; }} while (0)
|
|
|
|
|
|
|
|
// update mixing structure, checking for changes
|
|
|
|
for (uint8_t i=0; i<IOMCU_MAX_CHANNELS; i++) {
|
|
|
|
const SRV_Channel *ch = SRV_Channels::srv_channel(i);
|
|
|
|
if (!ch) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
MIX_UPDATE(mixing.servo_trim[i], ch->get_trim());
|
|
|
|
MIX_UPDATE(mixing.servo_min[i], ch->get_output_min());
|
|
|
|
MIX_UPDATE(mixing.servo_max[i], ch->get_output_max());
|
|
|
|
MIX_UPDATE(mixing.servo_function[i], ch->get_function());
|
2018-10-30 23:10:51 -03:00
|
|
|
MIX_UPDATE(mixing.servo_reversed[i], ch->get_reversed());
|
2018-10-30 21:07:47 -03:00
|
|
|
}
|
|
|
|
// update RCMap
|
|
|
|
MIX_UPDATE(mixing.rc_channel[0], rcmap->roll());
|
|
|
|
MIX_UPDATE(mixing.rc_channel[1], rcmap->pitch());
|
|
|
|
MIX_UPDATE(mixing.rc_channel[2], rcmap->throttle());
|
|
|
|
MIX_UPDATE(mixing.rc_channel[3], rcmap->yaw());
|
|
|
|
for (uint8_t i=0; i<4; i++) {
|
|
|
|
const RC_Channel *ch = RC_Channels::rc_channel(mixing.rc_channel[i]-1);
|
|
|
|
if (!ch) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
MIX_UPDATE(mixing.rc_min[i], ch->get_radio_min());
|
|
|
|
MIX_UPDATE(mixing.rc_max[i], ch->get_radio_max());
|
|
|
|
MIX_UPDATE(mixing.rc_trim[i], ch->get_radio_trim());
|
2018-10-30 23:10:51 -03:00
|
|
|
MIX_UPDATE(mixing.rc_reversed[i], ch->get_reverse());
|
|
|
|
|
|
|
|
// cope with reversible throttle
|
|
|
|
if (i == 2 && ch->get_type() == RC_Channel::RC_CHANNEL_TYPE_ANGLE) {
|
|
|
|
MIX_UPDATE(mixing.throttle_is_angle, 1);
|
|
|
|
} else {
|
|
|
|
MIX_UPDATE(mixing.throttle_is_angle, 0);
|
|
|
|
}
|
2018-10-30 21:07:47 -03:00
|
|
|
}
|
2018-10-30 23:10:51 -03:00
|
|
|
|
2018-10-30 21:07:47 -03:00
|
|
|
MIX_UPDATE(mixing.rc_chan_override, override_chan);
|
2018-10-31 00:16:17 -03:00
|
|
|
MIX_UPDATE(mixing.mixing_gain, (uint16_t)(mixing_gain*1000));
|
2018-10-31 01:09:49 -03:00
|
|
|
MIX_UPDATE(mixing.manual_rc_mask, manual_rc_mask);
|
2018-10-30 23:10:51 -03:00
|
|
|
|
2018-10-30 21:07:47 -03:00
|
|
|
// and enable
|
|
|
|
MIX_UPDATE(mixing.enabled, 1);
|
|
|
|
if (changed) {
|
|
|
|
trigger_event(IOEVENT_MIXING);
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2018-11-05 01:44:20 -04:00
|
|
|
/*
|
|
|
|
return the RC protocol name
|
|
|
|
*/
|
|
|
|
const char *AP_IOMCU::get_rc_protocol(void)
|
|
|
|
{
|
|
|
|
if (!is_chibios_backend) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return AP_RCProtocol::protocol_name_from_protocol((AP_RCProtocol::rcprotocol_t)rc_input.data);
|
|
|
|
}
|
|
|
|
|
2018-01-02 01:47:42 -04:00
|
|
|
#endif // HAL_WITH_IO_MCU
|