From 32ddbca4282b9219e387da5521adb4c1c6de42a4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Jan 2018 14:43:11 +1100 Subject: [PATCH] AP_Radio: do cypress sends as single transfer this prevents timing errors to cypress chip on packet send --- libraries/AP_Radio/AP_Radio_cypress.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Radio/AP_Radio_cypress.cpp b/libraries/AP_Radio/AP_Radio_cypress.cpp index b11ce9b660..c59f541ab2 100644 --- a/libraries/AP_Radio/AP_Radio_cypress.cpp +++ b/libraries/AP_Radio/AP_Radio_cypress.cpp @@ -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(®, 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); } /*