mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_IOMCU: pass supported RC protocols to IOMCU
This commit is contained in:
parent
959e3da406
commit
017f005737
@ -19,6 +19,7 @@
|
|||||||
#include <AP_RCProtocol/AP_RCProtocol.h>
|
#include <AP_RCProtocol/AP_RCProtocol.h>
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
#include <AP_RCProtocol/AP_RCProtocol.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
@ -247,6 +248,8 @@ void AP_IOMCU::thread_main(void)
|
|||||||
pwm_out.failsafe_pwm_sent = set;
|
pwm_out.failsafe_pwm_sent = set;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
send_rc_protocols();
|
||||||
}
|
}
|
||||||
done_shutdown = true;
|
done_shutdown = true;
|
||||||
}
|
}
|
||||||
@ -769,6 +772,18 @@ void AP_IOMCU::update_safety_options(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// update enabled RC protocols mask
|
||||||
|
void AP_IOMCU::send_rc_protocols()
|
||||||
|
{
|
||||||
|
const uint32_t v = rc().enabled_protocols();
|
||||||
|
if (last_rc_protocols == v) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (write_registers(PAGE_SETUP, PAGE_REG_SETUP_RC_PROTOCOLS, 2, (uint16_t *)&v)) {
|
||||||
|
last_rc_protocols = v;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
check ROMFS firmware against CRC on IOMCU, and if incorrect then upload new firmware
|
check ROMFS firmware against CRC on IOMCU, and if incorrect then upload new firmware
|
||||||
*/
|
*/
|
||||||
@ -1023,6 +1038,7 @@ void AP_IOMCU::check_iomcu_reset(void)
|
|||||||
}
|
}
|
||||||
trigger_event(IOEVENT_SET_RATES);
|
trigger_event(IOEVENT_SET_RATES);
|
||||||
trigger_event(IOEVENT_SET_DEFAULT_RATE);
|
trigger_event(IOEVENT_SET_DEFAULT_RATE);
|
||||||
|
last_rc_protocols = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -161,6 +161,7 @@ private:
|
|||||||
void discard_input(void);
|
void discard_input(void);
|
||||||
void event_failed(uint8_t event);
|
void event_failed(uint8_t event);
|
||||||
void update_safety_options(void);
|
void update_safety_options(void);
|
||||||
|
void send_rc_protocols(void);
|
||||||
|
|
||||||
// CONFIG page
|
// CONFIG page
|
||||||
struct page_config config;
|
struct page_config config;
|
||||||
@ -223,6 +224,7 @@ private:
|
|||||||
uint32_t last_iocmu_timestamp_ms;
|
uint32_t last_iocmu_timestamp_ms;
|
||||||
uint32_t read_status_errors;
|
uint32_t read_status_errors;
|
||||||
uint32_t read_status_ok;
|
uint32_t read_status_ok;
|
||||||
|
uint32_t last_rc_protocols;
|
||||||
|
|
||||||
// firmware upload
|
// firmware upload
|
||||||
const char *fw_name = "io_firmware.bin";
|
const char *fw_name = "io_firmware.bin";
|
||||||
|
@ -558,6 +558,15 @@ bool AP_IOMCU_FW::handle_code_write()
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case PAGE_REG_SETUP_RC_PROTOCOLS: {
|
||||||
|
if (rx_io_packet.count == 2) {
|
||||||
|
uint32_t v;
|
||||||
|
memcpy(&v, &rx_io_packet.regs[0], 4);
|
||||||
|
AP::RC().set_rc_protocols(v);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -83,6 +83,7 @@ enum iopage {
|
|||||||
#define PAGE_REG_SETUP_IGNORE_SAFETY 20 /* bitmask of surfaces to ignore the safety status */
|
#define PAGE_REG_SETUP_IGNORE_SAFETY 20 /* bitmask of surfaces to ignore the safety status */
|
||||||
#define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21
|
#define PAGE_REG_SETUP_HEATER_DUTY_CYCLE 21
|
||||||
#define PAGE_REG_SETUP_DSM_BIND 22
|
#define PAGE_REG_SETUP_DSM_BIND 22
|
||||||
|
#define PAGE_REG_SETUP_RC_PROTOCOLS 23 // uses 2 slots, 23 and 24
|
||||||
|
|
||||||
// config page registers
|
// config page registers
|
||||||
#define PAGE_CONFIG_PROTOCOL_VERSION 0
|
#define PAGE_CONFIG_PROTOCOL_VERSION 0
|
||||||
|
Loading…
Reference in New Issue
Block a user