mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: add support for getting output mode and mcuid
give an appropriate MCUID on F103
This commit is contained in:
parent
2dd4f3f581
commit
7b96f66413
|
@ -58,7 +58,7 @@ AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) :
|
|||
singleton = this;
|
||||
}
|
||||
|
||||
#define IOMCU_DEBUG_ENABLE 1
|
||||
#define IOMCU_DEBUG_ENABLE 0
|
||||
|
||||
#if IOMCU_DEBUG_ENABLE
|
||||
#include <stdio.h>
|
||||
|
@ -140,6 +140,8 @@ void AP_IOMCU::thread_main(void)
|
|||
is_chibios_backend = (config.protocol_version == IOMCU_PROTOCOL_VERSION &&
|
||||
config.protocol_version2 == IOMCU_PROTOCOL_VERSION2);
|
||||
|
||||
DEV_PRINTF("IOMCU: 0x%lx\n", config.mcuid);
|
||||
|
||||
// set IO_ARM_OK and FMU_ARMED
|
||||
if (!modify_register(PAGE_SETUP, PAGE_REG_SETUP_ARMING, 0,
|
||||
P_SETUP_ARMING_IO_ARM_OK |
|
||||
|
@ -863,6 +865,12 @@ void AP_IOMCU::set_output_mode(uint16_t mask, uint16_t mode)
|
|||
trigger_event(IOEVENT_SET_OUTPUT_MODE);
|
||||
}
|
||||
|
||||
AP_HAL::RCOutput::output_mode AP_IOMCU::get_output_mode(uint8_t& mask) const
|
||||
{
|
||||
mask = reg_status.rcout_mask;
|
||||
return AP_HAL::RCOutput::output_mode(reg_status.rcout_mode);
|
||||
}
|
||||
|
||||
// setup channels
|
||||
void AP_IOMCU::enable_ch(uint8_t ch)
|
||||
{
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
|
||||
#include "iofirmware/ioprotocol.h"
|
||||
#include <AP_RCMapper/AP_RCMapper.h>
|
||||
#include <AP_HAL/RCOutput.h>
|
||||
|
||||
typedef uint32_t eventmask_t;
|
||||
typedef struct ch_thread thread_t;
|
||||
|
@ -101,6 +102,12 @@ public:
|
|||
// set output mode
|
||||
void set_output_mode(uint16_t mask, uint16_t mode);
|
||||
|
||||
// get output mode
|
||||
AP_HAL::RCOutput::output_mode get_output_mode(uint8_t& mask) const;
|
||||
|
||||
// MCUID
|
||||
uint32_t get_mcu_id() const { return config.mcuid; }
|
||||
|
||||
#if HAL_DSHOT_ENABLED
|
||||
// set dshot output period
|
||||
void set_dshot_period(uint16_t period_us, uint8_t drate);
|
||||
|
|
|
@ -38,6 +38,9 @@ static AP_IOMCU_FW iomcu;
|
|||
void setup();
|
||||
void loop();
|
||||
|
||||
#undef CH_DBG_ENABLE_STACK_CHECK
|
||||
#define CH_DBG_ENABLE_STACK_CHECK FALSE
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
/*
|
||||
|
@ -198,11 +201,8 @@ using namespace ChibiOS;
|
|||
copy of uart_lld_serve_tx_end_irq() from ChibiOS hal_uart_lld
|
||||
that is re-instated upon switching the DMA channel
|
||||
*/
|
||||
static void uart_lld_serve_tx_end_irq(hal_uart_driver *uart, uint32_t flags) {
|
||||
/* DMA errors handling.*/
|
||||
if ((flags & (STM32_DMA_ISR_TEIF | STM32_DMA_ISR_DMEIF)) != 0) {
|
||||
}
|
||||
|
||||
static void uart_lld_serve_tx_end_irq(hal_uart_driver *uart, uint32_t flags)
|
||||
{
|
||||
dmaStreamDisable(uart->dmatx);
|
||||
|
||||
/* A callback is generated, if enabled, after a completed transfer.*/
|
||||
|
@ -288,6 +288,13 @@ void AP_IOMCU_FW::init()
|
|||
// old NuttX based firmwares
|
||||
config.protocol_version = IOMCU_PROTOCOL_VERSION;
|
||||
config.protocol_version2 = IOMCU_PROTOCOL_VERSION2;
|
||||
#if defined(STM32F103xB) || defined(STM32F103x8)
|
||||
// Errata 2.2.2 - Debug registers cannot be read by user software
|
||||
config.mcuid = 0x20036410; // STM32F10x (Medium Density) rev Y
|
||||
#else
|
||||
config.mcuid = (*(uint32_t *)DBGMCU_BASE);
|
||||
#endif
|
||||
|
||||
|
||||
thread_ctx = chThdGetSelfX();
|
||||
|
||||
|
@ -430,7 +437,6 @@ void AP_IOMCU_FW::update()
|
|||
// send a response if required
|
||||
if (mask & IOEVENT_TX_BEGIN) {
|
||||
chSysLock();
|
||||
reg_status.deferred_locks++;
|
||||
setup_tx_dma(&UARTD2);
|
||||
chSysUnlock();
|
||||
}
|
||||
|
@ -1081,6 +1087,10 @@ void AP_IOMCU_FW::rcout_config_update(void)
|
|||
hal.rcout->set_output_mode(mode_out.mask, AP_HAL::RCOutput::MODE_PWM_BRUSHED);
|
||||
hal.rcout->set_freq(mode_out.mask, reg_setup.pwm_altrate);
|
||||
}
|
||||
|
||||
uint32_t output_mask = 0;
|
||||
reg_status.rcout_mode = hal.rcout->get_output_mode(output_mask);
|
||||
reg_status.rcout_mask = uint8_t(0xFF & output_mask);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
|
||||
#include <stdint.h>
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
/*
|
||||
common protocol definitions between AP_IOMCU and iofirmware
|
||||
*/
|
||||
|
@ -106,6 +107,7 @@ enum iopage {
|
|||
struct page_config {
|
||||
uint16_t protocol_version;
|
||||
uint16_t protocol_version2;
|
||||
uint32_t mcuid;
|
||||
};
|
||||
|
||||
struct page_reg_status {
|
||||
|
@ -119,8 +121,9 @@ struct page_reg_status {
|
|||
uint32_t total_pkts;
|
||||
uint32_t total_ticks;
|
||||
uint32_t total_events;
|
||||
uint32_t deferred_locks;
|
||||
uint8_t flag_safety_off;
|
||||
uint8_t rcout_mask;
|
||||
uint8_t rcout_mode;
|
||||
uint8_t err_crc;
|
||||
uint8_t err_bad_opcode;
|
||||
uint8_t err_read;
|
||||
|
|
Loading…
Reference in New Issue