mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_IOMCU: use more bandwidth efficient IO read
This commit is contained in:
parent
d5c29fc57e
commit
ec73a7072b
@ -361,13 +361,19 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1
|
||||
pkt.offset = offset;
|
||||
pkt.crc = 0;
|
||||
|
||||
uint8_t pkt_size = pkt.get_size();
|
||||
if (config.protocol_version == IOMCU_PROTOCOL_VERSION) {
|
||||
// save bandwidth on reads
|
||||
pkt_size = 4;
|
||||
}
|
||||
|
||||
/*
|
||||
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
|
||||
*/
|
||||
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt.get_size());
|
||||
if (uart.write((uint8_t *)&pkt, pkt.get_size()) != pkt.get_size()) {
|
||||
pkt.crc = crc_crc8((const uint8_t *)&pkt, pkt_size);
|
||||
if (uart.write((uint8_t *)&pkt, pkt_size) != pkt_size) {
|
||||
protocol_fail_count++;
|
||||
return false;
|
||||
}
|
||||
|
@ -156,6 +156,8 @@ void loop(void)
|
||||
|
||||
void AP_IOMCU_FW::init()
|
||||
{
|
||||
config.protocol_version = IOMCU_PROTOCOL_VERSION;
|
||||
|
||||
thread_ctx = chThdGetSelfX();
|
||||
|
||||
if (palReadLine(HAL_GPIO_PIN_IO_HW_DETECT1) == 1 && palReadLine(HAL_GPIO_PIN_IO_HW_DETECT2) == 0) {
|
||||
@ -261,8 +263,18 @@ void AP_IOMCU_FW::rcin_update()
|
||||
void AP_IOMCU_FW::process_io_packet()
|
||||
{
|
||||
uint8_t rx_crc = rx_io_packet.crc;
|
||||
uint8_t calc_crc;
|
||||
rx_io_packet.crc = 0;
|
||||
uint8_t calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, rx_io_packet.get_size());
|
||||
uint8_t pkt_size = rx_io_packet.get_size();
|
||||
if (rx_io_packet.code == CODE_READ) {
|
||||
// allow for more bandwidth efficient read packets
|
||||
calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, 4);
|
||||
if (calc_crc != rx_crc) {
|
||||
calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, pkt_size);
|
||||
}
|
||||
} else {
|
||||
calc_crc = crc_crc8((const uint8_t *)&rx_io_packet, pkt_size);
|
||||
}
|
||||
if (rx_crc != calc_crc) {
|
||||
memset(&tx_io_packet, 0xFF, sizeof(tx_io_packet));
|
||||
tx_io_packet.count = 0;
|
||||
|
@ -90,7 +90,7 @@ enum iopage {
|
||||
#define FORCE_SAFETY_MAGIC 22027
|
||||
|
||||
struct PACKED page_config {
|
||||
uint16_t protocol_version = IOMCU_PROTOCOL_VERSION;
|
||||
uint16_t protocol_version;
|
||||
};
|
||||
|
||||
struct PACKED page_reg_status {
|
||||
|
Loading…
Reference in New Issue
Block a user