Skip to content
Snippets Groups Projects
Commit 9efe9e5b authored by Emilio Corigliano's avatar Emilio Corigliano
Browse files

[HIL] Removed everything regarding HIL framework on OBSW

parent 7fa9a0ea
No related branches found
No related tags found
1 merge request!72[HIL] Updated boardcore submodule to integrate HIL framework and removed old OBSW HIL framework
Pipeline #9629 passed
Showing
with 0 additions and 2087 deletions
......@@ -89,30 +89,6 @@
"${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_compute_unit/**"
]
},
{
"name": "stm32f767zi_compute_unit_HIL",
"cStandard": "c11",
"cppStandard": "c++14",
"compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
"defines": [
"{defaultDefines}",
"_MIOSIX_BOARDNAME=stm32f767zi_compute_unit",
"_BOARD_STM32F767ZI_COMPUTE_UNIT",
"_ARCH_CORTEXM7_STM32F7",
"STM32F767xx",
"HSE_VALUE=25000000",
"SYSCLK_FREQ_216MHz=216000000",
"__ENABLE_XRAM",
"V_DDA_VOLTAGE=3.3f",
"HILTest"
],
"includePath": [
"${defaultIncludePaths}",
"${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM7_stm32f7/common",
"${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_compute_unit/**",
"${workspaceFolder}/src/hardware_in_the_loop"
]
},
{
"name": "stm32f767zi_death_stack_v4",
"cStandard": "c11",
......@@ -133,29 +109,6 @@
"${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_death_stack_v4/**"
]
},
{
"name": "stm32f767zi_death_stack_v4_HIL",
"cStandard": "c11",
"cppStandard": "c++14",
"compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
"defines": [
"{defaultDefines}",
"_ARCH_CORTEXM7_STM32F7",
"_BOARD_STM32F767ZI_DEATH_STACK_V4",
"_MIOSIX_BOARDNAME=stm32f767zi_death_stack_v4",
"HSE_VALUE=8000000",
"SYSCLK_FREQ_168MHz=168000000",
"ROCCARASO",
"HILSimulation",
"HILMain"
],
"includePath": [
"${defaultIncludePaths}",
"${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM7_stm32f7/common",
"${workspaceFolder}/skyward-boardcore/src/bsps/stm32f767zi_death_stack_v4/**",
"${workspaceFolder}/src/hardware_in_the_loop"
]
},
{
"name": "stm32f429zi_skyward_pyxis_auxiliary",
"cStandard": "c11",
......
......@@ -34,11 +34,6 @@ project(OnBoardSoftware)
# Flight entrypoints #
#-----------------------------------------------------------------------------#
add_executable(test-hil src/entrypoints/HIL/test-hil.cpp ${HIL})
target_include_directories(test-hil PRIVATE ${OBSW_INCLUDE_DIRS})
target_compile_definitions(test-hil PRIVATE HILTest)
sbs_target(test-hil stm32f767zi_compute_unit)
add_executable(main-entry src/entrypoints/Main/main-entry.cpp ${MAIN_COMPUTER})
target_include_directories(main-entry PRIVATE ${OBSW_INCLUDE_DIRS})
sbs_target(main-entry stm32f767zi_death_stack_v4)
......
......@@ -22,12 +22,6 @@
set(OBSW_INCLUDE_DIRS
src
src/boards
src/hardware_in_the_loop
)
set(HIL
src/hardware_in_the_loop/HIL/HILFlightPhasesManager.cpp
src/hardware_in_the_loop/HIL/HILTransceiver.cpp
)
set(MAIN_COMPUTER
......
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <drivers/timer/TimestampTimer.h>
#include <drivers/usart/USART.h>
#include <utils/Debug.h>
#include <utils/Stats/Stats.h>
#include <list>
#include <utils/ModuleManager/ModuleManager.hpp>
#include "algorithms/ADA/ADAData.h"
#include "algorithms/NAS/NAS.h"
#include "algorithms/NAS/NASState.h"
#include "sensors/SensorInfo.h"
namespace HILConfig
{
struct SensorConfig : public Boardcore::SensorInfo
{
SensorConfig(const std::string s, const uint32_t period)
: Boardcore::SensorInfo{s, period, []() {}, true}
{
}
};
/** baudrate of connection */
const int SIM_BAUDRATE = 115200;
/** Period of simulation in milliseconds */
const int SIMULATION_PERIOD = 100;
/** sample frequency of sensor (samples/second) */
const int ACCEL_FREQ = 100;
const int GYRO_FREQ = 100;
const int MAGN_FREQ = 100;
const int IMU_FREQ = 100;
const int BARO_FREQ = 20;
const int PITOT_FREQ = 20;
const int TEMP_FREQ = 10;
const int GPS_FREQ = 10;
// /** update frequency of airbrakes control algorithm */
// const int CONTROL_FREQ = 10;
// /** min and max values in radiants of the actuator */
// const float MinAlphaDegree = 0.0;
// const float MaxAlphaDegree = 0.84;
/** sensors configuration */
const SensorConfig accelConfig("accel", ACCEL_FREQ);
const SensorConfig gyroConfig("gyro", GYRO_FREQ);
const SensorConfig magnConfig("magn", MAGN_FREQ);
const SensorConfig imuConfig("imu", IMU_FREQ);
const SensorConfig baroConfig("baro", BARO_FREQ);
const SensorConfig pitotConfig("pitot", PITOT_FREQ);
const SensorConfig gpsConfig("gps", GPS_FREQ);
const SensorConfig tempConfig("temp", TEMP_FREQ);
/** Number of samples per sensor at each simulator iteration */
const int N_DATA_ACCEL = (ACCEL_FREQ * SIMULATION_PERIOD) / 1000; // 10
const int N_DATA_GYRO = (GYRO_FREQ * SIMULATION_PERIOD) / 1000; // 10
const int N_DATA_MAGN = (MAGN_FREQ * SIMULATION_PERIOD) / 1000; // 10
const int N_DATA_IMU = (IMU_FREQ * SIMULATION_PERIOD) / 1000; // 10
const int N_DATA_BARO = (BARO_FREQ * SIMULATION_PERIOD) / 1000; // 2
const int N_DATA_PITOT = (PITOT_FREQ * SIMULATION_PERIOD) / 1000; // 2
const int N_DATA_GPS = (GPS_FREQ * SIMULATION_PERIOD) / 1000; // 1
const int N_DATA_TEMP = (TEMP_FREQ * SIMULATION_PERIOD) / 1000; // 1
/**
* @brief Data structure used by the simulator in order to directly deserialize
* the data received
*
* This structure then is accessed by sensors and other components in order to
* get the data they need
*/
struct SimulatorData
{
struct Accelerometer
{
float measures[N_DATA_ACCEL][3];
} accelerometer;
struct Gyro
{
float measures[N_DATA_GYRO][3];
} gyro;
struct Magnetometer
{
float measures[N_DATA_MAGN][3];
} magnetometer;
struct Gps
{
float positionMeasures[N_DATA_GPS][3];
float velocityMeasures[N_DATA_GPS][3];
float fix;
float num_satellites;
} gps;
struct Barometer
{
float measures[N_DATA_BARO];
} barometer1, barometer2, barometer3;
struct Pitot
{
float deltaP[N_DATA_PITOT];
float staticPressure[N_DATA_PITOT];
} pitot;
struct Temperature
{
float measure;
} temperature;
struct Flags
{
float flag_flight;
float flag_ascent;
float flag_burning;
float flag_airbrakes;
float flag_para1;
float flag_para2;
} flags;
void printAccelerometer()
{
TRACE("accel\n");
for (int i = 0; i < N_DATA_ACCEL; i++)
TRACE("%+.3f\t%+.3f\t%+.3f\n", accelerometer.measures[i][0],
accelerometer.measures[i][1], accelerometer.measures[i][2]);
}
void printGyro()
{
TRACE("gyro\n");
for (int i = 0; i < N_DATA_GYRO; i++)
TRACE("%+.3f\t%+.3f\t%+.3f\n", gyro.measures[i][0],
gyro.measures[i][1], gyro.measures[i][2]);
}
void printMagnetometer()
{
TRACE("magneto\n");
for (int i = 0; i < N_DATA_MAGN; i++)
TRACE("%+.3f\t%+.3f\t%+.3f\n", magnetometer.measures[i][0],
magnetometer.measures[i][1], magnetometer.measures[i][2]);
}
void printGPS()
{
TRACE("gps\n");
TRACE("pos\n");
for (int i = 0; i < N_DATA_GPS; i++)
TRACE("%+.3f\t%+.3f\t%+.3f\n", gps.positionMeasures[i][0],
gps.positionMeasures[i][1], gps.positionMeasures[i][2]);
TRACE("vel\n");
for (int i = 0; i < N_DATA_GPS; i++)
TRACE("%+.3f\t%+.3f\t%+.3f\n", gps.velocityMeasures[i][0],
gps.velocityMeasures[i][1], gps.velocityMeasures[i][2]);
TRACE("fix:%+.3f\tnsat:%+.3f\n", gps.fix, gps.num_satellites);
}
void printBarometer1()
{
TRACE("press1\n");
for (int i = 0; i < N_DATA_BARO; i++)
TRACE("%+.3f\n", barometer1.measures[i]);
}
void printBarometer2()
{
TRACE("press2\n");
for (int i = 0; i < N_DATA_BARO; i++)
TRACE("%+.3f\n", barometer2.measures[i]);
}
void printBarometer3()
{
TRACE("press3\n");
for (int i = 0; i < N_DATA_BARO; i++)
TRACE("%+.3f\n", barometer3.measures[i]);
}
void printPitot()
{
TRACE("pitot\n");
for (int i = 0; i < N_DATA_PITOT; i++)
TRACE("%+.3f, \n", pitot.staticPressure[i], pitot.deltaP[i]);
}
void printTemperature()
{
TRACE("temp\n");
for (int i = 0; i < N_DATA_TEMP; i++)
TRACE("%+.3f\n", temperature.measure);
}
void printFlags()
{
TRACE("flags\n");
TRACE(
"flight:\t%+.3f\n"
"ascent:\t%+.3f\n"
"burning:\t%+.3f\n"
"airbrakes:\t%+.3f\n"
"para1:\t%+.3f\n"
"para2:\t%+.3f\n",
flags.flag_flight, flags.flag_ascent, flags.flag_burning,
flags.flag_airbrakes, flags.flag_para1, flags.flag_para2);
}
void print()
{
printAccelerometer();
printGyro();
printMagnetometer();
printGPS();
printBarometer1();
printBarometer2();
printBarometer3();
printPitot();
printTemperature();
printFlags();
}
};
/**
* @brief ADA data sent to the simulator
*/
struct ADAdataHIL
{
uint64_t ada_timestamp;
float aglAltitude; // Altitude at mean sea level [m].
float verticalSpeed; // Vertical speed [m/s].
ADAdataHIL& operator+=(const ADAdataHIL& x)
{
this->ada_timestamp += x.ada_timestamp;
this->aglAltitude += x.aglAltitude;
this->verticalSpeed += x.verticalSpeed;
return *this; // return the result by reference
}
ADAdataHIL operator/(int x)
{
return ADAdataHIL{this->ada_timestamp / x, this->aglAltitude / x,
this->verticalSpeed / x};
}
ADAdataHIL operator*(int x)
{
return ADAdataHIL{this->ada_timestamp * x, this->aglAltitude * x,
this->verticalSpeed * x};
}
static std::string header()
{
return "timestamp,aglAltitude,verticalSpeed\n";
}
void print(std::ostream& os) const
{
os << ada_timestamp << "," << aglAltitude << "," << verticalSpeed
<< "\n";
}
};
/**
* @brief Data structure expected by the simulator
*/
struct ActuatorData
{
Boardcore::NASState nasState; ///< NAS
ADAdataHIL adaState; ///< ADA
float airbrakes_opening; ///< Airbrakes opening (percentage)
float estimated_mass; ///< Estimated mass of the rocket
float liftoff; ///< Flag for liftoff
float burning_shutdown; ///< Flag for engine shutdown
void print() const
{
TRACE(
"size:%u, %u, %u\n"
"abk:%f\n"
"tsnas:%f\n"
"ned:%f,%f,%f\n"
"vned:%f,%f,%f\n"
"q:%f,%f,%f,%f\n"
"bias:%f,%f,%f\n"
"tsada:%f\n"
"ada:%f,%f\n\n",
sizeof(airbrakes_opening), sizeof(Boardcore::NASState),
sizeof(ADAdataHIL), airbrakes_opening, nasState.timestamp,
nasState.n, nasState.e, nasState.d, nasState.vn, nasState.ve,
nasState.vd, nasState.qx, nasState.qy, nasState.qz, nasState.qw,
nasState.bx, nasState.by, nasState.bz, adaState.ada_timestamp,
adaState.aglAltitude, adaState.verticalSpeed);
}
};
} // namespace HILConfig
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <HIL.h>
#include <HILConfig.h>
#include <common/Events.h>
#include <common/Topics.h>
#include <diagnostic/CpuMeter/CpuMeter.h>
#include <diagnostic/PrintLogger.h>
#include <diagnostic/StackLogger.h>
#include <drivers/timer/TimestampTimer.h>
#include <events/EventBroker.h>
#include <events/EventData.h>
#include <events/utils/EventSniffer.h>
#include <scheduler/TaskScheduler.h>
#include <utils/ModuleManager/ModuleManager.hpp>
using namespace Boardcore;
using namespace Common;
using namespace HILConfig;
int main()
{
// Overall status, if at some point it becomes false, there is a problem
// somewhere
bool initResult = true;
PrintLogger logger = Logging::getLogger("main");
// Create modules
USART usart2(USART2, 115200);
HIL* hil = new HIL(usart2, new HILFlightPhasesManager());
Boardcore::TaskScheduler scheduler;
// Insert modules
#ifdef HILTest
if (!ModuleManager::getInstance().insert<HIL>(hil))
{
initResult = false;
LOG_ERR(logger, "Error inserting the HIL module");
}
#endif
// Start modules
if (!EventBroker::getInstance().start())
{
initResult = false;
LOG_ERR(logger, "Error starting the EventBroker module");
}
if (!scheduler.start())
{
initResult = false;
LOG_ERR(logger, "Error starting the board scheduler module");
}
// Log all the events
EventSniffer sniffer(
EventBroker::getInstance(), TOPICS_LIST,
[](uint8_t event, uint8_t topic)
{
EventData ev{TimestampTimer::getTimestamp(), event, topic};
Logger::getInstance().log(ev);
});
#ifdef HILTest
if (!ModuleManager::getInstance().get<HIL>()->start())
{
initResult = false;
LOG_ERR(logger, "Error starting the HIL module");
}
scheduler.addTask(
[&]()
{
HILConfig::SimulatorData* sensorData =
ModuleManager::getInstance()
.get<HIL>()
->simulator->getSensorData();
HILConfig::ADAdataHIL adaDataHil{
Boardcore::TimestampTimer::getTimestamp(),
sensorData->gps.positionMeasures[0][2],
sensorData->gps.velocityMeasures[0][2]};
HILConfig::ActuatorData actuatorData{
NASState{},
adaDataHil,
0,
30,
sensorData->flags.flag_ascent,
sensorData->flags.flag_burning};
// Sending to the simulator
ModuleManager::getInstance().get<HIL>()->send(actuatorData);
},
HILConfig::SIMULATION_PERIOD);
// scheduler.addTask(
// [&]() {
// ModuleManager::getInstance().get<HIL>()->simulator->getSensorData()->print();
// }, 1000);
#endif
// Check the init result and launch an event
if (initResult)
{
// Post OK
LOG_INFO(logger, "Init OK");
// Set the LED status
miosix::ledOn();
}
else
{
LOG_ERR(logger, "Init ERROR");
}
// Periodic statistics
while (true)
{
Thread::sleep(1000);
printf("max: %.3f, min: %.3f, free stack: %ld, free heap: %ld\n",
CpuMeter::getCpuStats().maxValue,
CpuMeter::getCpuStats().minValue,
CpuMeter::getCpuStats().freeStack,
CpuMeter::getCpuStats().freeHeap);
CpuMeter::resetCpuStats();
StackLogger::getInstance().log();
}
return 0;
}
\ No newline at end of file
/* Copyright (c) 2021-2023 Skyward Experimental Rocketry
* Authors: Luca Conterio, Emilio Corigliano
*
* 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 <HIL/HILFlightPhasesManager.h>
#include <HIL/HILTransceiver.h>
#include <HILConfig.h>
#include <Singleton.h>
#include <utils/ModuleManager/ModuleManager.hpp>
/**
* @brief Single interface to the hardware-in-the-loop framework.
*/
class HIL : public Boardcore::Module
{
public:
HIL(Boardcore::USART &hilSerial,
HILFlightPhasesManager *flightPhasesManager)
: flightPhasesManager(flightPhasesManager)
{
simulator = new HILTransceiver(hilSerial);
}
HILTransceiver *simulator;
HILFlightPhasesManager *flightPhasesManager;
/**
* @brief Start the needed hardware-in-the-loop components.
*/
[[nodiscard]] bool start()
{
return simulator->start() && flightPhasesManager->start();
}
void stop() { simulator->stop(); }
void send(HILConfig::ActuatorData actuatorData)
{
simulator->setActuatorData(actuatorData);
}
/**
* @brief Returns if all the schedulers are up and running
*/
bool isStarted();
};
/* Copyright (c) 2021-2023 Skyward Experimental Rocketry
* Authors: Luca Conterio, Emilio Corigliano
*
* 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 "HILFlightPhasesManager.h"
#include <events/Event.h>
#include "events/EventBroker.h"
/* CPUMeter */
// #include "diagnostic/CpuMeter/CpuMeter.h"
using namespace Common;
using namespace HILConfig;
HILFlightPhasesManager::HILFlightPhasesManager()
: Boardcore::EventHandler(),
flagsFlightPhases({{FlightPhases::SIM_FLYING, false},
{FlightPhases::SIM_ASCENT, false},
{FlightPhases::SIM_BURNING, false},
{FlightPhases::SIM_AEROBRAKES, false},
{FlightPhases::SIM_PARA1, false},
{FlightPhases::SIM_PARA2, false},
{FlightPhases::SIMULATION_STARTED, false},
{FlightPhases::CALIBRATION, false},
{FlightPhases::CALIBRATION_OK, false},
{FlightPhases::ARMED, false},
{FlightPhases::LIFTOFF_PIN_DETACHED, false},
{FlightPhases::LIFTOFF, false},
{FlightPhases::AEROBRAKES, false},
{FlightPhases::APOGEE, false},
{FlightPhases::PARA1, false},
{FlightPhases::PARA2, false},
{FlightPhases::SIMULATION_STOPPED, false}})
{
prev_flagsFlightPhases = flagsFlightPhases;
auto& eventBroker = Boardcore::EventBroker::getInstance();
eventBroker.subscribe(this, TOPIC_ABK);
eventBroker.subscribe(this, TOPIC_ADA);
eventBroker.subscribe(this, TOPIC_MEA);
eventBroker.subscribe(this, TOPIC_DPL);
eventBroker.subscribe(this, TOPIC_CAN);
eventBroker.subscribe(this, TOPIC_FLIGHT);
eventBroker.subscribe(this, TOPIC_FMM);
eventBroker.subscribe(this, TOPIC_FSR);
eventBroker.subscribe(this, TOPIC_NAS);
eventBroker.subscribe(this, TOPIC_TMTC);
eventBroker.subscribe(this, TOPIC_MOTOR);
eventBroker.subscribe(this, TOPIC_TARS);
eventBroker.subscribe(this, TOPIC_ALT);
}
void HILFlightPhasesManager::setCurrentPositionSource(
std::function<Boardcore::TimedTrajectoryPoint()> getCurrentPosition)
{
this->getCurrentPosition = getCurrentPosition;
}
bool HILFlightPhasesManager::isFlagActive(FlightPhases flag)
{
return flagsFlightPhases[flag];
}
void HILFlightPhasesManager::registerToFlightPhase(FlightPhases flag,
TCallback func)
{
callbacks[flag].push_back(func);
}
void HILFlightPhasesManager::setFlagFlightPhase(FlightPhases flag,
bool isEnable)
{
flagsFlightPhases[flag] = isEnable;
}
void HILFlightPhasesManager::processFlags(FlightPhasesFlags hil_flags)
{
updateSimulatorFlags(hil_flags);
std::vector<FlightPhases> changed_flags;
// set true when the first packet from the simulator arrives
if (isSetTrue(FlightPhases::SIMULATION_STARTED))
{
t_start = Boardcore::TimestampTimer::getTimestamp();
TRACE("[HIL] ------- SIMULATION STARTED ! ------- \n");
changed_flags.push_back(FlightPhases::SIMULATION_STARTED);
}
if (flagsFlightPhases[FlightPhases::SIM_FLYING])
{
if (isSetTrue(FlightPhases::SIM_FLYING))
{
registerOutcomes(FlightPhases::SIM_FLYING);
TRACE("[HIL] ------- SIMULATOR LIFTOFF ! ------- \n");
changed_flags.push_back(FlightPhases::SIM_FLYING);
}
if (isSetFalse(FlightPhases::SIM_BURNING))
{
registerOutcomes(FlightPhases::SIM_BURNING);
TRACE("[HIL] ------- STOPPED BURNING ! ------- \n");
changed_flags.push_back(FlightPhases::SIM_BURNING);
}
if (isSetTrue(FlightPhases::SIM_AEROBRAKES))
{
registerOutcomes(FlightPhases::SIM_AEROBRAKES);
changed_flags.push_back(FlightPhases::SIM_AEROBRAKES);
}
if (isSetTrue(FlightPhases::SIM_PARA1))
{
registerOutcomes(FlightPhases::SIM_PARA1);
TRACE("[HIL] ------- PARACHUTE 1 ! ------- \n");
changed_flags.push_back(FlightPhases::SIM_PARA1);
}
if (isSetTrue(FlightPhases::SIM_PARA2))
{
registerOutcomes(FlightPhases::SIM_PARA2);
TRACE("[HIL] ------- PARACHUTE 2 ! ------- \n");
changed_flags.push_back(FlightPhases::SIM_PARA2);
}
}
/* calling the callbacks subscribed to the changed flags */
for (unsigned int i = 0; i < changed_flags.size(); i++)
{
std::vector<TCallback> callbacksToCall = callbacks[changed_flags[i]];
for (unsigned int j = 0; j < callbacksToCall.size(); j++)
{
callbacksToCall[j]();
}
}
prev_flagsFlightPhases = flagsFlightPhases;
}
void HILFlightPhasesManager::registerOutcomes(FlightPhases phase)
{
Boardcore::TimedTrajectoryPoint temp = getCurrentPosition();
outcomes[phase] = Outcomes(temp.z, temp.vz);
}
void HILFlightPhasesManager::printOutcomes()
{
printf("OUTCOMES: (times dt from liftoff)\n\n");
printf("Simulation time: %.3f [sec]\n\n",
(double)(t_stop - t_start) / 1000000.0f);
printf("Motor stopped burning (simulation flag): \n");
outcomes[FlightPhases::SIM_BURNING].print(t_liftoff);
printf("Airbrakes exit shadowmode: \n");
outcomes[FlightPhases::AEROBRAKES].print(t_liftoff);
printf("Apogee: \n");
outcomes[FlightPhases::APOGEE].print(t_liftoff);
printf("Parachute 1: \n");
outcomes[FlightPhases::PARA1].print(t_liftoff);
printf("Parachute 2: \n");
outcomes[FlightPhases::PARA2].print(t_liftoff);
printf("Simulation Stopped: \n");
outcomes[FlightPhases::SIMULATION_STOPPED].print(t_liftoff);
// auto cpuMeter = Boardcore::CpuMeter::getCpuStats();
// printf("max cpu usage: %+.3f\n", cpuMeter.maxValue);
// printf("avg cpu usage: %+.3f\n", cpuMeter.mean);
// printf("min free heap: %+.3lu\n", cpuMeter.minFreeHeap);
// printf("max free stack:%+.3lu\n", cpuMeter.minFreeStack);
}
/**
* @brief Updates the flags of the object with the flags sent from matlab
* and checks for the apogee
*/
void HILFlightPhasesManager::updateSimulatorFlags(FlightPhasesFlags hil_flags)
{
flagsFlightPhases[FlightPhases::SIM_ASCENT] = hil_flags.flag_ascent;
flagsFlightPhases[FlightPhases::SIM_FLYING] = hil_flags.flag_flight;
flagsFlightPhases[FlightPhases::SIM_BURNING] = hil_flags.flag_burning;
flagsFlightPhases[FlightPhases::SIM_AEROBRAKES] = hil_flags.flag_airbrakes;
flagsFlightPhases[FlightPhases::SIM_PARA1] = hil_flags.flag_para1;
flagsFlightPhases[FlightPhases::SIM_PARA2] = hil_flags.flag_para2;
flagsFlightPhases[FlightPhases::SIMULATION_STOPPED] =
isSetFalse(FlightPhases::SIM_FLYING) ||
prev_flagsFlightPhases[FlightPhases::SIMULATION_STOPPED];
}
void HILFlightPhasesManager::handleEvent(const Boardcore::Event& e)
{
std::vector<FlightPhases> changed_flags;
switch (e)
{
case FMM_INIT_ERROR:
printf("[HIL] ------- INIT FAILED ! ------- \n");
case FMM_INIT_OK:
setFlagFlightPhase(FlightPhases::CALIBRATION, true);
TRACE("[HIL] ------- CALIBRATION ! ------- \n");
changed_flags.push_back(FlightPhases::CALIBRATION);
break;
case FLIGHT_DISARMED:
setFlagFlightPhase(FlightPhases::CALIBRATION_OK, true);
TRACE("[HIL] CALIBRATION OK!\n");
changed_flags.push_back(FlightPhases::CALIBRATION_OK);
break;
case FLIGHT_ARMED:
setFlagFlightPhase(FlightPhases::ARMED, true);
printf("[HIL] ------- READY TO LAUNCH ! ------- \n");
changed_flags.push_back(FlightPhases::ARMED);
break;
case FLIGHT_LAUNCH_PIN_DETACHED:
setFlagFlightPhase(FlightPhases::LIFTOFF_PIN_DETACHED, true);
TRACE("[HIL] ------- LIFTOFF PIN DETACHED ! ------- \n");
changed_flags.push_back(FlightPhases::LIFTOFF_PIN_DETACHED);
break;
case FLIGHT_LIFTOFF:
case TMTC_FORCE_LAUNCH:
t_liftoff = Boardcore::TimestampTimer::getTimestamp();
printf("[HIL] ------- LIFTOFF -------: %f, %f \n",
getCurrentPosition().z, getCurrentPosition().vz);
changed_flags.push_back(FlightPhases::LIFTOFF);
break;
case ABK_SHADOW_MODE_TIMEOUT:
setFlagFlightPhase(FlightPhases::AEROBRAKES, true);
registerOutcomes(FlightPhases::AEROBRAKES);
TRACE("[HIL] ABK shadow mode timeout\n");
changed_flags.push_back(FlightPhases::AEROBRAKES);
break;
case ADA_SHADOW_MODE_TIMEOUT:
TRACE("[HIL] ADA shadow mode timeout\n");
break;
case ABK_DISABLE:
setFlagFlightPhase(FlightPhases::AEROBRAKES, false);
TRACE("[HIL] ABK disabled\n");
break;
case FLIGHT_APOGEE_DETECTED:
case CAN_APOGEE_DETECTED:
setFlagFlightPhase(FlightPhases::AEROBRAKES, false);
registerOutcomes(FlightPhases::APOGEE);
printf("[HIL] ------- APOGEE DETECTED ! ------- %f, %f \n",
getCurrentPosition().z, getCurrentPosition().vz);
changed_flags.push_back(FlightPhases::APOGEE);
break;
case FLIGHT_DROGUE_DESCENT:
case TMTC_FORCE_EXPULSION:
setFlagFlightPhase(FlightPhases::PARA1, true);
registerOutcomes(FlightPhases::PARA1);
printf("[HIL] ------- PARA1 ! -------%f, %f \n",
getCurrentPosition().z, getCurrentPosition().vz);
changed_flags.push_back(FlightPhases::PARA1);
break;
case FLIGHT_WING_DESCENT:
case FLIGHT_DPL_ALT_DETECTED:
case TMTC_FORCE_DEPLOYMENT:
setFlagFlightPhase(FlightPhases::PARA1, false);
setFlagFlightPhase(FlightPhases::PARA2, true);
registerOutcomes(FlightPhases::PARA2);
printf("[HIL] ------- PARA2 ! ------- %f, %f \n",
getCurrentPosition().z, getCurrentPosition().vz);
changed_flags.push_back(FlightPhases::PARA2);
break;
case FLIGHT_LANDING_DETECTED:
case TMTC_FORCE_LANDING:
t_stop = Boardcore::TimestampTimer::getTimestamp();
setFlagFlightPhase(FlightPhases::PARA2, false);
setFlagFlightPhase(FlightPhases::SIMULATION_STOPPED, true);
changed_flags.push_back(FlightPhases::SIMULATION_STOPPED);
registerOutcomes(FlightPhases::SIMULATION_STOPPED);
TRACE("[HIL] ------- SIMULATION STOPPED ! -------: %f \n\n\n",
(double)t_stop / 1000000.0f);
printOutcomes();
break;
default:
TRACE("%s invalid event\n", getEventString(e).c_str());
}
/* calling the callbacks subscribed to the changed flags */
for (unsigned int i = 0; i < changed_flags.size(); i++)
{
std::vector<TCallback> callbacksToCall = callbacks[changed_flags[i]];
for (unsigned int j = 0; j < callbacksToCall.size(); j++)
{
callbacksToCall[j]();
}
}
prev_flagsFlightPhases = flagsFlightPhases;
}
bool HILFlightPhasesManager::isSetTrue(FlightPhases phase)
{
return flagsFlightPhases[phase] && !prev_flagsFlightPhases[phase];
}
bool HILFlightPhasesManager::isSetFalse(FlightPhases phase)
{
return !flagsFlightPhases[phase] && prev_flagsFlightPhases[phase];
}
/* Copyright (c) 2021-2023 Skyward Experimental Rocketry
* Authors: Luca Conterio, Emilio Corigliano
*
* 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 <HIL/HILTransceiver.h>
#include <algorithms/AirBrakes/TrajectoryPoint.h>
#include <common/Events.h>
#include <drivers/timer/TimestampTimer.h>
#include <events/Event.h>
#include <events/EventHandler.h>
#include <miosix.h>
#include <iostream>
#include <map>
typedef std::function<void()> TCallback;
class HILTransceiver;
enum class FlightPhases
{
// simulator flags
SIM_FLYING,
SIM_ASCENT,
SIM_BURNING,
SIM_AEROBRAKES,
SIM_PARA1,
SIM_PARA2,
// flight flags
SIMULATION_STARTED,
CALIBRATION,
CALIBRATION_OK,
ARMED,
LIFTOFF_PIN_DETACHED,
LIFTOFF,
AEROBRAKES,
APOGEE,
PARA1,
PARA2,
SIMULATION_STOPPED
};
struct Outcomes
{
uint64_t t = 0;
float z = 0;
float vz = 0;
Outcomes() : t(0), z(0), vz(0) {}
Outcomes(float z, float vz)
: t(Boardcore::TimestampTimer::getTimestamp()), z(z), vz(vz)
{
}
void print(uint64_t t_start) const
{
printf("@time : %f [sec]\n", (double)(t - t_start) / 1000000);
printf("@altitude : %f [m]\n", z);
printf("@velocity : %f [m/s]\n\n", vz);
}
};
/**
* @brief Singleton object that manages all the phases of the simulation.
* After his instantiation we need to set the source of the current position in
* order to be able to save the outcomes for each event.
*/
class HILFlightPhasesManager : public Boardcore::EventHandler
{
using FlightPhasesFlags = HILConfig::SimulatorData::Flags;
public:
HILFlightPhasesManager();
void setCurrentPositionSource(
std::function<Boardcore::TimedTrajectoryPoint()> getCurrentPosition);
bool isFlagActive(FlightPhases flag);
void registerToFlightPhase(FlightPhases flag, TCallback func);
void setFlagFlightPhase(FlightPhases flag, bool isEnable);
virtual void processFlags(FlightPhasesFlags hil_flags);
protected:
virtual void handleEvent(const Boardcore::Event& e) override;
virtual void registerOutcomes(FlightPhases phase);
virtual void printOutcomes();
/**
* @brief Updates the flags of the object with the flags sent from matlab
* and checks for the apogee
*/
virtual void updateSimulatorFlags(FlightPhasesFlags hil_flags);
bool isSetTrue(FlightPhases phase);
bool isSetFalse(FlightPhases phase);
uint64_t t_start = 0;
uint64_t t_liftoff = 0;
uint64_t t_stop = 0;
std::map<FlightPhases, bool> flagsFlightPhases;
std::map<FlightPhases, bool> prev_flagsFlightPhases;
std::map<FlightPhases, vector<TCallback>> callbacks;
std::map<FlightPhases, Outcomes> outcomes;
std::function<Boardcore::TimedTrajectoryPoint()> getCurrentPosition;
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 "HIL.h"
#include "drivers/usart/USART.h"
using namespace HILConfig;
/**
* @brief Construct a serial connection attached to a control algorithm
*/
HILTransceiver::HILTransceiver(Boardcore::USART &hilSerial)
: hilSerial(hilSerial), actuatorData(ActuatorData{})
{
}
/**
* @brief sets the actuator data and then wakes up the MatlabTransceiver
* thread in order to send the data back to the simulator (called by the
* control algorithm)
* @param actuatorData sets the data that will be sent to the simulator
*/
void HILTransceiver::setActuatorData(ActuatorData actuatorData)
{
this->actuatorData = actuatorData;
updated = true;
condVar.signal();
}
/**
* @brief returns the reference of the SimulatorData
*
* @return reference to the data simulated by matlab
*/
SimulatorData *HILTransceiver::getSensorData() { return &sensorData; }
/**
* @brief adds to the resetSampleCounter list an object that has to be
* notified when a new packet of data is arrived from the simulator
*
* @param t SimTimestampManagement object
*/
void HILTransceiver::addResetSampleCounter(HILTimestampManagement *t)
{
sensorsTimestamp.push_back(t);
}
/**
* @brief The thread deals with the communication between the simulator and the
* board.
*
* TODO: Check:
* The first read is done in the init() function
*
* After the first time the data is received, the loop of this thread:
* - Reads the simulated data and copies them in the SensorData structure;
* - Notifies every sensor that new data arrived;
* - Waits for the control algorithms to update the actuator data;
* - Sends back the value to the simulator.
*/
void HILTransceiver::run()
{
TRACE("[HILT] Transceiver started\n");
bool lostUpdate = false;
hilSerial.clearQueue();
while (true)
{
// Pausing the kernel in order to copy the data in the shared structure
{
SimulatorData tempData;
miosix::led3On();
if (!hilSerial.readBlocking(&tempData, sizeof(SimulatorData)))
{
TRACE("Failed Serial read\n");
}
hilSerial.clearQueue();
miosix::led3Off();
miosix::PauseKernelLock kLock;
sensorData = tempData;
if (updated)
{
lostUpdate = true;
updated = false; // We want the last computation
}
}
// If this is the first packet to be received, then update the flight
// phase manager
if (!receivedFirstPacket)
{
receivedFirstPacket = true;
Boardcore::ModuleManager::getInstance()
.get<HIL>()
->flightPhasesManager->setFlagFlightPhase(
FlightPhases::SIMULATION_STARTED, true);
}
// Notify all sensors that a new set of data is arrived
//[REVIEW] Could be moved in HILFlightPhasesManager
for (auto st : sensorsTimestamp)
st->resetSampleCounter();
// Trigger events relative to the flight phases
Boardcore::ModuleManager::getInstance()
.get<HIL>()
->flightPhasesManager->processFlags(sensorData.flags);
if (lostUpdate)
{
// This means also that the number of samples used for the mean sent
// to the HIL simulator is made up of more than the number of
// samples we though
TRACE("[HILT] lost updates!\n");
lostUpdate = false;
}
waitActuatorData();
miosix::led2On();
hilSerial.write(&actuatorData, sizeof(ActuatorData));
miosix::led2Off();
}
}
/**
* @brief Waits for the control algorithms to update actuatorData.
*/
void HILTransceiver::waitActuatorData()
{
miosix::Lock<miosix::FastMutex> l(mutex);
while (!updated)
{
condVar.wait(l);
}
updated = false;
}
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <ActiveObject.h>
#include <HILConfig.h>
#include <HIL_sensors/HILTimestampManagement.h>
#include <drivers/timer/TimestampTimer.h>
#include <drivers/usart/USART.h>
#include <utils/Debug.h>
/**
* @brief HILTransceiver is a Singleton and provides an easy interface for
* the control algorithms to send and receive data during a simulation
*/
class HILTransceiver : public Boardcore::ActiveObject
{
public:
/**
* @brief Construct a serial connection attached to a control algorithm
*/
explicit HILTransceiver(Boardcore::USART &hilSerial);
/**
* @brief sets the actuator data and then wakes up the MatlabTransceiver
* thread in order to send the data back to the simulator (called by the
* control algorithm)
* @param actuatorData sets the data that will be sent to the simulator
*/
void setActuatorData(HILConfig::ActuatorData actuatorData);
/**
* @brief returns the reference of the SimulatorData
*
* @return reference to the data simulated by matlab
*/
HILConfig::SimulatorData *getSensorData();
/**
* @brief adds to the resetSampleCounter list an object that has to be
* notified when a new packet of data is arrived from the simulator
*
* @param t SimTimestampManagement object
*/
void addResetSampleCounter(HILTimestampManagement *t);
private:
/**
* @brief Waits for the control algorithm(s) to update actuatorData.
*/
void waitActuatorData();
void run() override;
Boardcore::USART &hilSerial;
bool receivedFirstPacket = false;
bool updated = false;
HILConfig::SimulatorData sensorData;
HILConfig::ActuatorData actuatorData;
std::vector<HILTimestampManagement *> sensorsTimestamp;
miosix::FastMutex mutex;
miosix::ConditionVariable condVar;
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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
/**
* @brief Configuration file that includes only the right structures described
* in the config file of the test.
*
* Usage:
* #elif <Flag>
* #include "<test-directory>/HILSimulationConfig.h"
*
* REMEMBER:
* when defining the entry in "CMakeLists" you should add
* target_compile_definitions(<test-directory> PRIVATE <Flag>)
*
* WARNING:
* You should always CLEAN your board before flashing a new entrypoint. Some
* flags could still be in memory
*/
/* Hardware in the loop entrypoint */
#if defined(HILTest)
#include "entrypoints/HIL/HILSimulationConfig.h"
/*
#elif defined(HIL_<tuoFlag>)
#include "<test-directory>/HILSimulationConfig.h"
*/
#else
#error You have add the flag of your configuration file for the HIL testing!
#endif
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <actuators/Servo/Servo.h>
#include "HIL.h"
class HILServo : public Boardcore::Servo
{
public:
explicit HILServo(TIM_TypeDef* const timer,
Boardcore::TimerUtils::Channel pwmChannel,
unsigned int minPulse, unsigned int maxPulse,
unsigned int frequency = 50)
: Servo(timer, pwmChannel, minPulse, maxPulse, frequency)
{
}
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include "HILSensor.h"
/**
* @brief fake accelerometer sensor used for the simulation.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
class HILAccelerometer : public HILSensor<HILAccelerometerData>
{
public:
HILAccelerometer(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData)
{
}
protected:
HILAccelerometerData updateData() override
{
HILAccelerometerData tempData;
miosix::PauseKernelLock pkLock;
HILConfig::SimulatorData::Accelerometer *accelerometer =
reinterpret_cast<HILConfig::SimulatorData::Accelerometer *>(
sensorData);
tempData.accelerationX = accelerometer->measures[sampleCounter][0];
tempData.accelerationY = accelerometer->measures[sampleCounter][1];
tempData.accelerationZ = accelerometer->measures[sampleCounter][2];
tempData.accelerationTimestamp = updateTimestamp();
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include "HILSensor.h"
/**
* @brief fake barometer sensor used for the simulation.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
class HILBarometer : public HILSensor<HILBarometerData>
{
public:
HILBarometer(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData)
{
}
protected:
HILBarometerData updateData() override
{
HILBarometerData tempData;
miosix::PauseKernelLock pkLock;
HILConfig::SimulatorData::Barometer *barometer =
reinterpret_cast<HILConfig::SimulatorData::Barometer *>(sensorData);
tempData.pressure = barometer->measures[sampleCounter];
tempData.pressureTimestamp = updateTimestamp();
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include <cmath>
#include "HILSensor.h"
/**
* @brief fake gps sensor used for the HILulation.
*
* This class is used to HILulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a HILulator.
*/
class HILGps : public HILSensor<HILGpsData>
{
public:
HILGps(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData)
{
}
protected:
HILGpsData updateData() override
{
HILGpsData tempData;
miosix::PauseKernelLock pkLock;
HILConfig::SimulatorData::Gps *gps =
reinterpret_cast<HILConfig::SimulatorData::Gps *>(sensorData);
tempData.latitude =
gps->positionMeasures[sampleCounter][0]; // divide by earth radius
tempData.longitude = gps->positionMeasures[sampleCounter][1];
tempData.height = gps->positionMeasures[sampleCounter][2];
tempData.velocityNorth = gps->velocityMeasures[sampleCounter][0];
tempData.velocityEast = gps->velocityMeasures[sampleCounter][1];
tempData.velocityDown = gps->velocityMeasures[sampleCounter][2];
tempData.speed = sqrtf(tempData.velocityNorth * tempData.velocityNorth +
tempData.velocityDown * tempData.velocityDown);
tempData.positionDOP = 0;
tempData.fix = static_cast<uint8_t>(gps->fix);
tempData.satellites = static_cast<uint8_t>(gps->num_satellites);
tempData.gpsTimestamp = updateTimestamp();
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include "HILSensor.h"
/**
* @brief fake gyroscope sensor used for the simulation.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
class HILGyroscope : public HILSensor<HILGyroscopeData>
{
public:
HILGyroscope(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData)
{
}
protected:
HILGyroscopeData updateData() override
{
HILGyroscopeData tempData;
miosix::PauseKernelLock pkLock;
HILConfig::SimulatorData::Gyro *gyroscope =
reinterpret_cast<HILConfig::SimulatorData::Gyro *>(sensorData);
tempData.angularSpeedX = gyroscope->measures[sampleCounter][0];
tempData.angularSpeedY = gyroscope->measures[sampleCounter][1];
tempData.angularSpeedZ = gyroscope->measures[sampleCounter][2];
tempData.angularSpeedTimestamp = updateTimestamp();
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include "HILSensor.h"
/**
* @brief fake magnetometer sensor used for the simulation.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
class HILMagnetometer : public HILSensor<HILMagnetometerData>
{
public:
HILMagnetometer(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData)
{
}
protected:
HILMagnetometerData updateData() override
{
HILMagnetometerData tempData;
miosix::PauseKernelLock pkLock;
HILConfig::SimulatorData::Magnetometer *magnetometer =
reinterpret_cast<HILConfig::SimulatorData::Magnetometer *>(
sensorData);
tempData.magneticFieldX = magnetometer->measures[sampleCounter][0];
tempData.magneticFieldY = magnetometer->measures[sampleCounter][1];
tempData.magneticFieldZ = magnetometer->measures[sampleCounter][2];
tempData.magneticFieldTimestamp = updateTimestamp();
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
};
/* Copyright (c) 2022-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <logger/Logger.h>
#include <sensors/analog/Pitot/Pitot.h>
#include <utils/AeroUtils/AeroUtils.h>
#include "HILSensor.h"
/**
* @brief fake pitot (differential pressure) sensor used for the simulation.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
class HILPitot : public HILSensor<HILPitotData>
{
public:
HILPitot(int n_data_sensor, void *sensorData)
: HILSensor(n_data_sensor, sensorData),
pitot([&]() { return this->getDeltaP().pressure; },
[&]() { return this->getStaticPressure(); })
{
}
Boardcore::PressureData getDeltaP() { return deltaP; }
float getStaticPressure() { return staticPressure; }
protected:
HILPitotData updateData() override
{
miosix::PauseKernelLock pkLock;
deltaP = Boardcore::PressureData{
Boardcore::TimestampTimer::getTimestamp(),
reinterpret_cast<HILConfig::SimulatorData::Pitot *>(sensorData)
->deltaP[sampleCounter]};
staticPressure =
reinterpret_cast<HILConfig::SimulatorData::Pitot *>(sensorData)
->staticPressure[sampleCounter];
pitot.sample();
HILPitotData tempData;
tempData.timestamp = updateTimestamp();
tempData.deltaP = pitot.getLastSample().deltaP;
tempData.airspeed = pitot.getLastSample().airspeed;
Boardcore::Logger::getInstance().log(tempData);
return tempData;
}
Boardcore::PressureData deltaP;
float staticPressure;
Boardcore::Pitot pitot;
};
/* Copyright (c) 2020-2023 Skyward Experimental Rocketry
* Author: Emilio Corigliano
*
* 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 <typeinfo>
#include "HIL.h"
#include "HILConfig.h"
#include "HILSensorsData.h"
#include "HILTimestampManagement.h"
#include "drivers/timer/TimestampTimer.h"
#include "sensors/Sensor.h"
#include "sensors/SensorData.h"
/**
* @brief Fake sensor base used for the simulation. Every sensor for the
* simulation should extend this class.
*
* This class is used to simulate as near as possible the situation of the
* OBSW during the flight, using fake sensors classes instead of the real
* ones, taking their data from the data received from a simulator.
*/
template <typename HILSensorData>
class HILSensor : public virtual HILTimestampManagement,
public virtual Boardcore::Sensor<HILSensorData>
{
public:
/**
* @brief constructor of the fake sensor used for the simulation.
*
* @param matlab reference of the MatlabTransceiver object that deals with
* the simulator
* @param n_data_sensor number of samples in every period of simulation
*/
HILSensor(int n_data_sensor, void *sensorData)
{
this->sensorData = sensorData;
this->n_data_sensor = n_data_sensor;
/* Registers the sensor on the MatlabTransceiver to be notified when a
* new packet of simulated data arrives */
Boardcore::ModuleManager::getInstance()
.get<HIL>()
->simulator->addResetSampleCounter(this);
}
/**
* @brief sets the sample counter to 0.
*
* Updates the reference timestamp, resets the sampleCounter and clears the
* lastError variable. Called by the HILTransceiver when receives a new
* simulated period.
*/
void resetSampleCounter() override
{
this->lastError = Boardcore::SensorErrors::NO_ERRORS;
sampleCounter = 0;
}
/**
* @brief Initializes the fake sensor.
*/
bool init() override
{
if (initialized)
{
this->lastError = Boardcore::SensorErrors::ALREADY_INIT;
TRACE("ALREADY INITIALIZED!");
}
else
{
initialized = true;
}
return initialized;
}
bool selfTest() override { return true; }
protected:
/**
* @brief Updates the internal structure of the fake sensor from the
* structure received from the simulator.
*
* Takes the next unread sample available, continues sending the last sample
* with the old timestamp if we already read all the samples.
*/
HILSensorData sampleImpl() override
{
if (initialized)
{
/* updates the last_sensor only if there is still data to be read */
if (sampleCounter >= n_data_sensor)
{
this->lastError = Boardcore::SensorErrors::NO_NEW_DATA;
/*TRACE("[%s] NO NEW DATA! Simulation error\n",
typeid(this).name());*/
}
else if (this->lastError != Boardcore::SensorErrors::NO_NEW_DATA)
{
return updateData();
}
}
else
{
this->lastError = Boardcore::SensorErrors::NOT_INIT;
TRACE(
"[HILSensor] sampleImpl() : not initialized, unable to "
"sample data \n");
}
return this->lastSample;
}
/**
* @brief updates the timestamp and increments the sampleCounter.
* WARNING: You should call this method after all the values has been
* updated, it modifies the sampleCounter!
* @return the timestamp of the sample
*/
uint64_t updateTimestamp()
{
sampleCounter++;
return Boardcore::TimestampTimer::getTimestamp();
}
/**
* @brief Function that updates the sensor structure with new data.
*
* Sensor struct updated from MatlabTransceiver::sensorData.
* WARNING: This method should call **AT THE END** the updateTimestamp
* method.
*/
virtual HILSensorData updateData() = 0;
bool initialized = false;
int sampleCounter = 0; /**< counter of the next sample to take */
int n_data_sensor; /**< number of samples in every period */
void *sensorData; /**< reference to the Buffer structure */
};
/* Copyright (c) 2021-2023 Skyward Experimental Rocketry
* Author: Luca Conterio
*
* 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 <sensors/SensorData.h>
#include <sensors/analog/Pitot/PitotData.h>
struct HILAccelerometerData : public Boardcore::AccelerometerData
{
static std::string header()
{
return "timestamp,accelerationX,accelerationY,accelerationZ\n";
}
void print(std::ostream& os) const
{
os << accelerationTimestamp << "," << accelerationX << ","
<< accelerationY << "," << accelerationZ << "\n";
}
};
struct HILGyroscopeData : public Boardcore::GyroscopeData
{
static std::string header()
{
return "timestamp,angularSpeedX,angularSpeedY,angularSpeedZ\n";
}
void print(std::ostream& os) const
{
os << angularSpeedTimestamp << "," << angularSpeedX << ","
<< angularSpeedY << "," << angularSpeedZ << "\n";
}
};
struct HILMagnetometerData : public Boardcore::MagnetometerData
{
static std::string header()
{
return "timestamp,magneticFieldX,magneticFieldY,magneticFieldZ\n";
}
void print(std::ostream& os) const
{
os << magneticFieldTimestamp << "," << magneticFieldX << ","
<< magneticFieldY << "," << magneticFieldZ << "\n";
}
};
struct HILImuData : public HILAccelerometerData,
public HILGyroscopeData,
public HILMagnetometerData
{
static std::string header()
{
return "accelerationTimestamp,accelerationX,accelerationY,"
"accelerationZ,angularSpeedTimestamp,angularSpeedX,"
"angularSpeedY,angularSpeedZ,magneticFieldTimestamp,"
"magneticFieldX,magneticFieldY,magneticFieldZ\n";
}
void print(std::ostream& os) const
{
os << accelerationTimestamp << "," << accelerationX << ","
<< accelerationY << "," << accelerationZ << ","
<< angularSpeedTimestamp << "," << angularSpeedX << ","
<< angularSpeedY << "," << angularSpeedZ << ","
<< magneticFieldTimestamp << "," << magneticFieldX << ","
<< magneticFieldY << "," << magneticFieldZ << "\n";
}
};
struct HILGpsData : public Boardcore::GPSData
{
static std::string header()
{
return "timestamp,latitude,longitude,height,velocityNorth,velocityEast,"
"velocityDown,speed,track,positionDOP,satellites,fix\n";
}
void print(std::ostream& os) const
{
os << gpsTimestamp << "," << longitude << "," << latitude << ","
<< height << "," << velocityNorth << "," << velocityEast << ","
<< velocityDown << "," << speed << "," << track << "," << positionDOP
<< "," << (int)satellites << "," << (int)fix << "\n";
}
};
struct HILBarometerData : public Boardcore::PressureData
{
static std::string header() { return "timestamp,pressure\n"; }
void print(std::ostream& os) const
{
os << pressureTimestamp << "," << pressure << "\n";
}
};
struct HILPitotData : public Boardcore::PitotData
{
static std::string header() { return "timestamp,deltaP,airspeed\n"; }
void print(std::ostream& os) const
{
os << timestamp << "," << deltaP << "," << airspeed << "\n";
}
};
struct HILTempData : public Boardcore::TemperatureData
{
static std::string header() { return "timestamp,temperature\n"; }
void print(std::ostream& os) const
{
os << temperatureTimestamp << "," << temperature << "\n";
}
};
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment