mirror of https://github.com/ArduPilot/ardupilot
IO_Firmware: update IOMCU firmware with profiled LED support over safety pins
This commit is contained in:
parent
93d99ece0a
commit
4cbc4dfe34
|
@ -43,6 +43,7 @@ enum ioevents {
|
|||
IOEVENT_SET_DSHOT_PERIOD,
|
||||
IOEVENT_SET_CHANNEL_MASK,
|
||||
IOEVENT_DSHOT,
|
||||
IOEVENT_PROFILED,
|
||||
};
|
||||
|
||||
// max number of consecutve protocol failures we accept before raising
|
||||
|
@ -89,7 +90,9 @@ void AP_IOMCU::init(void)
|
|||
crc_is_ok = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
use_safety_as_led = boardconfig->use_safety_as_led();
|
||||
#endif
|
||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU",
|
||||
1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
|
||||
AP_HAL::panic("Unable to allocate IOMCU thread");
|
||||
|
@ -300,6 +303,16 @@ void AP_IOMCU::thread_main(void)
|
|||
}
|
||||
mask &= ~EVENT_MASK(IOEVENT_DSHOT);
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
if (mask & EVENT_MASK(IOEVENT_PROFILED)) {
|
||||
if (!write_registers(PAGE_PROFILED, 0, sizeof(profiled)/sizeof(uint16_t), (const uint16_t*)&profiled)) {
|
||||
event_failed(mask);
|
||||
continue;
|
||||
}
|
||||
}
|
||||
mask &= ~EVENT_MASK(IOEVENT_PROFILED);
|
||||
#endif
|
||||
|
||||
// check for regular timed events
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_rc_read_ms > 20) {
|
||||
|
@ -1439,6 +1452,23 @@ void AP_IOMCU::toggle_GPIO(uint8_t pin)
|
|||
trigger_event(IOEVENT_GPIO);
|
||||
}
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
// set profiled R G B values
|
||||
void AP_IOMCU::set_profiled(uint8_t r, uint8_t g, uint8_t b)
|
||||
{
|
||||
if (!use_safety_as_led) {
|
||||
return;
|
||||
}
|
||||
if (r == profiled.red && g == profiled.green && b == profiled.blue) {
|
||||
return;
|
||||
}
|
||||
profiled.magic = PROFILED_ENABLE_MAGIC;
|
||||
profiled.red = r;
|
||||
profiled.green = g;
|
||||
profiled.blue = b;
|
||||
trigger_event(IOEVENT_PROFILED);
|
||||
}
|
||||
#endif
|
||||
|
||||
namespace AP {
|
||||
AP_IOMCU *iomcu(void) {
|
||||
|
|
|
@ -176,6 +176,11 @@ public:
|
|||
// toggle a output pin
|
||||
void toggle_GPIO(uint8_t pin);
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
// set profiled values
|
||||
void set_profiled(uint8_t r, uint8_t g, uint8_t b);
|
||||
#endif
|
||||
|
||||
// channel group masks
|
||||
const uint8_t ch_masks[3] = { 0x03,0x0C,0xF0 };
|
||||
|
||||
|
@ -297,6 +302,11 @@ private:
|
|||
// output mode values
|
||||
struct page_mode_out mode_out;
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
// profiled control
|
||||
struct page_profiled profiled {0, 255, 255, 255}; // by default, white
|
||||
#endif
|
||||
|
||||
// IMU heater duty cycle
|
||||
uint8_t heater_duty_cycle;
|
||||
|
||||
|
@ -310,6 +320,9 @@ private:
|
|||
bool detected_io_reset;
|
||||
bool initialised;
|
||||
bool is_chibios_backend;
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
bool use_safety_as_led;
|
||||
#endif
|
||||
|
||||
uint32_t protocol_fail_count;
|
||||
uint32_t protocol_count;
|
||||
|
|
|
@ -489,6 +489,10 @@ void AP_IOMCU_FW::update()
|
|||
last_status_ms = now;
|
||||
page_status_update();
|
||||
}
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
profiled_update();
|
||||
#endif
|
||||
#ifdef HAL_WITH_BIDIR_DSHOT
|
||||
// EDT updates are semt at ~1Hz per ESC, but we want to make sure
|
||||
// that we don't delay updates unduly so sample at 5Hz
|
||||
|
@ -1029,6 +1033,20 @@ bool AP_IOMCU_FW::handle_code_write()
|
|||
break;
|
||||
}
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
case PAGE_PROFILED:
|
||||
if (rx_io_packet.count != 2 || (rx_io_packet.regs[0] & 0xFF) != PROFILED_ENABLE_MAGIC) {
|
||||
return false;
|
||||
}
|
||||
profiled_brg[0] = rx_io_packet.regs[0] >> 8;
|
||||
profiled_brg[1] = rx_io_packet.regs[1] & 0xFF;
|
||||
profiled_brg[2] = rx_io_packet.regs[1] >> 8;
|
||||
// push new led data
|
||||
profiled_num_led_pushed = 0;
|
||||
profiled_control_enabled = true;
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
@ -1063,6 +1081,48 @@ void AP_IOMCU_FW::calculate_fw_crc(void)
|
|||
reg_setup.crc[1] = sum >> 16;
|
||||
}
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
// bitbang profiled bitstream, 8-10 chunks at a time
|
||||
// Max time taken per call is ~7us
|
||||
void AP_IOMCU_FW::profiled_update(void)
|
||||
{
|
||||
if (profiled_num_led_pushed > PROFILED_LED_LEN) {
|
||||
profiled_byte_index = 0;
|
||||
profiled_leading_zeros = PROFILED_LEADING_ZEROS;
|
||||
return;
|
||||
}
|
||||
|
||||
// push 10 zero leading bits at a time
|
||||
if (profiled_leading_zeros != 0) {
|
||||
for (uint8_t i = 0; i < 10; i++) {
|
||||
palClearLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
palSetLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
profiled_leading_zeros--;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
if ((profiled_byte_index == 0) ||
|
||||
(profiled_byte_index == PROFILED_OUTPUT_BYTE_LEN)) {
|
||||
// start bit
|
||||
palClearLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
palSetLine(HAL_GPIO_PIN_SAFETY_LED);
|
||||
palSetLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
profiled_byte_index = 0;
|
||||
profiled_num_led_pushed++;
|
||||
}
|
||||
|
||||
uint8_t byte_val = profiled_brg[profiled_byte_index];
|
||||
for (uint8_t i = 0; i < 8; i++) {
|
||||
palClearLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
palWriteLine(HAL_GPIO_PIN_SAFETY_LED, byte_val & 1);
|
||||
byte_val >>= 1;
|
||||
palSetLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
}
|
||||
|
||||
profiled_byte_index++;
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
update safety state
|
||||
|
@ -1076,6 +1136,15 @@ void AP_IOMCU_FW::safety_update(void)
|
|||
}
|
||||
safety_update_ms = now;
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
if (profiled_control_enabled) {
|
||||
// set line mode to output for safety input pin
|
||||
palSetLineMode(HAL_GPIO_PIN_SAFETY_INPUT, PAL_MODE_OUTPUT_PUSHPULL);
|
||||
palSetLineMode(HAL_GPIO_PIN_SAFETY_LED, PAL_MODE_OUTPUT_PUSHPULL);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
bool safety_pressed = palReadLine(HAL_GPIO_PIN_SAFETY_INPUT);
|
||||
if (safety_pressed) {
|
||||
if (reg_status.flag_safety_off && (reg_setup.arming & P_SETUP_ARMING_SAFETY_DISABLE_ON)) {
|
||||
|
|
|
@ -17,6 +17,10 @@
|
|||
#define PWM_IGNORE_THIS_CHANNEL UINT16_MAX
|
||||
#define SERVO_COUNT 8
|
||||
|
||||
#define PROFILED_LED_LEN 2
|
||||
#define PROFILED_OUTPUT_BYTE_LEN 3
|
||||
#define PROFILED_LEADING_ZEROS 50
|
||||
|
||||
class AP_IOMCU_FW {
|
||||
public:
|
||||
void process_io_packet();
|
||||
|
@ -36,6 +40,9 @@ public:
|
|||
bool handle_code_write();
|
||||
bool handle_code_read();
|
||||
void schedule_reboot(uint32_t time_ms);
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
void profiled_update();
|
||||
#endif
|
||||
void safety_update();
|
||||
void rcout_config_update();
|
||||
void rcin_serial_init();
|
||||
|
@ -81,6 +88,14 @@ public:
|
|||
|
||||
uint16_t last_channel_mask;
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
uint8_t profiled_byte_index;
|
||||
uint8_t profiled_leading_zeros;
|
||||
uint8_t profiled_num_led_pushed;
|
||||
uint8_t profiled_brg[3];
|
||||
bool profiled_control_enabled;
|
||||
#endif
|
||||
|
||||
// CONFIG values
|
||||
struct page_config config;
|
||||
|
||||
|
@ -117,6 +132,11 @@ public:
|
|||
// output mode values
|
||||
struct page_mode_out mode_out;
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
// profiled control values
|
||||
struct page_profiled profiled;
|
||||
#endif
|
||||
|
||||
uint16_t last_output_mode_mask;
|
||||
uint16_t last_output_bdmask;
|
||||
uint16_t last_output_esc_type;
|
||||
|
|
|
@ -7,6 +7,10 @@
|
|||
common protocol definitions between AP_IOMCU and iofirmware
|
||||
*/
|
||||
|
||||
#ifndef AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
#define AP_IOMCU_PROFILED_SUPPORT_ENABLED 0
|
||||
#endif
|
||||
|
||||
// 22 is enough for the rc_input page in one transfer
|
||||
#define PKT_MAX_REGS 22
|
||||
// The number of channels that can be propagated - due to SBUS_OUT is higher than the physical channels
|
||||
|
@ -68,6 +72,9 @@ enum iopage {
|
|||
PAGE_RAW_DSHOT_TELEM_5_8 = 205,
|
||||
PAGE_RAW_DSHOT_TELEM_9_12 = 206,
|
||||
PAGE_RAW_DSHOT_TELEM_13_16 = 207,
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
PAGE_PROFILED = 208,
|
||||
#endif
|
||||
};
|
||||
|
||||
// setup page registers
|
||||
|
@ -114,6 +121,8 @@ enum iopage {
|
|||
#define PAGE_REG_SETUP_FORCE_SAFETY_ON 14
|
||||
#define FORCE_SAFETY_MAGIC 22027
|
||||
|
||||
#define PROFILED_ENABLE_MAGIC 123
|
||||
|
||||
struct page_config {
|
||||
uint16_t protocol_version;
|
||||
uint16_t protocol_version2;
|
||||
|
@ -230,3 +239,12 @@ struct page_dshot_telem {
|
|||
uint8_t edt2_stress[4];
|
||||
#endif
|
||||
};
|
||||
|
||||
#if AP_IOMCU_PROFILED_SUPPORT_ENABLED
|
||||
struct __attribute__((packed, aligned(2))) page_profiled {
|
||||
uint8_t magic;
|
||||
uint8_t blue;
|
||||
uint8_t red;
|
||||
uint8_t green;
|
||||
};
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue