From 48f2d9269cc3789f53cbffc97fb6e82cbc69b067 Mon Sep 17 00:00:00 2001 From: Davide Mor <davide.mor@skywarder.eu> Date: Tue, 1 Aug 2023 22:47:53 +0200 Subject: [PATCH] [sx1278] Updated mavlink test --- .../radio/sx1278/fsk/test-sx1278-mavlink.cpp | 112 +++++++++++++----- 1 file changed, 85 insertions(+), 27 deletions(-) diff --git a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp index c36bcf791..af10c8f79 100644 --- a/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp +++ b/src/tests/radio/sx1278/fsk/test-sx1278-mavlink.cpp @@ -33,7 +33,7 @@ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wcast-align" #pragma GCC diagnostic ignored "-Waddress-of-packed-member" -#include <mavlink_lib/pyxis/mavlink.h> +#include <mavlink_lib/gemini/mavlink.h> #pragma GCC diagnostic pop #include <radio/MavlinkDriver/MavlinkDriver.h> @@ -70,6 +70,59 @@ using mosi = interfaces::spi4::mosi; #define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl +#elif defined _BOARD_STM32F767ZI_GEMINI_GS +#include "interfaces-impl/hwmapping.h" + +#define SX1278_IS_SKYWARD433 +// #define SX1278_IS_EBYTE + +// Comment to use SX1278_2 +#define SX1278_1 + +#ifdef SX1278_1 +using cs = miosix::radio1::cs; +using dio0 = miosix::radio1::dio0; +using dio1 = miosix::radio1::dio1; +using dio3 = miosix::radio1::dio3; + +using sck = miosix::radio1::spi::sck; +using miso = miosix::radio1::spi::miso; +using mosi = miosix::radio1::spi::mosi; + +using txen = miosix::radio1::txen; +using rxen = miosix::radio1::rxen; + +#define SX1278_NRST +using rst = miosix::radio1::nrst; + +#define SX1278_SPI MIOSIX_RADIO1_SPI + +#define SX1278_IRQ_DIO0 MIOSIX_RADIO1_DIO0_IRQ +#define SX1278_IRQ_DIO1 MIOSIX_RADIO1_DIO1_IRQ +#define SX1278_IRQ_DIO3 MIOSIX_RADIO1_DIO3_IRQ +#else +using cs = miosix::radio2::cs; +using dio0 = miosix::radio2::dio0; +using dio1 = miosix::radio2::dio1; +using dio3 = miosix::radio2::dio3; + +using sck = miosix::radio2::spi::sck; +using miso = miosix::radio2::spi::miso; +using mosi = miosix::radio2::spi::mosi; + +using txen = miosix::radio2::txen; +using rxen = miosix::radio2::rxen; + +#define SX1278_NRST +using rst = miosix::radio2::nrst; + +#define SX1278_SPI MIOSIX_RADIO2_SPI + +#define SX1278_IRQ_DIO0 MIOSIX_RADIO2_DIO0_IRQ +#define SX1278_IRQ_DIO1 MIOSIX_RADIO2_DIO1_IRQ +#define SX1278_IRQ_DIO3 MIOSIX_RADIO2_DIO3_IRQ +#endif + #else #error "Target not supported" #endif @@ -100,43 +153,41 @@ Mav* channel; void onReceive(Mav* channel, const mavlink_message_t& msg) { - // Prepare ack messages - mavlink_message_t ackMsg; - mavlink_msg_ack_tm_pack(1, 1, &ackMsg, msg.msgid, msg.seq); + if (msg.msgid != MAVLINK_MSG_ID_ACK_TM) + { + // Prepare ack messages + mavlink_message_t ackMsg; + mavlink_msg_ack_tm_pack(1, 1, &ackMsg, msg.msgid, msg.seq); - // Send the ack back to the sender - channel->enqueueMsg(ackMsg); + // Send the ack back to the sender + channel->enqueueMsg(ackMsg); + + printf("[sx1278] Sending ack\n"); + } } void flightTmLoop() { + int i = 0; + while (1) { long long start = miosix::getTick(); mavlink_message_t msg; mavlink_rocket_flight_tm_t tm = {0}; + tm.acc_x = i; + tm.acc_y = i * 2; + tm.acc_z = i * 3; + mavlink_msg_rocket_flight_tm_encode(171, 96, &msg, &tm); channel->enqueueMsg(msg); Thread::sleepUntil(start + FLIGHT_TM_PERIOD); - } -} - -void statsTmLoop() -{ - while (1) - { - long long start = miosix::getTick(); + i += 1; - mavlink_message_t msg; - mavlink_rocket_stats_tm_t tm = {0}; - mavlink_msg_rocket_stats_tm_encode(171, 96, &msg, &tm); - - channel->enqueueMsg(msg); - - Thread::sleepUntil(start + STATS_TM_PERIOD); + printf("[sx1278] Message sent\n"); } } @@ -144,7 +195,18 @@ int main() { initBoard(); - SX1278Fsk::Config config; + SX1278Fsk::Config config = { + .freq_rf = 434000000, + .freq_dev = 50000, + .bitrate = 48000, + .rx_bw = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000, + .afc_bw = Boardcore::SX1278Fsk::Config::RxBw::HZ_125000, + .ocp = 120, + .power = 13, + .shaping = Boardcore::SX1278Fsk::Config::Shaping::GAUSSIAN_BT_1_0, + .dc_free = Boardcore::SX1278Fsk::Config::DcFree::WHITENING, + .enable_crc = true}; + SX1278Fsk::Error err; SPIBus bus(SX1278_SPI); @@ -169,11 +231,7 @@ int main() channel = new Mav(sx1278, &onReceive, 0, MAV_OUT_BUFFER_MAX_AGE); channel->start(); - std::thread flight_tm_loop([]() { flightTmLoop(); }); - std::thread stats_tm_loop([]() { statsTmLoop(); }); - - while (1) - Thread::wait(); + flightTmLoop(); return 0; } -- GitLab