ardupilot/libraries/AP_IOMCU/AP_IOMCU.cpp

131 lines
3.9 KiB
C++
Raw Normal View History

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"
extern const AP_HAL::HAL &hal;
#define PKT_MAX_REGS 32
struct PACKED IOPacket {
uint8_t count_code;
uint8_t crc;
uint8_t page;
uint8_t offset;
uint16_t regs[PKT_MAX_REGS];
};
#define PKT_CODE_READ 0x00 /* FMU->IO read transaction */
#define PKT_CODE_WRITE 0x40 /* FMU->IO write transaction */
#define PKT_CODE_SPIUART 0xC0 /* FMU<->IO spi-uart transaction */
#define PKT_CODE_SUCCESS 0x00 /* IO->FMU success reply */
#define PKT_CODE_CORRUPT 0x40 /* IO->FMU bad packet reply */
#define PKT_CODE_ERROR 0x80 /* IO->FMU register op error reply */
#define PKT_CODE_MASK 0xc0
#define PKT_COUNT_MASK 0x3f
#define PKT_COUNT(_p) ((_p).count_code & PKT_COUNT_MASK)
#define PKT_CODE(_p) ((_p).count_code & PKT_CODE_MASK)
#define PKT_SIZE(_p) ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p))))
#define IO_PROTOCOL_VERSION 4
#define IO_PAGE_CONFIG 0
static const uint8_t crc8_tab[256] =
{
0x00, 0x07, 0x0E, 0x09, 0x1C, 0x1B, 0x12, 0x15,
0x38, 0x3F, 0x36, 0x31, 0x24, 0x23, 0x2A, 0x2D,
0x70, 0x77, 0x7E, 0x79, 0x6C, 0x6B, 0x62, 0x65,
0x48, 0x4F, 0x46, 0x41, 0x54, 0x53, 0x5A, 0x5D,
0xE0, 0xE7, 0xEE, 0xE9, 0xFC, 0xFB, 0xF2, 0xF5,
0xD8, 0xDF, 0xD6, 0xD1, 0xC4, 0xC3, 0xCA, 0xCD,
0x90, 0x97, 0x9E, 0x99, 0x8C, 0x8B, 0x82, 0x85,
0xA8, 0xAF, 0xA6, 0xA1, 0xB4, 0xB3, 0xBA, 0xBD,
0xC7, 0xC0, 0xC9, 0xCE, 0xDB, 0xDC, 0xD5, 0xD2,
0xFF, 0xF8, 0xF1, 0xF6, 0xE3, 0xE4, 0xED, 0xEA,
0xB7, 0xB0, 0xB9, 0xBE, 0xAB, 0xAC, 0xA5, 0xA2,
0x8F, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9D, 0x9A,
0x27, 0x20, 0x29, 0x2E, 0x3B, 0x3C, 0x35, 0x32,
0x1F, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0D, 0x0A,
0x57, 0x50, 0x59, 0x5E, 0x4B, 0x4C, 0x45, 0x42,
0x6F, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7D, 0x7A,
0x89, 0x8E, 0x87, 0x80, 0x95, 0x92, 0x9B, 0x9C,
0xB1, 0xB6, 0xBF, 0xB8, 0xAD, 0xAA, 0xA3, 0xA4,
0xF9, 0xFE, 0xF7, 0xF0, 0xE5, 0xE2, 0xEB, 0xEC,
0xC1, 0xC6, 0xCF, 0xC8, 0xDD, 0xDA, 0xD3, 0xD4,
0x69, 0x6E, 0x67, 0x60, 0x75, 0x72, 0x7B, 0x7C,
0x51, 0x56, 0x5F, 0x58, 0x4D, 0x4A, 0x43, 0x44,
0x19, 0x1E, 0x17, 0x10, 0x05, 0x02, 0x0B, 0x0C,
0x21, 0x26, 0x2F, 0x28, 0x3D, 0x3A, 0x33, 0x34,
0x4E, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5C, 0x5B,
0x76, 0x71, 0x78, 0x7F, 0x6A, 0x6D, 0x64, 0x63,
0x3E, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2C, 0x2B,
0x06, 0x01, 0x08, 0x0F, 0x1A, 0x1D, 0x14, 0x13,
0xAE, 0xA9, 0xA0, 0xA7, 0xB2, 0xB5, 0xBC, 0xBB,
0x96, 0x91, 0x98, 0x9F, 0x8A, 0x8D, 0x84, 0x83,
0xDE, 0xD9, 0xD0, 0xD7, 0xC2, 0xC5, 0xCC, 0xCB,
0xE6, 0xE1, 0xE8, 0xEF, 0xFA, 0xFD, 0xF4, 0xF3
};
static uint8_t crc_packet(struct IOPacket *pkt)
{
uint8_t *end = (uint8_t *)(&pkt->regs[PKT_COUNT(*pkt)]);
uint8_t *p = (uint8_t *)pkt;
uint8_t c = 0;
while (p < end) {
c = crc8_tab[c ^ *(p++)];
}
return c;
}
AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) :
uart(_uart)
{}
void AP_IOMCU::write_channel(uint8_t chan, uint16_t pwm)
{
static uint32_t last_ms;
if (last_ms == 0) {
uart.begin(1500*1000, 256, 256);
}
uint32_t now = AP_HAL::millis();
if (now - last_ms < 1000) {
return;
}
last_ms = now;
IOPacket pkt;
memset(&pkt, 0, sizeof(pkt));
pkt.count_code = 4 | PKT_CODE_READ;
pkt.page = IO_PAGE_CONFIG;
pkt.offset = IO_PROTOCOL_VERSION;
pkt.crc = crc_packet(&pkt);
hal.console->printf("sending IO pkt\n");
uart.write((uint8_t *)&pkt, sizeof(pkt));
uint8_t n = uart.available();
if (n > 0) {
uint8_t *b = (uint8_t *)&pkt;
for (uint8_t i=0; i<n; i++) {
b[i] = uart.read();
}
hal.console->printf("IO PKT len=%u\n", n);
for (uint8_t i=0; i<n; i++) {
hal.console->printf("%02x ", b[i]);
}
hal.console->printf("\n");
}
}