AP_Radio: do cypress sends as single transfer

this prevents timing errors to cypress chip on packet send
This commit is contained in:
Andrew Tridgell 2018-01-20 14:43:11 +11:00
parent 65f4c0ba50
commit 32ddbca428
1 changed files with 4 additions and 5 deletions

View File

@ -682,11 +682,10 @@ uint8_t AP_Radio_cypress::read_register(uint8_t reg)
*/
void AP_Radio_cypress::write_multiple(uint8_t reg, uint8_t n, const uint8_t *data)
{
dev->set_chip_select(true);
reg |= FLAG_WRITE;
dev->transfer(&reg, 1, nullptr, 0);
dev->transfer(data, n, nullptr, 0);
dev->set_chip_select(false);
uint8_t pkt[n+1];
pkt[0] = reg | FLAG_WRITE;
memcpy(&pkt[1], data, n);
dev->transfer(pkt, n+1, nullptr, 0);
}
/*