diff --git a/src/entrypoints/sx1278-mav-raw.cpp b/src/entrypoints/sx1278-mav-raw.cpp index 01f8532ae4cab97968b7fdee52528294694327e9..3b30589feaf28afe4aa755eb207368585af297b2 100644 --- a/src/entrypoints/sx1278-mav-raw.cpp +++ b/src/entrypoints/sx1278-mav-raw.cpp @@ -22,9 +22,8 @@ #include <drivers/interrupt/external_interrupts.h> #include <filesystem/console/console_device.h> - -// SX1278 includes #include <mavlink_lib/gemini/mavlink.h> +// SX1278 includes #include <radio/SX1278/SX1278Frontends.h> #include <radio/SX1278/SX1278Fsk.h> #include <radio/SX1278/SX1278Lora.h> @@ -34,18 +33,9 @@ using namespace miosix; -// Uncomment the following line to enable Lora mode -// Or use SBS to define it for you -// #define SX1278_IS_LORA - #if defined _BOARD_STM32F429ZI_SKYWARD_GS_V2 #include "interfaces-impl/hwmapping.h" -// Uncomment the following line to enable Ebyte module -// #define SX1278_IS_EBYTE -// Uncomment the following line to ebable Skyward433 module -// #define SX1278_IS_SKYWARD433 - using cs = peripherals::ra01::pc13::cs; using dio0 = peripherals::ra01::pc13::dio0; using dio1 = peripherals::ra01::pc13::dio1; @@ -55,110 +45,46 @@ using sck = interfaces::spi4::sck; using miso = interfaces::spi4::miso; using mosi = interfaces::spi4::mosi; -#ifdef SX1278_IS_EBYTE -using txen = Gpio<GPIOE_BASE, 4>; -using rxen = Gpio<GPIOD_BASE, 4>; -#endif - #define SX1278_SPI SPI4 #define SX1278_IRQ_DIO0 EXTI6_IRQHandlerImpl #define SX1278_IRQ_DIO1 EXTI4_IRQHandlerImpl #define SX1278_IRQ_DIO3 EXTI11_IRQHandlerImpl - -#elif defined _BOARD_STM32F429ZI_SKYWARD_RIG -#include "interfaces-impl/hwmapping.h" - -#define SX1278_IS_EBYTE - -using cs = radio::cs; -using dio0 = radio::dio0; -using dio1 = radio::dio1; -using dio3 = radio::dio3; - -using sck = radio::sck; -using miso = radio::miso; -using mosi = radio::mosi; - -using txen = radio::txEn; -using rxen = radio::rxEn; - -#define SX1278_SPI SPI4 - -#define SX1278_IRQ_DIO0 EXTI5_IRQHandlerImpl -#define SX1278_IRQ_DIO1 EXTI12_IRQHandlerImpl -#define SX1278_IRQ_DIO3 EXTI13_IRQHandlerImpl - -#elif defined _BOARD_STM32F767ZI_GEMINI_GS -#include "interfaces-impl/hwmapping.h" -#include "mavlink_lib/gemini/mavlink_msg_payload_flight_tm.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 -#ifdef SX1278_IS_LORA -static constexpr size_t SX1278_MTU = Boardcore::SX1278Lora::MTU; -Boardcore::SX1278Lora* sx1278 = nullptr; -#else +// === CONSTANTS === static constexpr size_t SX1278_MTU = Boardcore::SX1278Fsk::MTU; -Boardcore::SX1278Fsk* sx1278 = nullptr; -#endif +constexpr size_t PACKET_SIZE = MAVLINK_MSG_ID_PAYLOAD_FLIGHT_TM_LEN; + +/** @brief Number of packets to send */ +constexpr size_t MSG_NUM = 580; + +/** @brief End of transmission byte. Used to signal the end of a packet. */ +constexpr uint8_t EOT = 0x04; + +static const Boardcore::SX1278Fsk::Config RADIO_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 = false}; + +// === GLOBALS === +Boardcore::SX1278Fsk* sx1278 = nullptr; +Boardcore::SPIBus sx1278_bus(SX1278_SPI); volatile int dio0_cnt = 0; volatile int dio1_cnt = 0; volatile int dio3_cnt = 0; +// === INTERRUPTS === #ifdef SX1278_IRQ_DIO0 void __attribute__((used)) SX1278_IRQ_DIO0() { @@ -186,51 +112,34 @@ void __attribute__((used)) SX1278_IRQ_DIO3() } #endif -void initBoard() -{ -#ifdef SX1278_IS_EBYTE - rxen::mode(Mode::OUTPUT); - txen::mode(Mode::OUTPUT); - rxen::low(); - txen::low(); -#endif - -#ifdef SX1278_NRST - rst::mode(miosix::Mode::OUTPUT); - rst::high(); -#endif -} - -constexpr size_t PACKET_SIZE = 158; +// === DEFINITIONS === +void recvLoop(); +void sendLoop(); +mavlink_payload_flight_tm_t readPacketFromSerial(); +void initBoard(); -/** @brief Number of packets to send */ -constexpr size_t MSG_NUM = 580; - -/** @brief End of transmission byte. Used to signal the end of a packet. */ -constexpr uint8_t EOT = 0x04; - -/** - * @brief Read a packet from the serial port - * @warning This function will parse raw bytes coming from - * serial into the struct - * @return mavlink_payload_flight_tm_t - */ -mavlink_payload_flight_tm_t readPacketFromSerial() +// === MAIN === +int main() { - mavlink_payload_flight_tm_t tm; - uint8_t* ptr_to_tm = (uint8_t*)&tm; - uint8_t serial_buffer[PACKET_SIZE]; + initBoard(); - auto serial = DefaultConsole::instance().get(); - serial->writeBlock(&EOT, 1, 0); - serial->readBlock(serial_buffer, PACKET_SIZE, 0); +#if defined SX1278_IS_SENDER + sendLoop(); +#elif defined SX1278_IS_RECEIVER + recvLoop(); +#else + // this may cause problems with stdin and stdout + // interfering with each other - // this may be shrunk to the above statement (needs further testing) - memcpy(ptr_to_tm, serial_buffer, sizeof(mavlink_payload_flight_tm_t)); + // Actually spawn threads + std::thread send([]() { sendLoop(); }); + recvLoop(); +#endif - return tm; + return 0; } +// === IMPLEMENTATIONS === void recvLoop() { uint8_t msg[SX1278_MTU]; @@ -240,11 +149,71 @@ void recvLoop() if (len > 0) { mavlink_payload_flight_tm_t tm; - memcpy(&tm, msg, sizeof(mavlink_payload_flight_tm_t)); + memcpy(&tm, msg, PACKET_SIZE); auto serial = miosix::DefaultConsole::instance().get(); // serial->writeBlock(msg, len, 0); - std::cout << "[sx1278] Received packet - time: " << tm.timestamp - << std::endl; + // std::cout << "[sx1278] Received packet - time: " << tm.timestamp + // << std::endl; + + std::cout << "[sx1278] tm.timestamp: " << tm.timestamp << std::endl; + // std::cout << "[sx1278] tm.pressure_digi: " << tm.pressure_digi + // << std::endl; + // std::cout << "[sx1278] tm.pressure_static: " << + // tm.pressure_static + // << std::endl; + // std::cout << "[sx1278] tm.airspeed_pitot: " << tm.airspeed_pitot + // << std::endl; + // std::cout << "[sx1278] tm.altitude_agl: " << tm.altitude_agl + // << std::endl; + // std::cout << "[sx1278] tm.acc_x: " << tm.acc_x << std::endl; + // std::cout << "[sx1278] tm.acc_y: " << tm.acc_y << std::endl; + // std::cout << "[sx1278] tm.acc_z: " << tm.acc_z << std::endl; + // std::cout << "[sx1278] tm.gyro_x: " << tm.gyro_x << std::endl; + // std::cout << "[sx1278] tm.gyro_y: " << tm.gyro_y << std::endl; + // std::cout << "[sx1278] tm.gyro_z: " << tm.gyro_z << std::endl; + // std::cout << "[sx1278] tm.mag_x: " << tm.mag_x << std::endl; + // std::cout << "[sx1278] tm.mag_y: " << tm.mag_y << std::endl; + // std::cout << "[sx1278] tm.mag_z: " << tm.mag_z << std::endl; + // std::cout << "[sx1278] tm.gps_lat: " << tm.gps_lat << std::endl; + // std::cout << "[sx1278] tm.gps_lon: " << tm.gps_lon << std::endl; + // std::cout << "[sx1278] tm.gps_alt: " << tm.gps_alt << std::endl; + // std::cout << "[sx1278] tm.left_servo_angle: " << + // tm.left_servo_angle + // << std::endl; + // std::cout << "[sx1278] tm.right_servo_angle: " + // << tm.right_servo_angle << std::endl; + // std::cout << "[sx1278] tm.nas_n: " << tm.nas_n << std::endl; + // std::cout << "[sx1278] tm.nas_e: " << tm.nas_e << std::endl; + // std::cout << "[sx1278] tm.nas_d: " << tm.nas_d << std::endl; + // std::cout << "[sx1278] tm.nas_vn: " << tm.nas_vn << std::endl; + // std::cout << "[sx1278] tm.nas_ve: " << tm.nas_ve << std::endl; + // std::cout << "[sx1278] tm.nas_vd: " << tm.nas_vd << std::endl; + // std::cout << "[sx1278] tm.nas_qx: " << tm.nas_qx << std::endl; + // std::cout << "[sx1278] tm.nas_qy: " << tm.nas_qy << std::endl; + // std::cout << "[sx1278] tm.nas_qz: " << tm.nas_qz << std::endl; + // std::cout << "[sx1278] tm.nas_qw: " << tm.nas_qw << std::endl; + // std::cout << "[sx1278] tm.nas_bias_x: " << tm.nas_bias_x + // << std::endl; + // std::cout << "[sx1278] tm.nas_bias_y: " << tm.nas_bias_y + // << std::endl; + // std::cout << "[sx1278] tm.nas_bias_z: " << tm.nas_bias_z + // << std::endl; + // std::cout << "[sx1278] tm.wes_n: " << tm.wes_n << std::endl; + // std::cout << "[sx1278] tm.wes_e: " << tm.wes_e << std::endl; + // std::cout << "[sx1278] tm.vbat: " << tm.vbat << std::endl; + // std::cout << "[sx1278] tm.vsupply_5v: " << tm.vsupply_5v + // << std::endl; + // std::cout << "[sx1278] tm.temperature: " << tm.temperature + // << std::endl; + // std::cout << "[sx1278] tm.fmm_state: " << tm.fmm_state << + // std::endl; std::cout << "[sx1278] tm.nas_state: " << tm.nas_state + // << std::endl; std::cout << "[sx1278] tm.wes_state: " << + // tm.wes_state << std::endl; std::cout << "[sx1278] tm.gps_fix: " + // << tm.gps_fix << std::endl; std::cout << "[sx1278] + // tm.pin_nosecone: " << tm.pin_nosecone + // << std::endl; + // std::cout << "[sx1278] tm.logger_error: " << tm.logger_error + // << std::endl; } } } @@ -256,82 +225,54 @@ void sendLoop() { mavlink_payload_flight_tm_t tm = readPacketFromSerial(); std::cout << "[sx1278] Sending packet " << i << std::endl; - memcpy(msg, &tm, sizeof(mavlink_payload_flight_tm_t)); - sx1278->send(msg, sizeof(mavlink_payload_flight_tm_t)); + memcpy(msg, &tm, PACKET_SIZE); + sx1278->send(msg, PACKET_SIZE); } } -Boardcore::SPIBus sx1278_bus(SX1278_SPI); - -int main() +/** + * @brief Read a packet from the serial port + * @warning This function will parse raw bytes coming from + * serial into the struct + * @return mavlink_payload_flight_tm_t + */ +mavlink_payload_flight_tm_t readPacketFromSerial() { - initBoard(); + mavlink_payload_flight_tm_t tm; + uint8_t* ptr_to_tm = (uint8_t*)&tm; + uint8_t serial_buffer[PACKET_SIZE]; -#if defined SX1278_IS_EBYTE - printf("[sx1278] Confuring Ebyte frontend...\n"); - std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend( - new Boardcore::EbyteFrontend(txen::getPin(), rxen::getPin())); -#elif defined SX1278_IS_SKYWARD433 - printf("[sx1278] Confuring Skyward 433 frontend...\n"); - std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend( - new Boardcore::Skyward433Frontend()); -#else - printf("[sx1278] Confuring RA01 frontend...\n"); - std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend( - new Boardcore::RA01Frontend()); -#endif + auto serial = DefaultConsole::instance().get(); + serial->writeBlock(&EOT, 1, 0); + serial->readBlock(serial_buffer, PACKET_SIZE, 0); -#ifdef SX1278_IS_LORA - // Run default configuration - Boardcore::SX1278Lora::Config config; - Boardcore::SX1278Lora::Error err; + // this may be shrunk to the above statement (needs further testing) + memcpy(ptr_to_tm, serial_buffer, PACKET_SIZE); - sx1278 = new Boardcore::SX1278Lora(sx1278_bus, cs::getPin(), dio0::getPin(), - dio1::getPin(), dio3::getPin(), - Boardcore::SPI::ClockDivider::DIV_64, - std::move(frontend)); + return tm; +} - printf("\n[sx1278] Configuring sx1278 lora...\n"); - if ((err = sx1278->init(config)) != Boardcore::SX1278Lora::Error::NONE) - { - printf("[sx1278] sx1278->init error\n"); - return -1; - } +void initBoard() +{ + printf("[sx1278] Configuring RA01 frontend...\n"); + std::unique_ptr<Boardcore::SX1278::ISX1278Frontend> frontend( + new Boardcore::RA01Frontend()); - printf("\n[sx1278] Initialization complete!\n"); -#else // Run default configuration - Boardcore::SX1278Fsk::Config config; Boardcore::SX1278Fsk::Error err; - config.freq_rf = 434000000; - config.enable_crc = false; - sx1278 = new Boardcore::SX1278Fsk(sx1278_bus, cs::getPin(), dio0::getPin(), dio1::getPin(), dio3::getPin(), Boardcore::SPI::ClockDivider::DIV_256, std::move(frontend)); printf("\n[sx1278] Configuring sx1278 fsk...\n"); - if ((err = sx1278->init(config)) != Boardcore::SX1278Fsk::Error::NONE) + if ((err = sx1278->init(RADIO_CONFIG)) != Boardcore::SX1278Fsk::Error::NONE) { // FIXME: Why does clang-format put this line up here? printf("[sx1278] sx1278->init error\n"); - return false; + return; } printf("\n[sx1278] Initialization complete!\n"); -#endif - -#if defined SX1278_IS_SENDER - sendLoop(); -#elif defined SX1278_IS_RECEIVER - recvLoop(); -#else - // Actually spawn threads - std::thread send([]() { sendLoop(); }); - recvLoop(); -#endif - - return 0; }