mirror of https://github.com/ArduPilot/ardupilot
AP_Radio: do cypress sends as single transfer
this prevents timing errors to cypress chip on packet send
This commit is contained in:
parent
65f4c0ba50
commit
32ddbca428
|
@ -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)
|
void AP_Radio_cypress::write_multiple(uint8_t reg, uint8_t n, const uint8_t *data)
|
||||||
{
|
{
|
||||||
dev->set_chip_select(true);
|
uint8_t pkt[n+1];
|
||||||
reg |= FLAG_WRITE;
|
pkt[0] = reg | FLAG_WRITE;
|
||||||
dev->transfer(®, 1, nullptr, 0);
|
memcpy(&pkt[1], data, n);
|
||||||
dev->transfer(data, n, nullptr, 0);
|
dev->transfer(pkt, n+1, nullptr, 0);
|
||||||
dev->set_chip_select(false);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue