From 54cb353b4797f790790537d8b5792719d6bc9b85 Mon Sep 17 00:00:00 2001 From: Alberto Nidasio <alberto.nidasio@skywarder.eu> Date: Wed, 27 Jul 2022 16:18:26 +0000 Subject: [PATCH] [CanHandler] Updated implementation of can protocol --- skyward-boardcore | 2 +- .../Auxiliary/CanHandler/CanHandler.cpp | 20 ++- src/boards/Main/CanHandler/CanHandler.cpp | 29 +++- src/boards/Main/CanHandler/CanHandler.h | 8 +- src/boards/Main/Radio/Radio.cpp | 23 +-- src/boards/Main/Radio/Radio.h | 4 +- src/boards/Payload/Actuators/Actuators.cpp | 13 +- src/boards/Payload/Actuators/Actuators.h | 8 + src/boards/Payload/CanHandler/CanHandler.cpp | 52 +++++- src/boards/Payload/CanHandler/CanHandler.h | 8 + src/boards/Payload/PinHandler/PinHandler.cpp | 31 +--- src/boards/Payload/PinHandler/PinHandler.h | 12 +- src/boards/Payload/Radio/Radio.cpp | 15 +- src/entrypoints/Auxiliary/auxiliary-entry.cpp | 4 +- {scripts => src/scripts}/eventgen.sh | 0 {scripts => src/scripts}/fsmgen.sh | 0 {scripts => src/scripts}/logdecoder/Makefile | 0 .../scripts}/logdecoder/logdecoder.cpp | 0 src/tests/Main/test-can-handler.cpp | 6 +- src/tests/common/test-can-event-handler.h | 70 --------- .../test-auxiliary-can.cpp | 83 ---------- .../test-flight-event-handler.h | 103 ------------ .../test-can-flight-sim/test-main-can.cpp | 148 ------------------ .../test-can-flight-sim/test-payload-can.cpp | 112 ------------- src/tests/common/test-can-handler.cpp | 97 ------------ 25 files changed, 154 insertions(+), 694 deletions(-) rename {scripts => src/scripts}/eventgen.sh (100%) rename {scripts => src/scripts}/fsmgen.sh (100%) rename {scripts => src/scripts}/logdecoder/Makefile (100%) rename {scripts => src/scripts}/logdecoder/logdecoder.cpp (100%) delete mode 100644 src/tests/common/test-can-event-handler.h delete mode 100644 src/tests/common/test-can-flight-sim/test-auxiliary-can.cpp delete mode 100644 src/tests/common/test-can-flight-sim/test-flight-event-handler.h delete mode 100644 src/tests/common/test-can-flight-sim/test-main-can.cpp delete mode 100644 src/tests/common/test-can-flight-sim/test-payload-can.cpp delete mode 100644 src/tests/common/test-can-handler.cpp diff --git a/skyward-boardcore b/skyward-boardcore index 8fc3bebc5..58e6975cc 160000 --- a/skyward-boardcore +++ b/skyward-boardcore @@ -1 +1 @@ -Subproject commit 8fc3bebc5211d0b384cfdc3467b36c0a09feeab4 +Subproject commit 58e6975cc65e582edcc83c8db2b778673732afaa diff --git a/src/boards/Auxiliary/CanHandler/CanHandler.cpp b/src/boards/Auxiliary/CanHandler/CanHandler.cpp index 14f9bf1de..eaa9f2011 100644 --- a/src/boards/Auxiliary/CanHandler/CanHandler.cpp +++ b/src/boards/Auxiliary/CanHandler/CanHandler.cpp @@ -54,16 +54,24 @@ CanHandler::CanHandler() static_cast<uint8_t>(Board::BROADCAST)); protocol->addFilter(static_cast<uint8_t>(Board::MAIN), static_cast<uint8_t>(Board::AUXILIARY)); + protocol->addFilter(static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::BROADCAST)); + protocol->addFilter(static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::AUXILIARY)); driver->init(); - - printf("Init done\n"); } void CanHandler::handleCanMessage(const CanMessage &msg) { PrimaryType msgType = static_cast<PrimaryType>(msg.getPrimaryType()); - printf("Received message\n"); + printf("Received packet:\n"); + printf("\tpriority: %d\n", msg.getPriority()); + printf("\tprimary type: %d\n", msg.getPrimaryType()); + printf("\tsource: %d\n", msg.getSource()); + printf("\tdestination: %d\n", msg.getDestination()); + printf("\tsecondary type: %d\n", msg.getSecondaryType()); + printf("\n"); switch (msgType) { @@ -84,15 +92,13 @@ void CanHandler::handleCanEvent(const CanMessage &msg) { EventId eventId = static_cast<EventId>(msg.getSecondaryType()); - printf("Handling event\n"); - switch (eventId) { case EventId::ARM: case EventId::CAM_ON: { Actuators::getInstance().ledOn(); - // Actuators::getInstance().camOn(); + Actuators::getInstance().camOn(); LOG_DEBUG(logger, "Cameras and leds turned on"); break; } @@ -100,7 +106,7 @@ void CanHandler::handleCanEvent(const CanMessage &msg) case EventId::CAM_OFF: { Actuators::getInstance().ledOff(); - // Actuators::getInstance().camOff(); + Actuators::getInstance().camOff(); LOG_DEBUG(logger, "Cameras and leds turned off"); break; } diff --git a/src/boards/Main/CanHandler/CanHandler.cpp b/src/boards/Main/CanHandler/CanHandler.cpp index db6ef1eb1..3ed419bcf 100644 --- a/src/boards/Main/CanHandler/CanHandler.cpp +++ b/src/boards/Main/CanHandler/CanHandler.cpp @@ -41,7 +41,25 @@ bool CanHandler::start() { return protocol->start(); } bool CanHandler::isStarted() { return protocol->isStarted(); } -void CanHandler::camOn() +void CanHandler::sendArmEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::MAIN), + static_cast<uint8_t>(Board::BROADCAST), + static_cast<uint8_t>(EventId::ARM)); +} + +void CanHandler::sendDisarmEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::MAIN), + static_cast<uint8_t>(Board::BROADCAST), + static_cast<uint8_t>(EventId::DISARM)); +} + +void CanHandler::sendCamOnEvent() { protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), static_cast<uint8_t>(PrimaryType::EVENTS), @@ -50,7 +68,7 @@ void CanHandler::camOn() static_cast<uint8_t>(EventId::CAM_ON)); } -void CanHandler::camOff() +void CanHandler::sendCamOffEvent() { protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), static_cast<uint8_t>(PrimaryType::EVENTS), @@ -65,10 +83,15 @@ CanHandler::CanHandler() bitTiming.baudRate = BAUD_RATE; bitTiming.samplePoint = SAMPLE_POINT; driver = new CanbusDriver(CAN1, {}, bitTiming); - driver->init(); protocol = new CanProtocol(driver, bind(&CanHandler::handleCanMessage, this, _1)); + + // protocol->addFilter(static_cast<uint8_t>(Board::MAIN), + // static_cast<uint8_t>(Board::BROADCAST)); + // protocol->addFilter(static_cast<uint8_t>(Board::MAIN), + // static_cast<uint8_t>(Board::AUXILIARY)); + driver->init(); } void CanHandler::handleCanMessage(const CanMessage &msg) diff --git a/src/boards/Main/CanHandler/CanHandler.h b/src/boards/Main/CanHandler/CanHandler.h index 07ece394a..b4aaccbf7 100644 --- a/src/boards/Main/CanHandler/CanHandler.h +++ b/src/boards/Main/CanHandler/CanHandler.h @@ -46,9 +46,13 @@ public: // void logStatus(); - void camOn(); + void sendArmEvent(); - void camOff(); + void sendDisarmEvent(); + + void sendCamOnEvent(); + + void sendCamOffEvent(); private: CanHandler(); diff --git a/src/boards/Main/Radio/Radio.cpp b/src/boards/Main/Radio/Radio.cpp index 312c8efa6..ef9977b9e 100644 --- a/src/boards/Main/Radio/Radio.cpp +++ b/src/boards/Main/Radio/Radio.cpp @@ -25,6 +25,7 @@ #include <Main/Actuators/Actuators.h> #include <Main/BoardScheduler.h> #include <Main/Buses.h> +#include <Main/CanHandler/CanHandler.h> #include <Main/PinHandler/PinHandler.h> #include <Main/Sensors/Sensors.h> #include <Main/TMRepository/TMRepository.h> @@ -47,8 +48,8 @@ void __attribute__((used)) EXTI10_IRQHandlerImpl() { using namespace Main; - if (Radio::getInstance().sx1278) - Radio::getInstance().sx1278->handleDioIRQ(); + if (Radio::getInstance().transceiver) + Radio::getInstance().transceiver->handleDioIRQ(); } namespace Main @@ -109,17 +110,17 @@ Radio::Radio() { // transceiver = new SerialTransceiver(Buses::getInstance().usart1); - sx1278 = + transceiver = new SX1278(Buses::getInstance().spi5, sensors::sx127x::cs::getPin()); - // Use default configuration - sx1278->init({}); + // // Use default configuration + transceiver->init({}); enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE); - mavDriver = - new MavDriver(sx1278, bind(&Radio::handleMavlinkMessage, this, _1, _2), - 0, MAV_OUT_BUFFER_MAX_AGE); + mavDriver = new MavDriver(transceiver, + bind(&Radio::handleMavlinkMessage, this, _1, _2), + 0, MAV_OUT_BUFFER_MAX_AGE); // Add to the scheduler the flight and statistics telemetries BoardScheduler::getInstance().getScheduler().addTask( @@ -431,6 +432,7 @@ void Radio::handleCommand(const mavlink_message_t& msg) LOG_DEBUG(logger, "Received command arm"); EventBroker::getInstance().post(TMTC_ARM, TOPIC_TMTC); + CanHandler::getInstance().sendArmEvent(); break; } @@ -439,6 +441,7 @@ void Radio::handleCommand(const mavlink_message_t& msg) LOG_DEBUG(logger, "Received command disarm"); EventBroker::getInstance().post(TMTC_DISARM, TOPIC_TMTC); + CanHandler::getInstance().sendArmEvent(); break; } @@ -506,14 +509,14 @@ void Radio::handleCommand(const mavlink_message_t& msg) { LOG_DEBUG(logger, "Received command start recording"); - // TODO: Apply command + CanHandler::getInstance().sendCamOnEvent(); break; } case MAV_CMD_STOP_RECORDING: { LOG_DEBUG(logger, "Received command stop recording"); - // TODO: Apply command + CanHandler::getInstance().sendCamOffEvent(); break; } diff --git a/src/boards/Main/Radio/Radio.h b/src/boards/Main/Radio/Radio.h index eac2b901e..59c2de324 100644 --- a/src/boards/Main/Radio/Radio.h +++ b/src/boards/Main/Radio/Radio.h @@ -25,8 +25,8 @@ #include <Main/Configs/RadioConfig.h> #include <common/Mavlink.h> #include <radio/MavlinkDriver/MavlinkDriver.h> -// #include <radio/SerialTransceiver/SerialTransceiver.h> #include <radio/SX1278/SX1278.h> +#include <radio/SerialTransceiver/SerialTransceiver.h> #include <scheduler/TaskScheduler.h> namespace Main @@ -42,7 +42,7 @@ class Radio : public Boardcore::Singleton<Radio> public: // Boardcore::SerialTransceiver* transceiver; - Boardcore::SX1278* sx1278; + Boardcore::SX1278* transceiver; MavDriver* mavDriver; diff --git a/src/boards/Payload/Actuators/Actuators.cpp b/src/boards/Payload/Actuators/Actuators.cpp index 22c5ebc28..23395bedb 100644 --- a/src/boards/Payload/Actuators/Actuators.cpp +++ b/src/boards/Payload/Actuators/Actuators.cpp @@ -23,10 +23,7 @@ #include "Actuators.h" #include <Payload/Configs/ActuatorsConfigs.h> - -#ifndef COMPILE_FOR_HOST -#include <interfaces-impl/hwmapping.h> -#endif +#include <interfaces-impl/bsp_impl.h> using namespace miosix; using namespace Payload::ActuatorsConfigs; @@ -139,6 +136,14 @@ float Actuators::getServoPosition(ServosList servoId) return 0; } +void Actuators::ledOn() { miosix::ledOn(); } + +void Actuators::ledOff() { miosix::ledOff(); } + +void Actuators::camOn() { interfaces::camMosfet::high(); } + +void Actuators::camOff() { interfaces::camMosfet::low(); } + Actuators::Actuators() : led1(leds::led_red1::getPin()), led2(leds::led_red2::getPin()), led3(leds::led_blue1::getPin()), diff --git a/src/boards/Payload/Actuators/Actuators.h b/src/boards/Payload/Actuators/Actuators.h index 686b091b1..e3dff18c2 100644 --- a/src/boards/Payload/Actuators/Actuators.h +++ b/src/boards/Payload/Actuators/Actuators.h @@ -71,6 +71,14 @@ struct Actuators : public Boardcore::Singleton<Actuators> float getServoPosition(ServosList servoId); + void ledOn(); + + void ledOff(); + + void camOn(); + + void camOff(); + private: Actuators(); diff --git a/src/boards/Payload/CanHandler/CanHandler.cpp b/src/boards/Payload/CanHandler/CanHandler.cpp index 03ebc2d90..bd3606ea4 100644 --- a/src/boards/Payload/CanHandler/CanHandler.cpp +++ b/src/boards/Payload/CanHandler/CanHandler.cpp @@ -22,6 +22,7 @@ #include "CanHandler.h" +#include <Payload/Actuators/Actuators.h> #include <Payload/BoardScheduler.h> #include <Payload/Configs/SensorsConfig.h> #include <Payload/Sensors/Sensors.h> @@ -46,17 +47,58 @@ bool CanHandler::start() { return protocol->start(); } bool CanHandler::isStarted() { return protocol->isStarted(); } +void CanHandler::sendArmEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::BROADCAST), + static_cast<uint8_t>(EventId::ARM)); +} + +void CanHandler::sendDisarmEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::BROADCAST), + static_cast<uint8_t>(EventId::DISARM)); +} + +void CanHandler::sendCamOnEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::AUXILIARY), + static_cast<uint8_t>(EventId::CAM_ON)); +} + +void CanHandler::sendCamOffEvent() +{ + protocol->enqueueEvent(static_cast<uint8_t>(Priority::CRITICAL), + static_cast<uint8_t>(PrimaryType::EVENTS), + static_cast<uint8_t>(Board::PAYLOAD), + static_cast<uint8_t>(Board::AUXILIARY), + static_cast<uint8_t>(EventId::CAM_OFF)); +} + CanHandler::CanHandler() { CanbusDriver::AutoBitTiming bitTiming; bitTiming.baudRate = BAUD_RATE; bitTiming.samplePoint = SAMPLE_POINT; driver = new CanbusDriver(CAN1, {}, bitTiming); - driver->init(); protocol = new CanProtocol(driver, bind(&CanHandler::handleCanMessage, this, _1)); + protocol->addFilter(static_cast<uint8_t>(Board::MAIN), + static_cast<uint8_t>(Board::BROADCAST)); + protocol->addFilter(static_cast<uint8_t>(Board::MAIN), + static_cast<uint8_t>(Board::PAYLOAD)); + driver->init(); + BoardScheduler::getInstance().getScheduler().addTask( [&]() { @@ -98,11 +140,19 @@ void CanHandler::handleCanEvent(const CanMessage &msg) case EventId::ARM: { EventBroker::getInstance().post(TMTC_ARM, TOPIC_TMTC); + } + case EventId::CAM_ON: + { + Actuators::getInstance().camOn(); break; } case EventId::DISARM: { EventBroker::getInstance().post(TMTC_DISARM, TOPIC_TMTC); + } + case EventId::CAM_OFF: + { + Actuators::getInstance().camOff(); break; } diff --git a/src/boards/Payload/CanHandler/CanHandler.h b/src/boards/Payload/CanHandler/CanHandler.h index 610aa2b41..32a619033 100644 --- a/src/boards/Payload/CanHandler/CanHandler.h +++ b/src/boards/Payload/CanHandler/CanHandler.h @@ -46,6 +46,14 @@ public: // void logStatus(); + void sendArmEvent(); + + void sendDisarmEvent(); + + void sendCamOnEvent(); + + void sendCamOffEvent(); + private: CanHandler(); diff --git a/src/boards/Payload/PinHandler/PinHandler.cpp b/src/boards/Payload/PinHandler/PinHandler.cpp index e8b51b3a3..80fbe767e 100644 --- a/src/boards/Payload/PinHandler/PinHandler.cpp +++ b/src/boards/Payload/PinHandler/PinHandler.cpp @@ -37,20 +37,7 @@ using namespace Common; namespace Payload { -void PinHandler::onLaunchPinTransition(PinTransition transition) -{ - if (transition == LAUNCH_PIN_TRIGGER) - EventBroker::getInstance().post(Event{FLIGHT_LIFTOFF}, TOPIC_FLIGHT); -} - -void PinHandler::onNCPinTransition(PinTransition transition) -{ - if (transition == NC_DETACH_PIN_TRIGGER) - EventBroker::getInstance().post(Event{FLIGHT_NC_DETACHED}, - TOPIC_FLIGHT); -} - -void PinHandler::onDPLServoPinTransition(PinTransition transition) +void PinHandler::onExpulsionPinTransition(PinTransition transition) { if (transition == DPL_SERVO_PIN_TRIGGER) EventBroker::getInstance().post(Event{DPL_SERVO_ACTUATION_DETECTED}, @@ -61,10 +48,6 @@ std::map<PinsList, PinData> PinHandler::getPinsData() { std::map<PinsList, PinData> data; - data[PinsList::LAUNCH_PIN] = - PinObserver::getInstance().getPinData(inputs::launchpad::getPin()); - data[PinsList::NOSECONE_PIN] = PinObserver::getInstance().getPinData( - inputs::nosecone_detach::getPin()); data[PinsList::DEPLOYMENT_PIN] = PinObserver::getInstance().getPinData(inputs::expulsion::getPin()); @@ -73,19 +56,9 @@ std::map<PinsList, PinData> PinHandler::getPinsData() PinHandler::PinHandler() { - PinObserver::getInstance().registerPinCallback( - inputs::launchpad::getPin(), - bind(&PinHandler::onLaunchPinTransition, this, _1), - LAUNCH_PIN_THRESHOLD); - - PinObserver::getInstance().registerPinCallback( - inputs::nosecone_detach::getPin(), - bind(&PinHandler::onLaunchPinTransition, this, _1), - NC_DETACH_PIN_THRESHOLD); - PinObserver::getInstance().registerPinCallback( inputs::expulsion::getPin(), - bind(&PinHandler::onLaunchPinTransition, this, _1), + bind(&PinHandler::onExpulsionPinTransition, this, _1), DPL_SERVO_PIN_THRESHOLD); } diff --git a/src/boards/Payload/PinHandler/PinHandler.h b/src/boards/Payload/PinHandler/PinHandler.h index cc1ada229..7fadfe59d 100644 --- a/src/boards/Payload/PinHandler/PinHandler.h +++ b/src/boards/Payload/PinHandler/PinHandler.h @@ -41,21 +41,11 @@ class PinHandler : public Boardcore::Singleton<PinHandler> friend Boardcore::Singleton<PinHandler>; public: - /** - * @brief Called when a launch pin is detected. - */ - void onLaunchPinTransition(Boardcore::PinTransition transition); - - /** - * @brief Called when the nosecone pin is detected. - */ - void onNCPinTransition(Boardcore::PinTransition transition); - /** * @brief Called when the deployment servo actuation is detected via the * optical sensor. */ - void onDPLServoPinTransition(Boardcore::PinTransition transition); + void onExpulsionPinTransition(Boardcore::PinTransition transition); /** * @brief Returns a vector with all the pins data. diff --git a/src/boards/Payload/Radio/Radio.cpp b/src/boards/Payload/Radio/Radio.cpp index 4f497769d..de2bb32b5 100644 --- a/src/boards/Payload/Radio/Radio.cpp +++ b/src/boards/Payload/Radio/Radio.cpp @@ -25,6 +25,7 @@ #include <Payload/Actuators/Actuators.h> #include <Payload/BoardScheduler.h> #include <Payload/Buses.h> +#include <Payload/CanHandler/CanHandler.h> #include <Payload/PinHandler/PinHandler.h> #include <Payload/Sensors/Sensors.h> #include <common/events/Events.h> @@ -438,7 +439,7 @@ void Radio::handleCommand(const mavlink_message_t& msg) LOG_DEBUG(logger, "Received command arm"); EventBroker::getInstance().post(TMTC_ARM, TOPIC_TMTC); - + CanHandler::getInstance().sendArmEvent(); break; } case MAV_CMD_DISARM: @@ -446,7 +447,7 @@ void Radio::handleCommand(const mavlink_message_t& msg) LOG_DEBUG(logger, "Received command disarm"); EventBroker::getInstance().post(TMTC_DISARM, TOPIC_TMTC); - + CanHandler::getInstance().sendDisarmEvent(); break; } case MAV_CMD_FORCE_LAUNCH: @@ -513,14 +514,18 @@ void Radio::handleCommand(const mavlink_message_t& msg) { LOG_DEBUG(logger, "Received command start recording"); - // TODO: Apply command + Actuators::getInstance().camOn(); + Actuators::getInstance().ledOn(); + CanHandler::getInstance().sendCamOnEvent(); break; } case MAV_CMD_STOP_RECORDING: { LOG_DEBUG(logger, "Received command stop recording"); - // TODO: Apply command + Actuators::getInstance().camOff(); + Actuators::getInstance().ledOff(); + CanHandler::getInstance().sendCamOffEvent(); break; } @@ -534,4 +539,4 @@ void Radio::handleCommand(const mavlink_message_t& msg) sendAck(msg); } -} // namespace Payload \ No newline at end of file +} // namespace Payload diff --git a/src/entrypoints/Auxiliary/auxiliary-entry.cpp b/src/entrypoints/Auxiliary/auxiliary-entry.cpp index 53c8462b4..f3fe49c20 100644 --- a/src/entrypoints/Auxiliary/auxiliary-entry.cpp +++ b/src/entrypoints/Auxiliary/auxiliary-entry.cpp @@ -30,8 +30,6 @@ int main() { CanHandler::getInstance().start(); - printf("Started\n"); - while (true) Thread::sleep(1000); -} \ No newline at end of file +} diff --git a/scripts/eventgen.sh b/src/scripts/eventgen.sh similarity index 100% rename from scripts/eventgen.sh rename to src/scripts/eventgen.sh diff --git a/scripts/fsmgen.sh b/src/scripts/fsmgen.sh similarity index 100% rename from scripts/fsmgen.sh rename to src/scripts/fsmgen.sh diff --git a/scripts/logdecoder/Makefile b/src/scripts/logdecoder/Makefile similarity index 100% rename from scripts/logdecoder/Makefile rename to src/scripts/logdecoder/Makefile diff --git a/scripts/logdecoder/logdecoder.cpp b/src/scripts/logdecoder/logdecoder.cpp similarity index 100% rename from scripts/logdecoder/logdecoder.cpp rename to src/scripts/logdecoder/logdecoder.cpp diff --git a/src/tests/Main/test-can-handler.cpp b/src/tests/Main/test-can-handler.cpp index 035c0e54b..b31394812 100644 --- a/src/tests/Main/test-can-handler.cpp +++ b/src/tests/Main/test-can-handler.cpp @@ -32,12 +32,12 @@ int main() while (true) { - CanHandler::getInstance().camOn(); + CanHandler::getInstance().sendCamOnEvent(); printf("Sent event for cam on\n"); Thread::sleep(1000); - CanHandler::getInstance().camOff(); + CanHandler::getInstance().sendCamOffEvent(); printf("Sent event for cam off\n"); Thread::sleep(1000); } -} \ No newline at end of file +} diff --git a/src/tests/common/test-can-event-handler.h b/src/tests/common/test-can-event-handler.h deleted file mode 100644 index a228cc67a..000000000 --- a/src/tests/common/test-can-event-handler.h +++ /dev/null @@ -1,70 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#pragma once - -#include <common/canbus/CanHandler.h> -#include <events/EventBroker.h> -#include <events/EventHandler.h> - -class MyEventHandler : public Boardcore::EventHandler -{ -public: - MyEventHandler() - : EventHandler(), // call parent constructor - last_event(0) - { - // make this object to subscribe to TOPIC_CAN_EVENTS - Boardcore::EventBroker::getInstance().subscribe( - this, common::CanTopics::TOPIC_CAN_EVENTS); - } - - ~MyEventHandler() - { - // unsubscribe from all the topics this object was subscribed to - Boardcore::EventBroker::getInstance().unsubscribe(this); - } - -protected: - void handleEvent(const Boardcore::Event& ev) override - { - switch (ev) - { - case common::CanEvent::EV_LIFTOFF: - TRACE("Received EV_LIFTOFF \n"); - break; - case common::CanEvent::EV_APOGEE: - TRACE("Received EV_APOGEE \n"); - break; - case common::CanEvent::EV_ARMED: - TRACE("Received EV_ARMED \n"); - break; - default: - TRACE("Invalid event \n"); - } - - last_event = ev; - } - -private: - uint8_t last_event; -}; diff --git a/src/tests/common/test-can-flight-sim/test-auxiliary-can.cpp b/src/tests/common/test-can-flight-sim/test-auxiliary-can.cpp deleted file mode 100644 index 58b51fbc2..000000000 --- a/src/tests/common/test-can-flight-sim/test-auxiliary-can.cpp +++ /dev/null @@ -1,83 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include <common/canbus/CanHandler.h> -#include <common/canbus/MockSensors/MockPitot.h> -#include <time.h> -#include <utils/collections/IRQCircularBuffer.h> - -#include <thread> - -#include "test-flight-event-handler.h" - -using namespace Boardcore::Canbus; -using namespace miosix; -using namespace common; - -CanHandler* handler; -bool running; -void receivePressure(MockPitot* pitot) -{ - while (true) - { - (*pitot).waitTillUpdated(); - (*pitot).getData(); - TRACE("ERROR received a pressure \n"); - } -} - -int main() -{ - // We accept only packet with source main - Filter f; - f.source = Boards::Main; - - MockPitot* pitot = new MockPitot(Pitot); - handler = new CanHandler(Boards::Main); - handler->addFilter(f); - (*handler).startHandler(); - - // We expect to receive multiple*100 packet of AereoBrakes packet,and - // multiple of each command packet - - MyEventHandler evh; - TRACE("Start sending\n"); - if (evh.start()) - { - std::thread recPress(receivePressure, pitot); - for (;;) - { - running = true; - evh.waitReset(); // First reset is to start sending - evh.waitReset(); // the second to stop - running = false; - evh.checkCounters(nEvents); - // We stop for 100 ms to wait for any unfinished print - Thread::sleep(100); - } - evh.stop(); // it posts an EV_EMPTY to wake up the thread - } - else - { - TRACE("Failed to start MyEventHandler\n"); - } -} diff --git a/src/tests/common/test-can-flight-sim/test-flight-event-handler.h b/src/tests/common/test-can-flight-sim/test-flight-event-handler.h deleted file mode 100644 index 2dc4a3e15..000000000 --- a/src/tests/common/test-can-flight-sim/test-flight-event-handler.h +++ /dev/null @@ -1,103 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#pragma once - -#include <common/canbus/CanConfig.h> -#include <events/EventBroker.h> -#include <events/EventHandler.h> - -#define MULTIPLIER 10 - -#define nPressure 100 * MULTIPLIER -#define nAir 50 * MULTIPLIER -#define nEvents 1 * MULTIPLIER - -class MyEventHandler : public Boardcore::EventHandler -{ -public: - MyEventHandler() - : EventHandler(), // call parent constructor - last_event(0) - { - // make this object to subscribe to TOPIC_CAN_EVENTS - Boardcore::EventBroker::getInstance().subscribe( - this, common::CanTopics::TOPIC_CAN_EVENTS); - } - - ~MyEventHandler() - { - // unsubscribe from all the topics this object was subscribed to - Boardcore::EventBroker::getInstance().unsubscribe(this); - } - void checkCounters(int number) - { - miosix::Lock<miosix::FastMutex> l(mutex); - if (apogee == number && armed == number) - { - TRACE("Received %d number of event\n", number); - } - else - { - TRACE("Expected Value %d\n", number); - TRACE("Received Apogee %d\n", apogee); - TRACE("Received Armed %d\n", armed); - } - apogee = 0; - armed = 0; - } - - void waitReset() - { - miosix::Lock<miosix::FastMutex> l(mutex); - conVar.wait(l); - } - -protected: - void handleEvent(const Boardcore::Event& ev) override - { - miosix::Lock<miosix::FastMutex> l(mutex); - switch (ev) - { - case common::CanEvent::EV_LIFTOFF: - conVar.broadcast(); - break; - case common::CanEvent::EV_APOGEE: - apogee++; - break; - case common::CanEvent::EV_ARMED: - armed++; - break; - default: - TRACE("Invalid event \n"); - } - - last_event = ev; - } - -private: - uint8_t last_event; - int apogee = 0; - int armed = 0; - miosix::FastMutex mutex; - miosix::ConditionVariable conVar; -}; diff --git a/src/tests/common/test-can-flight-sim/test-main-can.cpp b/src/tests/common/test-can-flight-sim/test-main-can.cpp deleted file mode 100644 index da2754326..000000000 --- a/src/tests/common/test-can-flight-sim/test-main-can.cpp +++ /dev/null @@ -1,148 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include <common/canbus/CanHandler.h> -#include <common/canbus/MockSensors/MockPitot.h> -#include <time.h> -#include <utils/collections/IRQCircularBuffer.h> - -#include <atomic> -#include <thread> - -#include "test-flight-event-handler.h" - -using namespace Boardcore::Canbus; -using namespace miosix; -using namespace common; - -CanHandler* handler; -std::atomic<bool> running; // 1 element we are active 0 we are inactive -miosix::FastMutex mutex; - -void receivePressure(MockPitot* pitot) -{ - int counter = 0; - while (true) - { - while (running) - { - clock_t start = clock(); - for (int i = 0; i < nPressure; i++) - { - (*pitot).waitTillUpdated(); - counter++; - (*pitot).getData(); - } - float time = float(clock() - start) / CLOCKS_PER_SEC; - TRACE("received %d packets in %f second\n", nPressure, time); - } - while (!running) - { - Thread::sleep(10); - } - } -} - -void sendCommands() -{ - int f; - int msWait = 1000 / (nEvents * 2); - while (true) - { - for (f = 0; f < nEvents && running; f++) - { - { - miosix::Lock<miosix::FastMutex> l(mutex); - (*handler).sendCan(Boards::Broadcast, common::Priority::Low, - Type::Events, EventsId::Apogee); - } - Thread::sleep(msWait); - { - miosix::Lock<miosix::FastMutex> l(mutex); - (*handler).sendCan(Boards::Broadcast, common::Priority::Low, - Type::Events, EventsId::Armed); - } - Thread::sleep(msWait); - } - TRACE("Sent %d commands\n", f); - if (f == nEvents) - { - while (running) - { - Thread::sleep(10); - } - } - while (!running) - { - Thread::sleep(10); - } - } -} - -int main() -{ - // We accept only packet with destination main - Filter f; - f.destination = Boards::Main; - MockPitot* pitot = new MockPitot(Pitot); - handler = new CanHandler(Boards::Main); - handler->addFilter(f); - (*handler).addMock(pitot); - - (*handler).startHandler(); - - // We expect to receive multiple*100 packet of Pressure packet, - // send multiple*100 AirBrakes Packet and multiple of each command packet - MyEventHandler evh; - TRACE("Start sending\n"); - if (evh.start()) - { - std::thread recPress(receivePressure, pitot); - std::thread sendCmd(sendCommands); - for (;;) - { - running = true; - { - miosix::Lock<miosix::FastMutex> l(mutex); - (*handler).sendCan(Boards::Broadcast, - common::Priority::Critical, Type::Events, - EventsId::Liftoff); - } - Thread::sleep(1000); - running = false; - { - miosix::Lock<miosix::FastMutex> l(mutex); - (*handler).sendCan(Boards::Broadcast, - common::Priority::Critical, Type::Events, - EventsId::Liftoff); - } - evh.checkCounters(0); - // We stop for 100 ms to wait for any unfinished print - Thread::sleep(100); - } - evh.stop(); // it posts an EV_EMPTY to wake up the thread - } - else - { - TRACE("Failed to start MyEventHandler\n"); - } -} diff --git a/src/tests/common/test-can-flight-sim/test-payload-can.cpp b/src/tests/common/test-can-flight-sim/test-payload-can.cpp deleted file mode 100644 index 2871546c5..000000000 --- a/src/tests/common/test-can-flight-sim/test-payload-can.cpp +++ /dev/null @@ -1,112 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include <common/canbus/CanHandler.h> -#include <common/canbus/MockSensors/MockPitot.h> -#include <utils/collections/IRQCircularBuffer.h> - -#include <atomic> -#include <thread> - -#include "test-flight-event-handler.h" - -using namespace Boardcore::Canbus; -using namespace miosix; -using namespace common; -CanHandler* handler; -std::atomic<bool> running; // 1 element we are active 0 we are inactive -void receivePressure(MockPitot* pitot) -{ - while (true) - { - (*pitot).waitTillUpdated(); - (*pitot).getData(); - TRACE("ERROR received a pressure packet\n"); - } -} - -void sendPressure(MockPitot* pitot) -{ - CanData temp = pitot->parseData({240, 1234.23}); - int f; - int msWait = 1000 / (nPressure); - while (true) - { - for (f = 0; f < nPressure && running; f++) - { - (*handler).sendCan(Boards::Main, common::Priority::Critical, - Type::Sensor, SensorId::Pitot, temp); - Thread::sleep(msWait); - } - TRACE("Sent %d pressure packets\n", f); - if (f == nPressure) - { - while (running) - { - Thread::sleep(10); - } - } - while (!running) - { - Thread::sleep(10); - } - } -} - -int main() -{ - - // We accept only packet with source main and destination payload - - Filter f; - f.source = Boards::Main; - f.destination = Boards::Broadcast; - MockPitot* pitot = new MockPitot(Pitot); - handler = new CanHandler(Boards::Main); - handler->addFilter(f); - - (*handler).startHandler(); - - // We expect to send multiple*100 packet of Pressure packet and receive - // multiple of each command packet - MyEventHandler evh; - if (evh.start()) - { - std::thread sendPress(sendPressure, pitot); - std::thread recPress(receivePressure, pitot); - for (;;) - { - running = true; - evh.waitReset(); // First reset is to start sending - evh.waitReset(); // the second to stop - running = false; - evh.checkCounters(nEvents); - // We stop for 100 ms to wait for any unfinished print - Thread::sleep(100); - } - evh.stop(); // It posts an EV_EMPTY to wake up the thread - } - else - { - TRACE("Failed to start MyEventHandler\n"); - } -} diff --git a/src/tests/common/test-can-handler.cpp b/src/tests/common/test-can-handler.cpp deleted file mode 100644 index bf82b4564..000000000 --- a/src/tests/common/test-can-handler.cpp +++ /dev/null @@ -1,97 +0,0 @@ -/* Copyright (c) 2022 Skyward Experimental Rocketry - * Author: Federico Mandelli - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - */ - -#include <common/canbus/CanHandler.h> -#include <common/canbus/MockSensors/MockPitot.h> -#include <drivers/canbus/BusLoadEstimation.h> -#include <drivers/canbus/Canbus.h> -#include <utils/collections/CircularBuffer.h> - -#include <thread> - -#include "test-can-event-handler.h" - -#define slp 1000 - -using namespace Boardcore::Canbus; -using namespace miosix; -using namespace common; - -void checkPressureData(MockPitot* pitot) -{ - Thread::sleep(10); // De-synchronize the sending from the receiving; - - while (true) - { - if ((*pitot).waitTillUpdated()) - { - TRACE("Received pressure packet. Data: %f, timestamp %llu\n", - (*pitot).getData().pressure, - (*pitot).getData().pressureTimestamp); - } - else - { - TRACE("No Pressure packet received in this time slot\n"); - } - - Thread::sleep(slp); - } -} - -int main() -{ - MockPitot* pitot = new MockPitot(SensorId::Pitot); - CanHandler handler(Boards::Main); - handler.addMock(pitot); - Filter f; // empty filter to accept all incoming messages - - handler.addFilter(f); - handler.startHandler(); - // send event, data and command - Boardcore::PressureData t{240, 12354.35}; - MyEventHandler evh; - if (evh.start()) - { - std::thread printPressureData(checkPressureData, pitot); - - for (;;) - { - TRACE("Sent a packet \n"); - handler.sendCan(Boards::Payload, common::Priority::Medium, - Type::Sensor, SensorId::Pitot, - (*pitot).parseData(t)); - // if we have to send a command we do not use a payload - handler.sendCan(Boards::Main, common::Priority::Low, Type::Events, - EventsId::Liftoff); - handler.sendCan(Boards::Main, common::Priority::Low, Type::Events, - EventsId::Apogee); - handler.sendCan(Boards::Main, common::Priority::Low, Type::Events, - EventsId::Armed); - Thread::sleep(slp); - } - evh.stop(); // it posts an EV_EMPTY to wake up the thread - } - else - { - TRACE("Failed to start MyEventHandler\n"); - } -} -- GitLab