v1.9.0 #175
@ -86,7 +86,6 @@ include (${CMAKE_SCRIPT_PATH}/HardwareOsPreConfig.cmake)
|
|||||||
pre_source_hw_os_config()
|
pre_source_hw_os_config()
|
||||||
|
|
||||||
if(TGT_BSP)
|
if(TGT_BSP)
|
||||||
message(STATUS ${TGT_BSP})
|
|
||||||
if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/raspberrypi"
|
if(TGT_BSP MATCHES "arm/q7s" OR TGT_BSP MATCHES "arm/raspberrypi"
|
||||||
OR TGT_BSP MATCHES "arm/beagleboneblack"
|
OR TGT_BSP MATCHES "arm/beagleboneblack"
|
||||||
)
|
)
|
||||||
|
@ -14,7 +14,8 @@
|
|||||||
#include "mission/core/GenericFactory.h"
|
#include "mission/core/GenericFactory.h"
|
||||||
#include "mission/utility/TmFunnel.h"
|
#include "mission/utility/TmFunnel.h"
|
||||||
#include <mission/devices/GPSHyperionHandler.h>
|
#include <mission/devices/GPSHyperionHandler.h>
|
||||||
#include "mission/devices/MGMHandlerLIS3MDL.h"
|
#include <mission/devices/MgmLIS3MDLHandler.h>
|
||||||
|
|
||||||
#include "mission/devices/MGMHandlerRM3100.h"
|
#include "mission/devices/MGMHandlerRM3100.h"
|
||||||
#include "mission/devices/GyroADIS16507Handler.h"
|
#include "mission/devices/GyroADIS16507Handler.h"
|
||||||
|
|
||||||
|
@ -19,18 +19,18 @@ static constexpr char UART_GNSS_1_DEV[] = "/dev/ttyUL2";
|
|||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
/** OBC1E */
|
/** OBC1E */
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
static constexpr char GPIO_MULTIPURPOSE_1V8_OBC1D[] = "gpiochip4";
|
static constexpr char GPIO_MULTIPURPOSE_1V8_OBC1D[] = "/amba_pl/gpio@42020000";
|
||||||
static const char* const GPIO_GYRO_ADIS_CHIP = GPIO_MULTIPURPOSE_1V8_OBC1D;
|
static const char* const GPIO_GYRO_ADIS_LABEL = GPIO_MULTIPURPOSE_1V8_OBC1D;
|
||||||
static constexpr uint32_t GPIO_GYRO_0_ADIS_CS = 0; // Package Pin: W20
|
static constexpr uint32_t GPIO_GYRO_0_ADIS_CS = 0; // Package Pin: W20
|
||||||
static constexpr uint32_t GPIO_GYRO_2_ADIS_CS = 2; // AA22
|
static constexpr uint32_t GPIO_GYRO_2_ADIS_CS = 2; // AA22
|
||||||
|
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
/** OBC1F B0 */
|
/** OBC1F B0 */
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
static constexpr char GPIO_FLEX_OBC1F_B0[] = "gpiochip5";
|
static constexpr char GPIO_FLEX_OBC1F_B0[] = "/amba_pl/gpio@42030000";
|
||||||
static const char* const GPIO_ACS_BOARD_DEFAULT_CHIP = GPIO_FLEX_OBC1F_B0;
|
static const char* const GPIO_ACS_BOARD_DEFAULT_LABEL = GPIO_FLEX_OBC1F_B0;
|
||||||
static const char* const GPIO_RW_DEFAULT_CHIP = GPIO_FLEX_OBC1F_B0;
|
static const char* const GPIO_RW_DEFAULT_LABEL = GPIO_FLEX_OBC1F_B0;
|
||||||
static const char* const GPIO_RAD_SENSOR_CHIP = GPIO_FLEX_OBC1F_B0;
|
static const char* const GPIO_RAD_SENSOR_LABEL = GPIO_FLEX_OBC1F_B0;
|
||||||
|
|
||||||
static constexpr uint32_t GPIO_RW_0_CS = 7; // B20
|
static constexpr uint32_t GPIO_RW_0_CS = 7; // B20
|
||||||
static constexpr uint32_t GPIO_RW_1_CS = 3; // G22
|
static constexpr uint32_t GPIO_RW_1_CS = 3; // G22
|
||||||
@ -40,7 +40,6 @@ static constexpr uint32_t GPIO_RW_3_CS = 6; // B19
|
|||||||
static constexpr uint32_t GPIO_GYRO_1_L3G_CS = 18; // N22
|
static constexpr uint32_t GPIO_GYRO_1_L3G_CS = 18; // N22
|
||||||
static constexpr uint32_t GPIO_GYRO_3_L3G_CS = 1; // M21
|
static constexpr uint32_t GPIO_GYRO_3_L3G_CS = 1; // M21
|
||||||
static constexpr uint32_t GPIO_MGM_0_LIS3_CS = 5; // C18
|
static constexpr uint32_t GPIO_MGM_0_LIS3_CS = 5; // C18
|
||||||
// MGM_2 is part of gpiochip6
|
|
||||||
static constexpr uint32_t GPIO_MGM_1_RM3100_CS = 16; // A16
|
static constexpr uint32_t GPIO_MGM_1_RM3100_CS = 16; // A16
|
||||||
static constexpr uint32_t GPIO_MGM_3_RM3100_CS = 10; // C17
|
static constexpr uint32_t GPIO_MGM_3_RM3100_CS = 10; // C17
|
||||||
|
|
||||||
@ -56,16 +55,16 @@ static constexpr uint32_t GPIO_RAD_SENSOR_CS = 19; // R18
|
|||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
/** OBC1F B1 */
|
/** OBC1F B1 */
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
static constexpr char GPIO_FLEX_OBC1F_B1[] = "gpiochip6";
|
static constexpr char GPIO_FLEX_OBC1F_B1[] = "/amba_pl/gpio@42030000";
|
||||||
static const char* const GPIO_MGM2_LIS3_CHIP = GPIO_FLEX_OBC1F_B1;
|
static const char* const GPIO_MGM2_LIS3_LABEL = GPIO_FLEX_OBC1F_B1;
|
||||||
static constexpr uint32_t GPIO_MGM_2_LIS3_CS = 0; // D18
|
static constexpr uint32_t GPIO_MGM_2_LIS3_CS = 0; // D18
|
||||||
|
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
/** OBC1C */
|
/** OBC1C */
|
||||||
/**************************************************************/
|
/**************************************************************/
|
||||||
static constexpr char GPIO_3V3_OBC1C[] = "gpiochip7";
|
static constexpr char GPIO_3V3_OBC1C[] = "/amba_pl/gpio@42040000";
|
||||||
static const char* const GPIO_HEATER_CHIP = GPIO_3V3_OBC1C;
|
static const char* const GPIO_HEATER_LABEL = GPIO_3V3_OBC1C;
|
||||||
static const char* const GPIO_SOLAR_ARR_DEPL_CHIP = GPIO_3V3_OBC1C;
|
static const char* const GPIO_SOLAR_ARR_DEPL_LABEL = GPIO_3V3_OBC1C;
|
||||||
static constexpr uint32_t GPIO_HEATER_0_PIN = 6;
|
static constexpr uint32_t GPIO_HEATER_0_PIN = 6;
|
||||||
static constexpr uint32_t GPIO_HEATER_1_PIN = 12;
|
static constexpr uint32_t GPIO_HEATER_1_PIN = 12;
|
||||||
static constexpr uint32_t GPIO_HEATER_2_PIN = 7;
|
static constexpr uint32_t GPIO_HEATER_2_PIN = 7;
|
||||||
@ -79,10 +78,18 @@ static constexpr uint32_t GPIO_GYRO_2_ENABLE = 18; // F22
|
|||||||
static constexpr uint32_t GPIO_SOL_DEPL_SA_0_PIN = 4;
|
static constexpr uint32_t GPIO_SOL_DEPL_SA_0_PIN = 4;
|
||||||
static constexpr uint32_t GPIO_SOL_DEPL_SA_1_PIN = 2;
|
static constexpr uint32_t GPIO_SOL_DEPL_SA_1_PIN = 2;
|
||||||
|
|
||||||
static constexpr char GPIO_RW_SPI_MUX_CHIP[] = "gpiochip11";
|
static constexpr char GPIO_RW_SPI_MUX_LABEL[] = "zynq_gpio";
|
||||||
// Uses EMIO interface to PL, starts at 54
|
// Uses EMIO interface to PL, starts at 54
|
||||||
static constexpr uint32_t GPIO_RW_SPI_MUX_CS = 54;
|
static constexpr uint32_t GPIO_RW_SPI_MUX_CS = 54;
|
||||||
|
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_1 = 13;
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_2 = 14;
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_3 = 15;
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_4 = 16;
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_5 = 17;
|
||||||
|
static constexpr uint32_t SPI_MUX_BIT_6 = 9;
|
||||||
|
static constexpr uint32_t EN_RW_CS = 17;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* BSP_Q7S_BOARDCONFIG_BUSCONF_H_ */
|
#endif /* BSP_Q7S_BOARDCONFIG_BUSCONF_H_ */
|
||||||
|
@ -289,13 +289,17 @@ void initmission::createPusTasks(TaskFactory &factory,
|
|||||||
|
|
||||||
void initmission::createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
void initmission::createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
std::vector<PeriodicTaskIF*>& taskVec) {
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
|
#if OBSW_ADD_TEST_TASK == 1 || OBSW_ADD_SPI_TEST_CODE == 1 || (BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1)
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
|
#endif
|
||||||
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
||||||
"TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc);
|
"TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc);
|
||||||
|
#if OBSW_ADD_TEST_TASK == 1
|
||||||
result = testTask->addComponent(objects::TEST_TASK);
|
result = testTask->addComponent(objects::TEST_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
||||||
}
|
}
|
||||||
|
#endif /* OBSW_ADD_TEST_TASK == 1 */
|
||||||
|
|
||||||
#if OBSW_ADD_SPI_TEST_CODE == 1
|
#if OBSW_ADD_SPI_TEST_CODE == 1
|
||||||
result = testTask->addComponent(objects::SPI_TEST);
|
result = testTask->addComponent(objects::SPI_TEST);
|
||||||
|
@ -35,7 +35,6 @@
|
|||||||
#include "mission/devices/GyroADIS16507Handler.h"
|
#include "mission/devices/GyroADIS16507Handler.h"
|
||||||
#include "mission/devices/IMTQHandler.h"
|
#include "mission/devices/IMTQHandler.h"
|
||||||
#include "mission/devices/SyrlinksHkHandler.h"
|
#include "mission/devices/SyrlinksHkHandler.h"
|
||||||
#include "mission/devices/MGMHandlerLIS3MDL.h"
|
|
||||||
#include "mission/devices/PlocMPSoCHandler.h"
|
#include "mission/devices/PlocMPSoCHandler.h"
|
||||||
#include "mission/devices/RadiationSensorHandler.h"
|
#include "mission/devices/RadiationSensorHandler.h"
|
||||||
#include "mission/devices/RwHandler.h"
|
#include "mission/devices/RwHandler.h"
|
||||||
@ -52,6 +51,7 @@
|
|||||||
|
|
||||||
#include "fsfw_hal/linux/uart/UartComIF.h"
|
#include "fsfw_hal/linux/uart/UartComIF.h"
|
||||||
#include "fsfw_hal/linux/uart/UartCookie.h"
|
#include "fsfw_hal/linux/uart/UartCookie.h"
|
||||||
|
#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h"
|
||||||
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
|
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
|
||||||
#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h"
|
#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h"
|
||||||
#include "fsfw_hal/linux/i2c/I2cCookie.h"
|
#include "fsfw_hal/linux/i2c/I2cCookie.h"
|
||||||
@ -111,7 +111,7 @@ void Factory::setStaticFrameworkObjectIds() {
|
|||||||
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::produce(void* args){
|
void ObjectFactory::produce(void* args) {
|
||||||
ObjectFactory::setStatics();
|
ObjectFactory::setStatics();
|
||||||
ObjectFactory::produceGenericObjects();
|
ObjectFactory::produceGenericObjects();
|
||||||
LinuxLibgpioIF* gpioComIF = nullptr;
|
LinuxLibgpioIF* gpioComIF = nullptr;
|
||||||
@ -139,8 +139,8 @@ void ObjectFactory::produce(void* args){
|
|||||||
createRtdComponents();
|
createRtdComponents();
|
||||||
#endif /* Q7S_ADD_RTD_DEVICES == 1 */
|
#endif /* Q7S_ADD_RTD_DEVICES == 1 */
|
||||||
|
|
||||||
I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ,
|
I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE,
|
||||||
IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV);
|
q7s::I2C_DEFAULT_DEV);
|
||||||
new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie);
|
new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie);
|
||||||
createReactionWheelComponents(gpioComIF);
|
createReactionWheelComponents(gpioComIF);
|
||||||
|
|
||||||
@ -197,13 +197,13 @@ void ObjectFactory::produce(void* args){
|
|||||||
auto udpBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR);
|
auto udpBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE);
|
new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE);
|
||||||
sif::info << "Created UDP server for TMTC commanding with listener port " <<
|
sif::info << "Created UDP server for TMTC commanding with listener port " <<
|
||||||
udpBridge->getUdpPort() << std::endl;
|
udpBridge->getUdpPort() << std::endl;
|
||||||
#else
|
#else
|
||||||
auto tmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR);
|
auto tmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
tmtcBridge->setMaxNumberOfPacketsStored(50);
|
tmtcBridge->setMaxNumberOfPacketsStored(50);
|
||||||
auto tcpServer = new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE);
|
auto tcpServer = new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE);
|
||||||
sif::info << "Created TCP server for TMTC commanding with listener port " <<
|
sif::info << "Created TCP server for TMTC commanding with listener port "
|
||||||
tcpServer->getTcpPort() << std::endl;
|
<< tcpServer->getTcpPort() << std::endl;
|
||||||
#endif /* OBSW_USE_TMTC_TCP_BRIDGE == 0 */
|
#endif /* OBSW_USE_TMTC_TCP_BRIDGE == 0 */
|
||||||
|
|
||||||
/* Test Task */
|
/* Test Task */
|
||||||
@ -229,19 +229,17 @@ void ObjectFactory::createTmpComponents() {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Temperature sensors */
|
/* Temperature sensors */
|
||||||
Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler(
|
Tmp1075Handler* tmp1075Handler_1 = new Tmp1075Handler(objects::TMP1075_HANDLER_1,
|
||||||
objects::TMP1075_HANDLER_1, objects::I2C_COM_IF,
|
objects::I2C_COM_IF, i2cCookieTmp1075tcs1);
|
||||||
i2cCookieTmp1075tcs1);
|
|
||||||
(void) tmp1075Handler_1;
|
(void) tmp1075Handler_1;
|
||||||
Tmp1075Handler* tmp1075Handler_2 = new Tmp1075Handler(
|
Tmp1075Handler* tmp1075Handler_2 = new Tmp1075Handler(objects::TMP1075_HANDLER_2,
|
||||||
objects::TMP1075_HANDLER_2, objects::I2C_COM_IF,
|
objects::I2C_COM_IF, i2cCookieTmp1075tcs2);
|
||||||
i2cCookieTmp1075tcs2);
|
|
||||||
(void) tmp1075Handler_2;
|
(void) tmp1075Handler_2;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF **gpioComIF,
|
void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF **gpioComIF, UartComIF** uartComIF,
|
||||||
UartComIF** uartComIF, SpiComIF** spiComIF) {
|
SpiComIF** spiComIF) {
|
||||||
if(gpioComIF == nullptr or uartComIF == nullptr or spiComIF == nullptr) {
|
if (gpioComIF == nullptr or uartComIF == nullptr or spiComIF == nullptr) {
|
||||||
sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer"
|
sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
@ -262,23 +260,19 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF **gpioComIF,
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createPcduComponents() {
|
void ObjectFactory::createPcduComponents() {
|
||||||
CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH,
|
CspCookie* p60DockCspCookie = new CspCookie(P60Dock::MAX_REPLY_LENGTH, addresses::P60DOCK);
|
||||||
addresses::P60DOCK);
|
CspCookie* pdu1CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU1);
|
||||||
CspCookie* pdu1CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH,
|
CspCookie* pdu2CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH, addresses::PDU2);
|
||||||
addresses::PDU1);
|
CspCookie* acuCspCookie = new CspCookie(ACU::MAX_REPLY_LENGTH, addresses::ACU);
|
||||||
CspCookie* pdu2CspCookie = new CspCookie(PDU::MAX_REPLY_LENGTH,
|
|
||||||
addresses::PDU2);
|
|
||||||
CspCookie* acuCspCookie = new CspCookie(ACU::MAX_REPLY_LENGTH,
|
|
||||||
addresses::ACU);
|
|
||||||
/* Device Handler */
|
/* Device Handler */
|
||||||
P60DockHandler* p60dockhandler = new P60DockHandler(objects::P60DOCK_HANDLER,
|
P60DockHandler* p60dockhandler = new P60DockHandler(objects::P60DOCK_HANDLER,
|
||||||
objects::CSP_COM_IF, p60DockCspCookie);
|
objects::CSP_COM_IF, p60DockCspCookie);
|
||||||
PDU1Handler* pdu1handler = new PDU1Handler(objects::PDU1_HANDLER,
|
PDU1Handler* pdu1handler = new PDU1Handler(objects::PDU1_HANDLER, objects::CSP_COM_IF,
|
||||||
objects::CSP_COM_IF, pdu1CspCookie);
|
pdu1CspCookie);
|
||||||
PDU2Handler* pdu2handler = new PDU2Handler(objects::PDU2_HANDLER,
|
PDU2Handler* pdu2handler = new PDU2Handler(objects::PDU2_HANDLER, objects::CSP_COM_IF,
|
||||||
objects::CSP_COM_IF, pdu2CspCookie);
|
pdu2CspCookie);
|
||||||
ACUHandler* acuhandler = new ACUHandler(objects::ACU_HANDLER,
|
ACUHandler* acuhandler = new ACUHandler(objects::ACU_HANDLER, objects::CSP_COM_IF,
|
||||||
objects::CSP_COM_IF, acuCspCookie);
|
acuCspCookie);
|
||||||
new PCDUHandler(objects::PCDU_HANDLER, 50);
|
new PCDUHandler(objects::PCDU_HANDLER, 50);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -293,8 +287,8 @@ void ObjectFactory::createPcduComponents() {
|
|||||||
|
|
||||||
void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) {
|
void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) {
|
||||||
GpioCookie* gpioCookieRadSensor = new GpioCookie;
|
GpioCookie* gpioCookieRadSensor = new GpioCookie;
|
||||||
GpiodRegular* chipSelectRadSensor = new GpiodRegular(q7s::GPIO_RAD_SENSOR_CHIP,
|
GpiodRegular* chipSelectRadSensor = new GpiodRegular("Chip Select Radiation Sensor", gpio::OUT,
|
||||||
q7s::GPIO_RAD_SENSOR_CS, "Chip Select Radiation Sensor", gpio::OUT, 1);
|
1, q7s::GPIO_RAD_SENSOR_LABEL, q7s::GPIO_RAD_SENSOR_CS);
|
||||||
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
|
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
|
||||||
gpioComIF->addGpios(gpioCookieRadSensor);
|
gpioComIF->addGpios(gpioCookieRadSensor);
|
||||||
|
|
||||||
@ -304,8 +298,7 @@ void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) {
|
|||||||
new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor);
|
new RadiationSensorHandler(objects::RAD_SENSOR, objects::SPI_COM_IF, spiCookieRadSensor);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF *gpioComIF,
|
void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF *gpioComIF, SpiComIF* spiComIF) {
|
||||||
SpiComIF* spiComIF) {
|
|
||||||
GpioCookie* gpioCookieSus = new GpioCookie();
|
GpioCookie* gpioCookieSus = new GpioCookie();
|
||||||
GpioCallback* susgpio = nullptr;
|
GpioCallback* susgpio = nullptr;
|
||||||
|
|
||||||
@ -422,46 +415,46 @@ void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF *gpioComIF,
|
|||||||
void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComIF* uartComIF) {
|
void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComIF* uartComIF) {
|
||||||
GpioCookie* gpioCookieAcsBoard = new GpioCookie();
|
GpioCookie* gpioCookieAcsBoard = new GpioCookie();
|
||||||
GpiodRegular* gpio = nullptr;
|
GpiodRegular* gpio = nullptr;
|
||||||
gpio = new GpiodRegular(q7s::GPIO_GYRO_ADIS_CHIP, q7s::GPIO_GYRO_0_ADIS_CS,
|
gpio = new GpiodRegular("CS_GYRO_0_ADIS", gpio::OUT, gpio::HIGH, q7s::GPIO_GYRO_ADIS_LABEL,
|
||||||
"CS_GYRO_0_ADIS", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_GYRO_0_ADIS_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_GYRO_1_L3G_CS,
|
gpio = new GpiodRegular("CS_GYRO_1_L3G", gpio::OUT, gpio::HIGH,
|
||||||
"CS_GYRO_1_L3G", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_GYRO_1_L3G_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_GYRO_ADIS_CHIP, q7s::GPIO_GYRO_2_ADIS_CS,
|
gpio = new GpiodRegular("CS_GYRO_2_ADIS", gpio::OUT, gpio::HIGH, q7s::GPIO_GYRO_ADIS_LABEL,
|
||||||
"CS_GYRO_2_ADIS", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_GYRO_2_ADIS_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_GYRO_3_L3G_CS,
|
gpio = new GpiodRegular("CS_GYRO_3_L3G", gpio::OUT, gpio::HIGH,
|
||||||
"CS_GYRO_3_L3G", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_GYRO_3_L3G_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_MGM_0_LIS3_CS,
|
gpio = new GpiodRegular("CS_MGM_0_LIS3_A", gpio::OUT, gpio::HIGH,
|
||||||
"CS_MGM_0_LIS3_A", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_0_LIS3_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_MGM_1_RM3100_CS,
|
gpio = new GpiodRegular("CS_MGM_1_RM3100_A", gpio::OUT, gpio::HIGH,
|
||||||
"CS_MGM_1_RM3100_A", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_1_RM3100_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_MGM2_LIS3_CHIP, q7s::GPIO_MGM_2_LIS3_CS,
|
gpio = new GpiodRegular("CS_MGM_2_LIS3_B", gpio::OUT, gpio::HIGH, q7s::GPIO_MGM2_LIS3_LABEL,
|
||||||
"CS_MGM_2_LIS3_B", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_MGM_2_LIS3_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_MGM_3_RM3100_CS,
|
gpio = new GpiodRegular("CS_MGM_3_RM3100_B", gpio::OUT, gpio::HIGH,
|
||||||
"CS_MGM_3_RM3100_B", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_MGM_3_RM3100_CS);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
||||||
|
|
||||||
// GNSS reset pins are active low
|
// GNSS reset pins are active low
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_RESET_GNSS_0,
|
gpio = new GpiodRegular("GNSS_0_NRESET", gpio::OUT, gpio::HIGH,
|
||||||
"GNSS_0_NRESET", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_RESET_GNSS_0);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, q7s::GPIO_RESET_GNSS_1,
|
gpio = new GpiodRegular("GNSS_1_NRESET", gpio::OUT, gpio::HIGH,
|
||||||
"GNSS_1_NRESET", gpio::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, q7s::GPIO_RESET_GNSS_1);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio);
|
||||||
|
|
||||||
// Enable pins must be pulled low for regular operations
|
// Enable pins must be pulled low for regular operations
|
||||||
gpio = new GpiodRegular(q7s::GPIO_FLEX_OBC1F_B0, q7s::GPIO_GYRO_0_ENABLE,
|
gpio = new GpiodRegular("GYRO_0_ENABLE", gpio::OUT, gpio::LOW, q7s::GPIO_FLEX_OBC1F_B0,
|
||||||
"GYRO_0_ENABLE", gpio::OUT, gpio::LOW);
|
q7s::GPIO_GYRO_0_ENABLE);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_3V3_OBC1C, q7s::GPIO_GYRO_2_ENABLE,
|
gpio = new GpiodRegular("GYRO_2_ENABLE", gpio::OUT, gpio::LOW, q7s::GPIO_3V3_OBC1C,
|
||||||
"GYRO_2_ENABLE", gpio::OUT, gpio::LOW);
|
q7s::GPIO_GYRO_2_ENABLE);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
|
||||||
|
|
||||||
// TODO: Add enable pins for GPS as soon as new interface board design is finished
|
// TODO: Add enable pins for GPS as soon as new interface board design is finished
|
||||||
@ -470,58 +463,78 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComI
|
|||||||
std::string spiDev = q7s::SPI_DEFAULT_DEV;
|
std::string spiDev = q7s::SPI_DEFAULT_DEV;
|
||||||
SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev,
|
SpiCookie* spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev,
|
||||||
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
||||||
auto mgmLis3Handler = new MGMHandlerLIS3MDL(objects::MGM_0_LIS3_HANDLER,
|
auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie);
|
spiCookie, 0);
|
||||||
mgmLis3Handler->setStartUpImmediately();
|
mgmLis3Handler->setStartUpImmediately();
|
||||||
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
|
mgmLis3Handler->setToGoToNormalMode(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev,
|
||||||
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
||||||
auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER,
|
auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie, pcduSwitches::SwitcherList::ACS_BOARD_SIDE_A);
|
spiCookie, pcduSwitches::SwitcherList::ACS_BOARD_SIDE_A);
|
||||||
mgmRm3100Handler->setStartUpImmediately();
|
mgmRm3100Handler->setStartUpImmediately();
|
||||||
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
|
mgmRm3100Handler->setToGoToNormalMode(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev,
|
||||||
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
||||||
auto mgmLis3Handler2 = new MGMHandlerLIS3MDL(objects::MGM_2_LIS3_HANDLER,
|
auto mgmLis3Handler2 = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie);
|
spiCookie, 0);
|
||||||
mgmLis3Handler2->setStartUpImmediately();
|
mgmLis3Handler2->setStartUpImmediately();
|
||||||
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
|
mgmLis3Handler2->setToGoToNormalMode(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev,
|
||||||
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
||||||
mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER,
|
mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie, pcduSwitches::SwitcherList::ACS_BOARD_SIDE_B);
|
spiCookie, pcduSwitches::SwitcherList::ACS_BOARD_SIDE_B);
|
||||||
mgmRm3100Handler->setStartUpImmediately();
|
mgmRm3100Handler->setStartUpImmediately();
|
||||||
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
|
mgmRm3100Handler->setToGoToNormalMode(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
// Commented until ACS board V2 in in clean room again
|
// Commented until ACS board V2 in in clean room again
|
||||||
// Gyro 0 Side A
|
// Gyro 0 Side A
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
||||||
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE,
|
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE,
|
||||||
spi::DEFAULT_ADIS16507_SPEED);
|
spi::DEFAULT_ADIS16507_SPEED);
|
||||||
auto adisHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER,
|
auto adisHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie);
|
spiCookie);
|
||||||
adisHandler->setStartUpImmediately();
|
adisHandler->setStartUpImmediately();
|
||||||
// Gyro 1 Side A
|
// Gyro 1 Side A
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev,
|
||||||
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER,
|
auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
spiCookie, 0);
|
||||||
gyroL3gHandler->setStartUpImmediately();
|
gyroL3gHandler->setStartUpImmediately();
|
||||||
//gyroL3gHandler->setGoNormalModeAtStartup();
|
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
||||||
|
gyroL3gHandler->setGoNormalModeAtStartup();
|
||||||
|
#endif
|
||||||
// Gyro 2 Side B
|
// Gyro 2 Side B
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev,
|
||||||
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE,
|
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE,
|
||||||
spi::DEFAULT_ADIS16507_SPEED);
|
spi::DEFAULT_ADIS16507_SPEED);
|
||||||
adisHandler = new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER,
|
adisHandler = new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie);
|
spiCookie);
|
||||||
adisHandler->setStartUpImmediately();
|
adisHandler->setStartUpImmediately();
|
||||||
// Gyro 3 Side B
|
// Gyro 3 Side B
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev,
|
||||||
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER,
|
gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
spiCookie, 0);
|
||||||
gyroL3gHandler->setStartUpImmediately();
|
gyroL3gHandler->setStartUpImmediately();
|
||||||
//gyroL3gHandler->setGoNormalModeAtStartup();
|
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
||||||
|
gyroL3gHandler->setGoNormalModeAtStartup();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool debugGps = false;
|
||||||
|
#if OBSW_DEBUG_GPS == 1
|
||||||
|
debugGps = true;
|
||||||
|
#endif
|
||||||
resetArgsGnss1.gnss1 = true;
|
resetArgsGnss1.gnss1 = true;
|
||||||
resetArgsGnss1.gpioComIF = gpioComIF;
|
resetArgsGnss1.gpioComIF = gpioComIF;
|
||||||
resetArgsGnss1.waitPeriodMs = 100;
|
resetArgsGnss1.waitPeriodMs = 100;
|
||||||
@ -537,11 +550,11 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComI
|
|||||||
uartCookieGps1->setToFlushInput(true);
|
uartCookieGps1->setToFlushInput(true);
|
||||||
uartCookieGps1->setReadCycles(6);
|
uartCookieGps1->setReadCycles(6);
|
||||||
auto gpsHandler0 = new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF,
|
auto gpsHandler0 = new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF,
|
||||||
uartCookieGps0, true);
|
uartCookieGps0, debugGps);
|
||||||
gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0);
|
gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0);
|
||||||
gpsHandler0->setStartUpImmediately();
|
gpsHandler0->setStartUpImmediately();
|
||||||
auto gpsHandler1 = new GPSHyperionHandler(objects::GPS1_HANDLER, objects::UART_COM_IF,
|
auto gpsHandler1 = new GPSHyperionHandler(objects::GPS1_HANDLER, objects::UART_COM_IF,
|
||||||
uartCookieGps1, true);
|
uartCookieGps1, debugGps);
|
||||||
gpsHandler1->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss1);
|
gpsHandler1->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss1);
|
||||||
gpsHandler1->setStartUpImmediately();
|
gpsHandler1->setStartUpImmediately();
|
||||||
}
|
}
|
||||||
@ -551,38 +564,37 @@ void ObjectFactory::createHeaterComponents() {
|
|||||||
GpioCookie* heaterGpiosCookie = new GpioCookie;
|
GpioCookie* heaterGpiosCookie = new GpioCookie;
|
||||||
|
|
||||||
/* Pin H2-11 on stack connector */
|
/* Pin H2-11 on stack connector */
|
||||||
GpiodRegular* gpioConfigHeater0 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater0 = new GpiodRegular("Heater0", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_0_PIN, "Heater0", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_0_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpioConfigHeater0);
|
||||||
|
|
||||||
/* Pin H2-12 on stack connector */
|
/* Pin H2-12 on stack connector */
|
||||||
GpiodRegular* gpioConfigHeater1 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater1 = new GpiodRegular("Heater1", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_1_PIN, "Heater1", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_1_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpioConfigHeater1);
|
||||||
|
|
||||||
/* Pin H2-13 on stack connector */
|
/* Pin H2-13 on stack connector */
|
||||||
GpiodRegular* gpioConfigHeater2 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater2 = new GpiodRegular("Heater2", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_2_PIN, "Heater2", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_2_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpioConfigHeater2);
|
||||||
|
|
||||||
GpiodRegular* gpioConfigHeater3 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater3 = new GpiodRegular("Heater3", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_3_PIN, "Heater3", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_3_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpioConfigHeater3);
|
||||||
|
|
||||||
GpiodRegular* gpioConfigHeater4 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater4 = new GpiodRegular("Heater4", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_4_PIN, "Heater4", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_4_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpioConfigHeater4);
|
||||||
|
|
||||||
GpiodRegular* gpioConfigHeater5 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater5 = new GpiodRegular("Heater5", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_5_PIN, "Heater5", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_5_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpioConfigHeater5);
|
||||||
|
|
||||||
GpiodRegular* gpioConfigHeater6 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater6 = new GpiodRegular("Heater6", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_6_PIN, "Heater6", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_6_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpioConfigHeater6);
|
||||||
|
|
||||||
GpiodRegular* gpioConfigHeater7 = new GpiodRegular(q7s::GPIO_HEATER_CHIP,
|
GpiodRegular* gpioConfigHeater7 = new GpiodRegular("Heater7", gpio::OUT, 0,
|
||||||
q7s::GPIO_HEATER_7_PIN, "Heater7", gpio::OUT, 0);
|
q7s::GPIO_HEATER_LABEL, q7s::GPIO_HEATER_7_PIN);
|
||||||
heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7);
|
heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpioConfigHeater7);
|
||||||
|
|
||||||
new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie,
|
new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie,
|
||||||
@ -592,11 +604,11 @@ void ObjectFactory::createHeaterComponents() {
|
|||||||
void ObjectFactory::createSolarArrayDeploymentComponents() {
|
void ObjectFactory::createSolarArrayDeploymentComponents() {
|
||||||
GpioCookie* solarArrayDeplCookie = new GpioCookie;
|
GpioCookie* solarArrayDeplCookie = new GpioCookie;
|
||||||
|
|
||||||
GpiodRegular* gpioConfigDeplSA0 = new GpiodRegular(q7s::GPIO_SOLAR_ARR_DEPL_CHIP,
|
GpiodRegular* gpioConfigDeplSA0 = new GpiodRegular("DeplSA0", gpio::OUT, 0,
|
||||||
q7s::GPIO_SOL_DEPL_SA_0_PIN, "DeplSA0", gpio::OUT, 0);
|
q7s::GPIO_SOLAR_ARR_DEPL_LABEL, q7s::GPIO_SOL_DEPL_SA_0_PIN);
|
||||||
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0);
|
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpioConfigDeplSA0);
|
||||||
GpiodRegular* gpioConfigDeplSA1 = new GpiodRegular(q7s::GPIO_SOLAR_ARR_DEPL_CHIP,
|
GpiodRegular* gpioConfigDeplSA1 = new GpiodRegular("DeplSA1", gpio::OUT, 0,
|
||||||
q7s::GPIO_SOL_DEPL_SA_1_PIN, "DeplSA1", gpio::OUT, 0);
|
q7s::GPIO_SOLAR_ARR_DEPL_LABEL, q7s::GPIO_SOL_DEPL_SA_1_PIN);
|
||||||
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1);
|
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpioConfigDeplSA1);
|
||||||
|
|
||||||
//TODO: Find out burn time. For now set to 1000 ms.
|
//TODO: Find out burn time. For now set to 1000 ms.
|
||||||
@ -668,69 +680,62 @@ void ObjectFactory::createRtdComponents(LinuxLibgpioIF *gpioComIF) {
|
|||||||
|
|
||||||
gpioComIF->addGpios(rtdGpioCookie);
|
gpioComIF->addGpios(rtdGpioCookie);
|
||||||
|
|
||||||
SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3,
|
SpiCookie* spiRtdIc3 = new SpiCookie(addresses::RTD_IC3, gpioIds::RTD_IC3, q7s::SPI_DEFAULT_DEV,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4, q7s::SPI_DEFAULT_DEV,
|
||||||
SpiCookie* spiRtdIc4 = new SpiCookie(addresses::RTD_IC4, gpioIds::RTD_IC4,
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
SpiCookie* spiRtdIc5 = new SpiCookie(addresses::RTD_IC5, gpioIds::RTD_IC5, q7s::SPI_DEFAULT_DEV,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc5 = new SpiCookie(addresses::RTD_IC5, gpioIds::RTD_IC5,
|
SpiCookie* spiRtdIc6 = new SpiCookie(addresses::RTD_IC6, gpioIds::RTD_IC6, q7s::SPI_DEFAULT_DEV,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
SpiCookie* spiRtdIc7 = new SpiCookie(addresses::RTD_IC7, gpioIds::RTD_IC7, q7s::SPI_DEFAULT_DEV,
|
||||||
SpiCookie* spiRtdIc6 = new SpiCookie(addresses::RTD_IC6, gpioIds::RTD_IC6,
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
SpiCookie* spiRtdIc8 = new SpiCookie(addresses::RTD_IC8, gpioIds::RTD_IC8, q7s::SPI_DEFAULT_DEV,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc7 = new SpiCookie(addresses::RTD_IC7, gpioIds::RTD_IC7,
|
SpiCookie* spiRtdIc9 = new SpiCookie(addresses::RTD_IC9, gpioIds::RTD_IC9, q7s::SPI_DEFAULT_DEV,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
|
||||||
SpiCookie* spiRtdIc8 = new SpiCookie(addresses::RTD_IC8, gpioIds::RTD_IC8,
|
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
|
||||||
SpiCookie* spiRtdIc9 = new SpiCookie(addresses::RTD_IC9, gpioIds::RTD_IC9,
|
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
|
||||||
SpiCookie* spiRtdIc10 = new SpiCookie(addresses::RTD_IC10, gpioIds::RTD_IC10,
|
SpiCookie* spiRtdIc10 = new SpiCookie(addresses::RTD_IC10, gpioIds::RTD_IC10,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc11 = new SpiCookie(addresses::RTD_IC11, gpioIds::RTD_IC11,
|
SpiCookie* spiRtdIc11 = new SpiCookie(addresses::RTD_IC11, gpioIds::RTD_IC11,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc12 = new SpiCookie(addresses::RTD_IC12, gpioIds::RTD_IC12,
|
SpiCookie* spiRtdIc12 = new SpiCookie(addresses::RTD_IC12, gpioIds::RTD_IC12,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc13 = new SpiCookie(addresses::RTD_IC13, gpioIds::RTD_IC13,
|
SpiCookie* spiRtdIc13 = new SpiCookie(addresses::RTD_IC13, gpioIds::RTD_IC13,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc14 = new SpiCookie(addresses::RTD_IC14, gpioIds::RTD_IC14,
|
SpiCookie* spiRtdIc14 = new SpiCookie(addresses::RTD_IC14, gpioIds::RTD_IC14,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc15 = new SpiCookie(addresses::RTD_IC15, gpioIds::RTD_IC15,
|
SpiCookie* spiRtdIc15 = new SpiCookie(addresses::RTD_IC15, gpioIds::RTD_IC15,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc16 = new SpiCookie(addresses::RTD_IC16, gpioIds::RTD_IC16,
|
SpiCookie* spiRtdIc16 = new SpiCookie(addresses::RTD_IC16, gpioIds::RTD_IC16,
|
||||||
std::string(q7s::SPI_DEFAULT_DEV), Max31865Definitions::MAX_REPLY_SIZE,
|
std::string(q7s::SPI_DEFAULT_DEV), Max31865Definitions::MAX_REPLY_SIZE,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc17 = new SpiCookie(addresses::RTD_IC17, gpioIds::RTD_IC17,
|
SpiCookie* spiRtdIc17 = new SpiCookie(addresses::RTD_IC17, gpioIds::RTD_IC17,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
SpiCookie* spiRtdIc18 = new SpiCookie(addresses::RTD_IC18, gpioIds::RTD_IC18,
|
SpiCookie* spiRtdIc18 = new SpiCookie(addresses::RTD_IC18, gpioIds::RTD_IC18,
|
||||||
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE,
|
q7s::SPI_DEFAULT_DEV, Max31865Definitions::MAX_REPLY_SIZE, spi::SpiModes::MODE_1,
|
||||||
spi::SpiModes::MODE_1, spi::RTD_SPEED);
|
spi::RTD_SPEED);
|
||||||
|
|
||||||
Max31865PT1000Handler* rtdIc3 = new Max31865PT1000Handler(objects::RTD_IC3,
|
Max31865PT1000Handler* rtdIc3 = new Max31865PT1000Handler(objects::RTD_IC3, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc3, 0); // 0 is switchId
|
spiRtdIc3, 0); // 0 is switchId
|
||||||
Max31865PT1000Handler* rtdIc4 = new Max31865PT1000Handler(objects::RTD_IC4,
|
Max31865PT1000Handler* rtdIc4 = new Max31865PT1000Handler(objects::RTD_IC4, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc4, 0);
|
spiRtdIc4, 0);
|
||||||
Max31865PT1000Handler* rtdIc5 = new Max31865PT1000Handler(objects::RTD_IC5,
|
Max31865PT1000Handler* rtdIc5 = new Max31865PT1000Handler(objects::RTD_IC5, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc5, 0);
|
spiRtdIc5, 0);
|
||||||
Max31865PT1000Handler* rtdIc6 = new Max31865PT1000Handler(objects::RTD_IC6,
|
Max31865PT1000Handler* rtdIc6 = new Max31865PT1000Handler(objects::RTD_IC6, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc6, 0);
|
spiRtdIc6, 0);
|
||||||
Max31865PT1000Handler* rtdIc7 = new Max31865PT1000Handler(objects::RTD_IC7,
|
Max31865PT1000Handler* rtdIc7 = new Max31865PT1000Handler(objects::RTD_IC7, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc7, 0);
|
spiRtdIc7, 0);
|
||||||
Max31865PT1000Handler* rtdIc8 = new Max31865PT1000Handler(objects::RTD_IC8,
|
Max31865PT1000Handler* rtdIc8 = new Max31865PT1000Handler(objects::RTD_IC8, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc8, 0);
|
spiRtdIc8, 0);
|
||||||
Max31865PT1000Handler* rtdIc9 = new Max31865PT1000Handler(objects::RTD_IC9,
|
Max31865PT1000Handler* rtdIc9 = new Max31865PT1000Handler(objects::RTD_IC9, objects::SPI_COM_IF,
|
||||||
objects::SPI_COM_IF, spiRtdIc9, 0);
|
spiRtdIc9, 0);
|
||||||
Max31865PT1000Handler* rtdIc10 = new Max31865PT1000Handler(objects::RTD_IC10,
|
Max31865PT1000Handler* rtdIc10 = new Max31865PT1000Handler(objects::RTD_IC10,
|
||||||
objects::SPI_COM_IF, spiRtdIc10, 0);
|
objects::SPI_COM_IF, spiRtdIc10, 0);
|
||||||
Max31865PT1000Handler* rtdIc11 = new Max31865PT1000Handler(objects::RTD_IC11,
|
Max31865PT1000Handler* rtdIc11 = new Max31865PT1000Handler(objects::RTD_IC11,
|
||||||
@ -770,30 +775,30 @@ void ObjectFactory::createRtdComponents(LinuxLibgpioIF *gpioComIF) {
|
|||||||
|
|
||||||
void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
|
void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
|
||||||
GpioCookie* gpioCookieRw = new GpioCookie;
|
GpioCookie* gpioCookieRw = new GpioCookie;
|
||||||
GpioCallback* csRw1 = new GpioCallback("Chip select reaction wheel 1", gpio::OUT,
|
GpioCallback* csRw1 = new GpioCallback("Chip select reaction wheel 1", gpio::OUT, gpio::HIGH,
|
||||||
gpio::HIGH, &gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
||||||
gpioCookieRw->addGpio(gpioIds::CS_RW1, csRw1);
|
gpioCookieRw->addGpio(gpioIds::CS_RW1, csRw1);
|
||||||
GpioCallback* csRw2 = new GpioCallback("Chip select reaction wheel 2", gpio::OUT,
|
GpioCallback* csRw2 = new GpioCallback("Chip select reaction wheel 2", gpio::OUT, gpio::HIGH,
|
||||||
gpio::HIGH, &gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
||||||
gpioCookieRw->addGpio(gpioIds::CS_RW2, csRw2);
|
gpioCookieRw->addGpio(gpioIds::CS_RW2, csRw2);
|
||||||
GpioCallback* csRw3 = new GpioCallback("Chip select reaction wheel 3", gpio::OUT,
|
GpioCallback* csRw3 = new GpioCallback("Chip select reaction wheel 3", gpio::OUT, gpio::HIGH,
|
||||||
gpio::HIGH, &gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
||||||
gpioCookieRw->addGpio(gpioIds::CS_RW3, csRw3);
|
gpioCookieRw->addGpio(gpioIds::CS_RW3, csRw3);
|
||||||
GpioCallback* csRw4 = new GpioCallback("Chip select reaction wheel 4", gpio::OUT,
|
GpioCallback* csRw4 = new GpioCallback("Chip select reaction wheel 4", gpio::OUT, gpio::HIGH,
|
||||||
gpio::HIGH, &gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
|
||||||
gpioCookieRw->addGpio(gpioIds::CS_RW4, csRw4);
|
gpioCookieRw->addGpio(gpioIds::CS_RW4, csRw4);
|
||||||
|
|
||||||
GpiodRegular* enRw1 = new GpiodRegular(q7s::GPIO_RW_DEFAULT_CHIP, q7s::GPIO_RW_0_CS,
|
GpiodRegular* enRw1 = new GpiodRegular("Enable reaction wheel 1", gpio::OUT, 0,
|
||||||
"Enable reaction wheel 1", gpio::OUT, 0);
|
q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_0_CS);
|
||||||
gpioCookieRw->addGpio(gpioIds::EN_RW1, enRw1);
|
gpioCookieRw->addGpio(gpioIds::EN_RW1, enRw1);
|
||||||
GpiodRegular* enRw2 = new GpiodRegular(q7s::GPIO_RW_DEFAULT_CHIP, q7s::GPIO_RW_1_CS,
|
GpiodRegular* enRw2 = new GpiodRegular("Enable reaction wheel 2", gpio::OUT, 0,
|
||||||
"Enable reaction wheel 2", gpio::OUT, 0);
|
q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_1_CS);
|
||||||
gpioCookieRw->addGpio(gpioIds::EN_RW2, enRw2);
|
gpioCookieRw->addGpio(gpioIds::EN_RW2, enRw2);
|
||||||
GpiodRegular* enRw3 = new GpiodRegular(q7s::GPIO_RW_DEFAULT_CHIP, q7s::GPIO_RW_2_CS,
|
GpiodRegular* enRw3 = new GpiodRegular("Enable reaction wheel 3", gpio::OUT, 0,
|
||||||
"Enable reaction wheel 3", gpio::OUT, 0);
|
q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_2_CS);
|
||||||
gpioCookieRw->addGpio(gpioIds::EN_RW3, enRw3);
|
gpioCookieRw->addGpio(gpioIds::EN_RW3, enRw3);
|
||||||
GpiodRegular* enRw4 = new GpiodRegular(q7s::GPIO_RW_DEFAULT_CHIP, q7s::GPIO_RW_3_CS,
|
GpiodRegular* enRw4 = new GpiodRegular("Enable reaction wheel 4", gpio::OUT, 0,
|
||||||
"Enable reaction wheel 4", gpio::OUT, 0);
|
q7s::GPIO_RW_DEFAULT_LABEL, q7s::GPIO_RW_3_CS);
|
||||||
gpioCookieRw->addGpio(gpioIds::EN_RW4, enRw4);
|
gpioCookieRw->addGpio(gpioIds::EN_RW4, enRw4);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -801,8 +806,8 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
* the PS SPI peripheral from the SPI interface and route out the SPI lines of the AXI SPI core.
|
* the PS SPI peripheral from the SPI interface and route out the SPI lines of the AXI SPI core.
|
||||||
* Per default the PS SPI is selected (EMIO = 0).
|
* Per default the PS SPI is selected (EMIO = 0).
|
||||||
*/
|
*/
|
||||||
GpiodRegular* spiMux = new GpiodRegular(q7s::GPIO_RW_SPI_MUX_CHIP, q7s::GPIO_RW_SPI_MUX_CS,
|
GpiodRegular* spiMux = new GpiodRegular("EMIO 0 SPI Mux", gpio::OUT, 0,
|
||||||
"EMIO 0 SPI Mux", gpio::OUT, 0);
|
q7s::GPIO_RW_SPI_MUX_LABEL, q7s::GPIO_RW_SPI_MUX_CS);
|
||||||
gpioCookieRw->addGpio(gpioIds::SPI_MUX, spiMux);
|
gpioCookieRw->addGpio(gpioIds::SPI_MUX, spiMux);
|
||||||
|
|
||||||
gpioComIF->addGpios(gpioCookieRw);
|
gpioComIF->addGpios(gpioCookieRw);
|
||||||
@ -844,11 +849,15 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1
|
#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1
|
||||||
|
#if OBSW_TEST_GPIO_LABEL == 1
|
||||||
/* Configure MIO0 as input */
|
/* Configure MIO0 as input */
|
||||||
GpiodRegular gpioConfigMio0(std::string("gpiochip0"), 0,
|
GpiodRegular* testGpio = new GpiodRegular("MIO0", gpio::OUT, 0, "/amba_pl/gpio@41200000", 0);
|
||||||
std::string("MIO0"), gpio::IN, 0);
|
#else
|
||||||
|
/* Configure MIO0 as input */
|
||||||
|
GpiodRegular* testGpio = new GpiodRegular("gpiochip0", 0, "MIO0", gpio::IN, 0);
|
||||||
|
#endif /* OBSW_TEST_GPIO_LABEL == 1 */
|
||||||
GpioCookie* gpioCookie = new GpioCookie;
|
GpioCookie* gpioCookie = new GpioCookie;
|
||||||
gpioCookie->addGpio(gpioIds::TEST_ID_0, gpioConfigMio0);
|
gpioCookie->addGpio(gpioIds::TEST_ID_0, testGpio);
|
||||||
new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie);
|
new LibgpiodTest(objects::LIBGPIOD_TEST, objects::GPIO_IF, gpioCookie);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1,4 +1,5 @@
|
|||||||
#include "gpioCallbacks.h"
|
#include "gpioCallbacks.h"
|
||||||
|
#include "busConf.h"
|
||||||
#include <devices/gpioIds.h>
|
#include <devices/gpioIds.h>
|
||||||
|
|
||||||
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
||||||
@ -24,29 +25,29 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
|
|||||||
GpioCookie* spiMuxGpios = new GpioCookie;
|
GpioCookie* spiMuxGpios = new GpioCookie;
|
||||||
|
|
||||||
/** Setting mux bit 1 to low will disable IC21 on the interface board */
|
/** Setting mux bit 1 to low will disable IC21 on the interface board */
|
||||||
GpiodRegular* spiMuxBit1 = new GpiodRegular(std::string("gpiochip7"), 13,
|
GpiodRegular* spiMuxBit1 = new GpiodRegular(std::string("SPI Mux Bit 1"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 1"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_1);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit1);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit1);
|
||||||
/** Setting mux bit 2 to low disables IC1 on the TCS board */
|
/** Setting mux bit 2 to low disables IC1 on the TCS board */
|
||||||
GpiodRegular* spiMuxBit2 = new GpiodRegular(std::string("gpiochip7"), 14,
|
GpiodRegular* spiMuxBit2 = new GpiodRegular(std::string("SPI Mux Bit 2"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 2"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_2);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit2);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit2);
|
||||||
/** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */
|
/** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */
|
||||||
GpiodRegular* spiMuxBit3 = new GpiodRegular(std::string("gpiochip7"), 15,
|
GpiodRegular* spiMuxBit3 = new GpiodRegular(std::string("SPI Mux Bit 3"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 3"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_3);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit3);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit3);
|
||||||
/** The following gpios can take arbitrary initial values */
|
/** The following gpios can take arbitrary initial values */
|
||||||
GpiodRegular* spiMuxBit4 = new GpiodRegular(std::string("gpiochip7"), 16,
|
GpiodRegular* spiMuxBit4 = new GpiodRegular(std::string("SPI Mux Bit 4"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 4"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_4);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit4);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit4);
|
||||||
GpiodRegular* spiMuxBit5 = new GpiodRegular(std::string("gpiochip7"), 17,
|
GpiodRegular* spiMuxBit5 = new GpiodRegular(std::string("SPI Mux Bit 5"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 5"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_5);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit5);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit5);
|
||||||
GpiodRegular* spiMuxBit6 = new GpiodRegular(std::string("gpiochip7"), 9,
|
GpiodRegular* spiMuxBit6 = new GpiodRegular(std::string("SPI Mux Bit 6"), gpio::OUT, 0,
|
||||||
std::string("SPI Mux Bit 6"), gpio::OUT, 0);
|
q7s::GPIO_3V3_OBC1C, q7s::SPI_MUX_BIT_6);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit6);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit6);
|
||||||
GpiodRegular* enRwDecoder = new GpiodRegular(std::string("gpiochip5"), 17,
|
GpiodRegular* enRwDecoder = new GpiodRegular(std::string("EN_RW_CS"), gpio::OUT, 1,
|
||||||
std::string("EN_RW_CS"), gpio::OUT, 1);
|
q7s::GPIO_FLEX_OBC1F_B1, q7s::EN_RW_CS);
|
||||||
spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder);
|
spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder);
|
||||||
|
|
||||||
result = gpioComInterface->addGpios(spiMuxGpios);
|
result = gpioComInterface->addGpios(spiMuxGpios);
|
||||||
|
@ -11,6 +11,10 @@ int simple::simple() {
|
|||||||
{
|
{
|
||||||
FileSystemTest fileSystemTest;
|
FileSystemTest fileSystemTest;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if TE0720_GPIO_TEST
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -26,10 +26,10 @@ static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_3;
|
|||||||
static constexpr uint32_t DEFAULT_ADIS16507_SPEED = 976'000;
|
static constexpr uint32_t DEFAULT_ADIS16507_SPEED = 976'000;
|
||||||
static constexpr spi::SpiModes DEFAULT_ADIS16507_MODE = spi::SpiModes::MODE_3;
|
static constexpr spi::SpiModes DEFAULT_ADIS16507_MODE = spi::SpiModes::MODE_3;
|
||||||
|
|
||||||
static constexpr uint32_t RW_SPEED = 300000;
|
static constexpr uint32_t RW_SPEED = 300'000;
|
||||||
static constexpr spi::SpiModes RW_MODE = spi::SpiModes::MODE_0;
|
static constexpr spi::SpiModes RW_MODE = spi::SpiModes::MODE_0;
|
||||||
|
|
||||||
static constexpr uint32_t RTD_SPEED = 2000000;
|
static constexpr uint32_t RTD_SPEED = 2'000'000;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
2
fsfw
2
fsfw
@ -1 +1 @@
|
|||||||
Subproject commit 8f3edc90ba844b9a4551bb77a71e6dcbdae6e9ee
|
Subproject commit 70a3749dbe2cf7d23c685b0e3b3ce350a7c9db05
|
@ -15,7 +15,7 @@ LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId,
|
|||||||
sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl;
|
sif::error << "LibgpiodTest::LibgpiodTest: Invalid Gpio interface." << std::endl;
|
||||||
}
|
}
|
||||||
gpioInterface->addGpios(gpioCookie);
|
gpioInterface->addGpios(gpioCookie);
|
||||||
testCase = TestCases::LOOPBACK;
|
testCase = TestCases::BLINK;
|
||||||
}
|
}
|
||||||
|
|
||||||
LibgpiodTest::~LibgpiodTest() {
|
LibgpiodTest::~LibgpiodTest() {
|
||||||
@ -29,7 +29,7 @@ ReturnValue_t LibgpiodTest::performPeriodicAction() {
|
|||||||
case(TestCases::READ): {
|
case(TestCases::READ): {
|
||||||
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState);
|
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::debug << "LibgpiodTest::performPeriodicAction: Failed to read gpio "
|
sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio "
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return RETURN_FAILED;
|
return RETURN_FAILED;
|
||||||
}
|
}
|
||||||
@ -42,6 +42,38 @@ ReturnValue_t LibgpiodTest::performPeriodicAction() {
|
|||||||
case(TestCases::LOOPBACK): {
|
case(TestCases::LOOPBACK): {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case(TestCases::BLINK): {
|
||||||
|
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio "
|
||||||
|
<< std::endl;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
if (gpioState == 1) {
|
||||||
|
result = gpioInterface->pullLow(gpioIds::TEST_ID_0);
|
||||||
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO low!"
|
||||||
|
<< std::endl;
|
||||||
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (gpioState == 0) {
|
||||||
|
result = gpioInterface->pullHigh(gpioIds::TEST_ID_0);
|
||||||
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO high!"
|
||||||
|
<< std::endl;
|
||||||
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
sif::warning << "LibgpiodTest::performPeriodicAction: Invalid GPIO state" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
sif::debug << "LibgpiodTest::performPeriodicAction: Invalid test case" << std::endl;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -56,6 +88,9 @@ ReturnValue_t LibgpiodTest::performOneShotAction() {
|
|||||||
case(TestCases::READ): {
|
case(TestCases::READ): {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case(TestCases::BLINK): {
|
||||||
|
break;
|
||||||
|
}
|
||||||
case(TestCases::LOOPBACK): {
|
case(TestCases::LOOPBACK): {
|
||||||
result = gpioInterface->pullHigh(gpioIds::TEST_ID_0);
|
result = gpioInterface->pullHigh(gpioIds::TEST_ID_0);
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
if(result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
@ -14,7 +14,8 @@ class LibgpiodTest: public TestTask {
|
|||||||
public:
|
public:
|
||||||
enum TestCases {
|
enum TestCases {
|
||||||
READ = 0,
|
READ = 0,
|
||||||
LOOPBACK = 1
|
LOOPBACK = 1,
|
||||||
|
BLINK
|
||||||
};
|
};
|
||||||
|
|
||||||
TestCases testCase;
|
TestCases testCase;
|
||||||
|
@ -24,7 +24,7 @@ gpioIF(gpioIF) {
|
|||||||
if(gpioIF == nullptr) {
|
if(gpioIF == nullptr) {
|
||||||
sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl;
|
sif::error << "SpiTestClass::SpiTestClass: Invalid GPIO ComIF!" << std::endl;
|
||||||
}
|
}
|
||||||
testMode = TestModes::MGM_RM3100;
|
testMode = TestModes::MGM_LIS3MDL;
|
||||||
spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data());
|
spiTransferStruct.rx_buf = reinterpret_cast<__u64>(recvBuffer.data());
|
||||||
spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data());
|
spiTransferStruct.tx_buf = reinterpret_cast<__u64>(sendBuffer.data());
|
||||||
}
|
}
|
||||||
@ -299,7 +299,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) {
|
|||||||
void SpiTestClass::acsInit() {
|
void SpiTestClass::acsInit() {
|
||||||
GpioCookie* gpioCookie = new GpioCookie();
|
GpioCookie* gpioCookie = new GpioCookie();
|
||||||
GpiodRegular* gpio = nullptr;
|
GpiodRegular* gpio = nullptr;
|
||||||
#ifdef RASPBERRY_PI
|
#ifdef RASPBERRY_PI
|
||||||
std::string rpiGpioName = "gpiochip0";
|
std::string rpiGpioName = "gpiochip0";
|
||||||
gpio = new GpiodRegular(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3",
|
gpio = new GpiodRegular(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3",
|
||||||
gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
@ -328,43 +328,43 @@ void SpiTestClass::acsInit() {
|
|||||||
gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100",
|
gpio = new GpiodRegular(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100",
|
||||||
gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
||||||
#elif defined(XIPHOS_Q7S)
|
#elif defined(XIPHOS_Q7S)
|
||||||
|
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, mgm0Lis3mdlChipSelect,
|
gpio = new GpiodRegular("MGM_0_LIS3", gpio::Direction::OUT, gpio::HIGH,
|
||||||
"MGM_0_LIS3", gpio::Direction::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm0Lis3mdlChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, mgm1Rm3100ChipSelect,
|
gpio = new GpiodRegular("MGM_1_RM3100", gpio::Direction::OUT, gpio::HIGH,
|
||||||
"MGM_1_RM3100", gpio::Direction::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm1Rm3100ChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_MGM2_LIS3_CHIP, mgm2Lis3mdlChipSelect,
|
gpio = new GpiodRegular("MGM_2_LIS3", gpio::Direction::OUT, gpio::HIGH, q7s::GPIO_MGM2_LIS3_LABEL,
|
||||||
"MGM_2_LIS3", gpio::Direction::OUT, gpio::HIGH);
|
mgm2Lis3mdlChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, mgm3Rm3100ChipSelect,
|
gpio = new GpiodRegular("MGM_3_RM3100", gpio::Direction::OUT, gpio::HIGH,
|
||||||
"MGM_3_RM3100", gpio::Direction::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, mgm3Rm3100ChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegular(q7s::GPIO_GYRO_ADIS_CHIP, gyro0AdisChipSelect,
|
gpio = new GpiodRegular("GYRO_0_ADIS", gpio::Direction::OUT, gpio::HIGH, q7s::GPIO_GYRO_ADIS_LABEL,
|
||||||
"GYRO_0_ADIS", gpio::Direction::OUT, gpio::HIGH);
|
gyro0AdisChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, gyro1L3gd20ChipSelect,
|
gpio = new GpiodRegular("GYRO_1_L3G", gpio::Direction::OUT, gpio::HIGH,
|
||||||
"GYRO_1_L3G", gpio::Direction::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, gyro1L3gd20ChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_GYRO_ADIS_CHIP, gyro2AdisChipSelect,
|
gpio = new GpiodRegular("GYRO_2_ADIS", gpio::Direction::OUT, gpio::HIGH, q7s::GPIO_GYRO_ADIS_LABEL,
|
||||||
"GYRO_2_ADIS", gpio::Direction::OUT, gpio::HIGH);
|
gyro2AdisChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_ACS_BOARD_DEFAULT_CHIP, gyro3L3gd20ChipSelect,
|
gpio = new GpiodRegular("GYRO_3_L3G", gpio::Direction::OUT, gpio::HIGH,
|
||||||
"GYRO_3_L3G", gpio::Direction::OUT, gpio::HIGH);
|
q7s::GPIO_ACS_BOARD_DEFAULT_LABEL, gyro3L3gd20ChipSelect);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
||||||
|
|
||||||
// Enable pins must be pulled low for regular operations
|
// Enable pins must be pulled low for regular operations
|
||||||
gpio = new GpiodRegular(q7s::GPIO_FLEX_OBC1F_B0, q7s::GPIO_GYRO_0_ENABLE,
|
gpio = new GpiodRegular("GYRO_0_ENABLE", gpio::OUT, gpio::LOW, q7s::GPIO_FLEX_OBC1F_B0,
|
||||||
"GYRO_0_ENABLE", gpio::OUT, gpio::LOW);
|
q7s::GPIO_GYRO_0_ENABLE);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
|
||||||
gpio = new GpiodRegular(q7s::GPIO_3V3_OBC1C, q7s::GPIO_GYRO_2_ENABLE,
|
gpio = new GpiodRegular("GYRO_2_ENABLE", gpio::OUT, gpio::LOW, q7s::GPIO_3V3_OBC1C,
|
||||||
"GYRO_2_ENABLE", gpio::OUT, gpio::LOW);
|
q7s::GPIO_GYRO_2_ENABLE);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
|
||||||
#endif
|
#endif
|
||||||
if(gpioIF != nullptr) {
|
if (gpioIF != nullptr) {
|
||||||
gpioIF->addGpios(gpioCookie);
|
gpioIF->addGpios(gpioCookie);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -74,6 +74,9 @@ static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048;
|
|||||||
|
|
||||||
#define FSFW_HAL_LINUX_SPI_WIRETAPPING 0
|
#define FSFW_HAL_LINUX_SPI_WIRETAPPING 0
|
||||||
#define FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV 0
|
#define FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV 0
|
||||||
|
|
||||||
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
|
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
|
||||||
|
#define FSFW_HAL_RM3100_MGM_DEBUG 0
|
||||||
|
#define FSFW_HAL_LIS3MDL_MGM_DEBUG 0
|
||||||
|
|
||||||
#endif /* CONFIG_FSFWCONFIG_H_ */
|
#endif /* CONFIG_FSFWCONFIG_H_ */
|
||||||
|
@ -48,7 +48,7 @@ debugging. */
|
|||||||
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1
|
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1
|
||||||
#define OBSW_PRINT_MISSED_DEADLINES 1
|
#define OBSW_PRINT_MISSED_DEADLINES 1
|
||||||
// If this is enabled, all other SPI code should be disabled
|
// If this is enabled, all other SPI code should be disabled
|
||||||
#define OBSW_ADD_TEST_CODE 1
|
#define OBSW_ADD_TEST_CODE 0
|
||||||
#define OBSW_ADD_SPI_TEST_CODE 0
|
#define OBSW_ADD_SPI_TEST_CODE 0
|
||||||
#define OBSW_ADD_TEST_PST 0
|
#define OBSW_ADD_TEST_PST 0
|
||||||
#define OBSW_ADD_TEST_TASK 0
|
#define OBSW_ADD_TEST_TASK 0
|
||||||
@ -59,15 +59,16 @@ debugging. */
|
|||||||
#define OBSW_TEST_CCSDS_BRIDGE 0
|
#define OBSW_TEST_CCSDS_BRIDGE 0
|
||||||
#define OBSW_TEST_CCSDS_PTME 0
|
#define OBSW_TEST_CCSDS_PTME 0
|
||||||
#define OBSW_TEST_TE7020_HEATER 0
|
#define OBSW_TEST_TE7020_HEATER 0
|
||||||
|
#define OBSW_TEST_GPIO_LABEL 0
|
||||||
|
|
||||||
#define OBSW_DEBUG_P60DOCK 0
|
#define OBSW_DEBUG_P60DOCK 0
|
||||||
#define OBSW_DEBUG_PDU1 0
|
#define OBSW_DEBUG_PDU1 0
|
||||||
#define OBSW_DEBUG_PDU2 0
|
#define OBSW_DEBUG_PDU2 0
|
||||||
|
#define OBSW_DEBUG_GPS 0
|
||||||
#define OBSW_DEBUG_ACU 0
|
#define OBSW_DEBUG_ACU 0
|
||||||
#define OBSW_DEBUG_SYRLINKS 0
|
#define OBSW_DEBUG_SYRLINKS 0
|
||||||
#define OBSW_DEBUG_IMQT 0
|
#define OBSW_DEBUG_IMQT 0
|
||||||
#define OBSW_DEBUG_ADIS16507 0
|
#define OBSW_DEBUG_ADIS16507 0
|
||||||
#define OBSW_DEBUG_L3GD20_GYRO 0
|
|
||||||
#define OBSW_DEBUG_RAD_SENSOR 0
|
#define OBSW_DEBUG_RAD_SENSOR 0
|
||||||
#define OBSW_DEBUG_SUS 0
|
#define OBSW_DEBUG_SUS 0
|
||||||
#define OBSW_DEBUG_RTD 0
|
#define OBSW_DEBUG_RTD 0
|
||||||
|
@ -425,93 +425,101 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
|
|||||||
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ);
|
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
#if OBSW_ADD_ACS_BOARD == 1
|
#if OBSW_ADD_ACS_BOARD == 1
|
||||||
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0,
|
bool enableAside = false;
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
bool enableBside = true;
|
||||||
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2,
|
if(enableAside) {
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
// A side
|
||||||
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.6,
|
||||||
|
DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * 0.8,
|
||||||
|
DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0,
|
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0,
|
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
// DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.2,
|
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
// DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.4,
|
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
// DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6,
|
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
// DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.8,
|
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
// DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0,
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
|
}
|
||||||
|
|
||||||
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0,
|
if(enableBside) {
|
||||||
// DeviceHandlerIF::PERFORM_OPERATION);
|
// B side
|
||||||
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0,
|
||||||
// DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.2,
|
||||||
// DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.4,
|
||||||
// DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
// thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.6,
|
||||||
// DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
|
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * 0.8,
|
||||||
|
DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0,
|
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0,
|
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0,
|
||||||
// DeviceHandlerIF::PERFORM_OPERATION);
|
// DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.2,
|
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.2,
|
||||||
// DeviceHandlerIF::SEND_WRITE);
|
// DeviceHandlerIF::SEND_WRITE);
|
||||||
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.4,
|
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.4,
|
||||||
// DeviceHandlerIF::GET_WRITE);
|
// DeviceHandlerIF::GET_WRITE);
|
||||||
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.6,
|
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.6,
|
||||||
// DeviceHandlerIF::SEND_READ);
|
// DeviceHandlerIF::SEND_READ);
|
||||||
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.8,
|
// thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, length * 0.8,
|
||||||
// DeviceHandlerIF::GET_READ);
|
// DeviceHandlerIF::GET_READ);
|
||||||
|
|
||||||
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0,
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
|
}
|
||||||
#endif /* OBSW_ADD_ACS_BOARD == 1 */
|
#endif /* OBSW_ADD_ACS_BOARD == 1 */
|
||||||
|
|
||||||
if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) {
|
if (thisSequence->checkSequence() != HasReturnvaluesIF::RETURN_OK) {
|
||||||
@ -547,13 +555,13 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
|
|||||||
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0,
|
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
@ -563,13 +571,13 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
|
|||||||
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0,
|
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0,
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2,
|
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2,
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
DeviceHandlerIF::SEND_WRITE);
|
||||||
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4,
|
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4,
|
||||||
DeviceHandlerIF::GET_WRITE);
|
DeviceHandlerIF::GET_WRITE);
|
||||||
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.6,
|
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.6,
|
||||||
DeviceHandlerIF::SEND_READ);
|
DeviceHandlerIF::SEND_READ);
|
||||||
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8,
|
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8,
|
||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if Q7S_ADD_SYRLINKS_HANDLER == 1
|
#if Q7S_ADD_SYRLINKS_HANDLER == 1
|
||||||
|
@ -1,6 +1,5 @@
|
|||||||
target_sources(${TARGET_NAME} PUBLIC
|
target_sources(${TARGET_NAME} PUBLIC
|
||||||
GPSHyperionHandler.cpp
|
GPSHyperionHandler.cpp
|
||||||
MGMHandlerLIS3MDL.cpp
|
|
||||||
GomspaceDeviceHandler.cpp
|
GomspaceDeviceHandler.cpp
|
||||||
Tmp1075Handler.cpp
|
Tmp1075Handler.cpp
|
||||||
PCDUHandler.cpp
|
PCDUHandler.cpp
|
||||||
|
@ -23,7 +23,6 @@ GPSHyperionHandler::~GPSHyperionHandler() {}
|
|||||||
void GPSHyperionHandler::doStartUp() {
|
void GPSHyperionHandler::doStartUp() {
|
||||||
if(internalState == InternalStates::NONE) {
|
if(internalState == InternalStates::NONE) {
|
||||||
commandExecuted = false;
|
commandExecuted = false;
|
||||||
updatePeriodicReply(true, GpsHyperion::GPS_REPLY);
|
|
||||||
internalState = InternalStates::WAIT_FIRST_MESSAGE;
|
internalState = InternalStates::WAIT_FIRST_MESSAGE;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -76,7 +75,7 @@ ReturnValue_t GPSHyperionHandler::scanForReply(const uint8_t *start, size_t len,
|
|||||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
DeviceCommandId_t *foundId, size_t *foundLen) {
|
||||||
// Pass data to GPS library
|
// Pass data to GPS library
|
||||||
if(len > 0) {
|
if(len > 0) {
|
||||||
sif::debug << "GPSHandler::scanForReply: Received " << len << " bytes" << std::endl;
|
// sif::debug << "GPSHandler::scanForReply: Received " << len << " bytes" << std::endl;
|
||||||
if (internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
if (internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
||||||
// TODO: Check whether data is valid by checking whether NMEA start string is valid?
|
// TODO: Check whether data is valid by checking whether NMEA start string is valid?
|
||||||
commandExecuted = true;
|
commandExecuted = true;
|
||||||
@ -202,3 +201,12 @@ void GPSHyperionHandler::setResetPinTriggerFunction(gpioResetFunction_t resetCal
|
|||||||
void GPSHyperionHandler::debugInterface(uint8_t positionTracker, object_id_t objectId,
|
void GPSHyperionHandler::debugInterface(uint8_t positionTracker, object_id_t objectId,
|
||||||
uint32_t parameter) {
|
uint32_t parameter) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ReturnValue_t GPSHyperionHandler::initialize() {
|
||||||
|
ReturnValue_t result = DeviceHandlerBase::initialize();
|
||||||
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
// Enable reply immediately for now
|
||||||
|
return updatePeriodicReply(true, GpsHyperion::GPS_REPLY);
|
||||||
|
}
|
||||||
|
@ -14,12 +14,16 @@
|
|||||||
*/
|
*/
|
||||||
class GPSHyperionHandler: public DeviceHandlerBase {
|
class GPSHyperionHandler: public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
using gpioResetFunction_t = ReturnValue_t (*) (void* args);
|
|
||||||
GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication,
|
GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||||
CookieIF* comCookie, bool debugHyperionGps = false);
|
CookieIF* comCookie, bool debugHyperionGps = false);
|
||||||
virtual ~GPSHyperionHandler();
|
virtual ~GPSHyperionHandler();
|
||||||
|
|
||||||
|
using gpioResetFunction_t = ReturnValue_t (*) (void* args);
|
||||||
|
|
||||||
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void*args);
|
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void*args);
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
gpioResetFunction_t resetCallback = nullptr;
|
gpioResetFunction_t resetCallback = nullptr;
|
||||||
|
@ -7,11 +7,11 @@ GomspaceDeviceHandler::GomspaceDeviceHandler(object_id_t objectId, object_id_t c
|
|||||||
DeviceHandlerBase(objectId, comIF, comCookie), maxConfigTableAddress(maxConfigTableAddress),
|
DeviceHandlerBase(objectId, comIF, comCookie), maxConfigTableAddress(maxConfigTableAddress),
|
||||||
maxHkTableAddress(maxHkTableAddress), hkTableReplySize(hkTableReplySize),
|
maxHkTableAddress(maxHkTableAddress), hkTableReplySize(hkTableReplySize),
|
||||||
hkTableDataset(hkTableDataset) {
|
hkTableDataset(hkTableDataset) {
|
||||||
if (comCookie == NULL) {
|
if (comCookie == nullptr) {
|
||||||
sif::error << "GomspaceDeviceHandler::GomspaceDeviceHandler: Invalid com cookie"
|
sif::error << "GomspaceDeviceHandler::GomspaceDeviceHandler: Invalid com cookie"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
if (hkTableDataset == NULL) {
|
if (hkTableDataset == nullptr) {
|
||||||
sif::error << "GomspaceDeviceHandler::GomspaceDeviceHandler: Invalid hk table data set"
|
sif::error << "GomspaceDeviceHandler::GomspaceDeviceHandler: Invalid hk table data set"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
@ -75,7 +75,7 @@ ReturnValue_t GomspaceDeviceHandler::buildCommandFromCommand(
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(GOMSPACE::PRINT_OUT_ENB_STATUS): {
|
case(GOMSPACE::PRINT_SWITCH_V_I): {
|
||||||
result = printStatus(deviceCommand);
|
result = printStatus(deviceCommand);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -99,7 +99,7 @@ void GomspaceDeviceHandler::fillCommandAndReplyMap(){
|
|||||||
this->insertInCommandAndReplyMap(GOMSPACE::PARAM_GET, 3);
|
this->insertInCommandAndReplyMap(GOMSPACE::PARAM_GET, 3);
|
||||||
this->insertInCommandAndReplyMap(GOMSPACE::REQUEST_HK_TABLE, 3);
|
this->insertInCommandAndReplyMap(GOMSPACE::REQUEST_HK_TABLE, 3);
|
||||||
this->insertInCommandMap(GOMSPACE::GNDWDT_RESET);
|
this->insertInCommandMap(GOMSPACE::GNDWDT_RESET);
|
||||||
this->insertInCommandMap(GOMSPACE::PRINT_OUT_ENB_STATUS);
|
this->insertInCommandMap(GOMSPACE::PRINT_SWITCH_V_I);
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t GomspaceDeviceHandler::scanForReply(const uint8_t *start,
|
ReturnValue_t GomspaceDeviceHandler::scanForReply(const uint8_t *start,
|
||||||
|
@ -1,498 +0,0 @@
|
|||||||
#include "MGMHandlerLIS3MDL.h"
|
|
||||||
|
|
||||||
#include "fsfw/datapool/PoolReadGuard.h"
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
MGMHandlerLIS3MDL::MGMHandlerLIS3MDL(object_id_t objectId,
|
|
||||||
object_id_t deviceCommunication, CookieIF* comCookie):
|
|
||||||
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
|
||||||
dataset(this) {
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
debugDivider = new PeriodicOperationDivider(5);
|
|
||||||
#endif
|
|
||||||
/* Set to default values right away. */
|
|
||||||
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
|
|
||||||
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
|
|
||||||
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
|
|
||||||
registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT;
|
|
||||||
registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
MGMHandlerLIS3MDL::~MGMHandlerLIS3MDL() {
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::doStartUp() {
|
|
||||||
switch (internalState) {
|
|
||||||
case(InternalState::STATE_NONE): {
|
|
||||||
internalState = InternalState::STATE_FIRST_CONTACT;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_FIRST_CONTACT): {
|
|
||||||
/* Will be set by checking device ID (WHO AM I register) */
|
|
||||||
if(commandExecuted) {
|
|
||||||
commandExecuted = false;
|
|
||||||
internalState = InternalState::STATE_SETUP;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_SETUP): {
|
|
||||||
internalState = InternalState::STATE_CHECK_REGISTERS;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_CHECK_REGISTERS): {
|
|
||||||
/* Set up cached registers which will be used to configure the MGM. */
|
|
||||||
if(commandExecuted) {
|
|
||||||
commandExecuted = false;
|
|
||||||
#if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1
|
|
||||||
setMode(MODE_NORMAL);
|
|
||||||
#else
|
|
||||||
setMode(_MODE_TO_ON);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::doShutDown() {
|
|
||||||
setMode(_MODE_POWER_DOWN);
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::buildTransitionDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) {
|
|
||||||
switch (internalState) {
|
|
||||||
case(InternalState::STATE_NONE):
|
|
||||||
case(InternalState::STATE_NORMAL): {
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_FIRST_CONTACT): {
|
|
||||||
*id = MGMLIS3MDL::IDENTIFY_DEVICE;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_SETUP): {
|
|
||||||
*id = MGMLIS3MDL::SETUP_MGM;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(InternalState::STATE_CHECK_REGISTERS): {
|
|
||||||
*id = MGMLIS3MDL::READ_CONFIG_AND_DATA;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default: {
|
|
||||||
/* might be a configuration error. */
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::warning << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" <<
|
|
||||||
std::endl;
|
|
||||||
#else
|
|
||||||
sif::printWarning("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n");
|
|
||||||
#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
return buildCommandFromCommand(*id, NULL, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t MGMHandlerLIS3MDL::readCommand(uint8_t command, bool continuousCom) {
|
|
||||||
command |= (1 << MGMLIS3MDL::RW_BIT);
|
|
||||||
if (continuousCom == true) {
|
|
||||||
command |= (1 << MGMLIS3MDL::MS_BIT);
|
|
||||||
}
|
|
||||||
return command;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t MGMHandlerLIS3MDL::writeCommand(uint8_t command, bool continuousCom) {
|
|
||||||
command &= ~(1 << MGMLIS3MDL::RW_BIT);
|
|
||||||
if (continuousCom == true) {
|
|
||||||
command |= (1 << MGMLIS3MDL::MS_BIT);
|
|
||||||
}
|
|
||||||
return command;
|
|
||||||
}
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::setupMgm() {
|
|
||||||
|
|
||||||
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
|
|
||||||
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
|
|
||||||
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
|
|
||||||
registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT;
|
|
||||||
registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT;
|
|
||||||
|
|
||||||
prepareCtrlRegisterWrite();
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::buildNormalDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) {
|
|
||||||
// Data/config register will be read in an alternating manner.
|
|
||||||
if(communicationStep == CommunicationStep::DATA) {
|
|
||||||
*id = MGMLIS3MDL::READ_CONFIG_AND_DATA;
|
|
||||||
communicationStep = CommunicationStep::TEMPERATURE;
|
|
||||||
return buildCommandFromCommand(*id, NULL, 0);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
*id = MGMLIS3MDL::READ_TEMPERATURE;
|
|
||||||
communicationStep = CommunicationStep::DATA;
|
|
||||||
return buildCommandFromCommand(*id, NULL, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::buildCommandFromCommand(
|
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) {
|
|
||||||
switch(deviceCommand) {
|
|
||||||
case(MGMLIS3MDL::READ_CONFIG_AND_DATA): {
|
|
||||||
std::memset(commandBuffer, 0, sizeof(commandBuffer));
|
|
||||||
commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true);
|
|
||||||
|
|
||||||
rawPacket = commandBuffer;
|
|
||||||
rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1;
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::READ_TEMPERATURE): {
|
|
||||||
std::memset(commandBuffer, 0, 3);
|
|
||||||
commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true);
|
|
||||||
|
|
||||||
rawPacket = commandBuffer;
|
|
||||||
rawPacketLen = 3;
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::IDENTIFY_DEVICE): {
|
|
||||||
return identifyDevice();
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::TEMP_SENSOR_ENABLE): {
|
|
||||||
return enableTemperatureSensor(commandData, commandDataLen);
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::SETUP_MGM): {
|
|
||||||
setupMgm();
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::ACCURACY_OP_MODE_SET): {
|
|
||||||
return setOperatingMode(commandData, commandDataLen);
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::identifyDevice() {
|
|
||||||
uint32_t size = 2;
|
|
||||||
commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR);
|
|
||||||
commandBuffer[1] = 0x00;
|
|
||||||
|
|
||||||
rawPacket = commandBuffer;
|
|
||||||
rawPacketLen = size;
|
|
||||||
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::scanForReply(const uint8_t *start,
|
|
||||||
size_t len, DeviceCommandId_t *foundId, size_t *foundLen) {
|
|
||||||
*foundLen = len;
|
|
||||||
if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) {
|
|
||||||
*foundLen = len;
|
|
||||||
*foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA;
|
|
||||||
// Check validity by checking config registers
|
|
||||||
if (start[1] != registers[0] or start[2] != registers[1] or
|
|
||||||
start[3] != registers[2] or start[4] != registers[3] or
|
|
||||||
start[5] != registers[4]) {
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl;
|
|
||||||
#else
|
|
||||||
sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n");
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
return DeviceHandlerIF::INVALID_DATA;
|
|
||||||
}
|
|
||||||
if(mode == _MODE_START_UP) {
|
|
||||||
commandExecuted = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
else if(len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) {
|
|
||||||
*foundLen = len;
|
|
||||||
*foundId = MGMLIS3MDL::READ_TEMPERATURE;
|
|
||||||
}
|
|
||||||
else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) {
|
|
||||||
*foundLen = len;
|
|
||||||
*foundId = MGMLIS3MDL::SETUP_MGM;
|
|
||||||
}
|
|
||||||
else if (len == SINGLE_COMMAND_ANSWER_LEN) {
|
|
||||||
*foundLen = len;
|
|
||||||
*foundId = getPendingCommand();
|
|
||||||
if(*foundId == MGMLIS3MDL::IDENTIFY_DEVICE) {
|
|
||||||
if(start[1] != MGMLIS3MDL::DEVICE_ID) {
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl;
|
|
||||||
#else
|
|
||||||
sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n");
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
return DeviceHandlerIF::INVALID_DATA;
|
|
||||||
}
|
|
||||||
|
|
||||||
if(mode == _MODE_START_UP) {
|
|
||||||
commandExecuted = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
return DeviceHandlerIF::INVALID_DATA;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Data with SPI Interface always has this answer */
|
|
||||||
if (start[0] == 0b11111111) {
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
return DeviceHandlerIF::INVALID_DATA;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::interpretDeviceReply(DeviceCommandId_t id,
|
|
||||||
const uint8_t *packet) {
|
|
||||||
|
|
||||||
switch (id) {
|
|
||||||
case MGMLIS3MDL::IDENTIFY_DEVICE: {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case MGMLIS3MDL::SETUP_MGM: {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case MGMLIS3MDL::READ_CONFIG_AND_DATA: {
|
|
||||||
// TODO: Store configuration in new local datasets.
|
|
||||||
float sensitivityFactor = getSensitivityFactor(getSensitivity(registers[2]));
|
|
||||||
|
|
||||||
int16_t mgmMeasurementRawX = packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8
|
|
||||||
| packet[MGMLIS3MDL::X_LOWBYTE_IDX] ;
|
|
||||||
int16_t mgmMeasurementRawY = packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8
|
|
||||||
| packet[MGMLIS3MDL::Y_LOWBYTE_IDX] ;
|
|
||||||
int16_t mgmMeasurementRawZ = packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8
|
|
||||||
| packet[MGMLIS3MDL::Z_LOWBYTE_IDX] ;
|
|
||||||
|
|
||||||
/* Target value in microtesla */
|
|
||||||
float mgmX = static_cast<float>(mgmMeasurementRawX) * sensitivityFactor
|
|
||||||
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
|
|
||||||
float mgmY = static_cast<float>(mgmMeasurementRawY) * sensitivityFactor
|
|
||||||
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
|
|
||||||
float mgmZ = static_cast<float>(mgmMeasurementRawZ) * sensitivityFactor
|
|
||||||
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
|
|
||||||
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
if(debugDivider->checkAndIncrement()) {
|
|
||||||
/* Set terminal to utf-8 if there is an issue with micro printout. */
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::info << "MGMHandlerLIS3: Magnetic field strength in"
|
|
||||||
" microtesla:" << std::endl;
|
|
||||||
sif::info << "X: " << mgmX << " uT" << std::endl;
|
|
||||||
sif::info << "Y: " << mgmY << " uT" << std::endl;
|
|
||||||
sif::info << "Z: " << mgmZ << " uT" << std::endl;
|
|
||||||
#else
|
|
||||||
sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n");
|
|
||||||
sif::printInfo("X: %f uT\n", mgmX);
|
|
||||||
sif::printInfo("Y: %f uT\n", mgmY);
|
|
||||||
sif::printInfo("Z: %f uT\n", mgmZ);
|
|
||||||
#endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */
|
|
||||||
}
|
|
||||||
#endif /* OBSW_VERBOSE_LEVEL >= 1 */
|
|
||||||
PoolReadGuard readHelper(&dataset);
|
|
||||||
if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
dataset.fieldStrengthX = mgmX;
|
|
||||||
dataset.fieldStrengthY = mgmY;
|
|
||||||
dataset.fieldStrengthZ = mgmZ;
|
|
||||||
dataset.setValidity(true, true);
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case MGMLIS3MDL::READ_TEMPERATURE: {
|
|
||||||
int16_t tempValueRaw = packet[2] << 8 | packet[1];
|
|
||||||
float tempValue = 25.0 + ((static_cast<float>(tempValueRaw)) / 8.0);
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
if(debugDivider->check()) {
|
|
||||||
/* Set terminal to utf-8 if there is an issue with micro printout. */
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" <<
|
|
||||||
std::endl;
|
|
||||||
#else
|
|
||||||
sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n");
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
ReturnValue_t result = dataset.read();
|
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
dataset.temperature = tempValue;
|
|
||||||
dataset.commit();
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
default: {
|
|
||||||
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
MGMLIS3MDL::Sensitivies MGMHandlerLIS3MDL::getSensitivity(uint8_t ctrlRegister2) {
|
|
||||||
bool fs0Set = ctrlRegister2 & (1 << MGMLIS3MDL::FSO); // Checks if FS0 bit is set
|
|
||||||
bool fs1Set = ctrlRegister2 & (1 << MGMLIS3MDL::FS1); // Checks if FS1 bit is set
|
|
||||||
|
|
||||||
if (fs0Set && fs1Set)
|
|
||||||
return MGMLIS3MDL::Sensitivies::GAUSS_16;
|
|
||||||
else if (!fs0Set && fs1Set)
|
|
||||||
return MGMLIS3MDL::Sensitivies::GAUSS_12;
|
|
||||||
else if (fs0Set && !fs1Set)
|
|
||||||
return MGMLIS3MDL::Sensitivies::GAUSS_8;
|
|
||||||
else
|
|
||||||
return MGMLIS3MDL::Sensitivies::GAUSS_4;
|
|
||||||
}
|
|
||||||
|
|
||||||
float MGMHandlerLIS3MDL::getSensitivityFactor(MGMLIS3MDL::Sensitivies sens) {
|
|
||||||
switch(sens) {
|
|
||||||
case(MGMLIS3MDL::GAUSS_4): {
|
|
||||||
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::GAUSS_8): {
|
|
||||||
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_8_SENS;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::GAUSS_12): {
|
|
||||||
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_12_SENS;
|
|
||||||
}
|
|
||||||
case(MGMLIS3MDL::GAUSS_16): {
|
|
||||||
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_16_SENS;
|
|
||||||
}
|
|
||||||
default: {
|
|
||||||
// Should never happen
|
|
||||||
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::enableTemperatureSensor(
|
|
||||||
const uint8_t *commandData, size_t commandDataLen) {
|
|
||||||
triggerEvent(CHANGE_OF_SETUP_PARAMETER);
|
|
||||||
uint32_t size = 2;
|
|
||||||
commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1);
|
|
||||||
if (commandDataLen > 1) {
|
|
||||||
return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS;
|
|
||||||
}
|
|
||||||
switch (*commandData) {
|
|
||||||
case (MGMLIS3MDL::ON): {
|
|
||||||
commandBuffer[1] = registers[0] | (1 << 7);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case (MGMLIS3MDL::OFF): {
|
|
||||||
commandBuffer[1] = registers[0] & ~(1 << 7);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
|
||||||
return INVALID_COMMAND_PARAMETER;
|
|
||||||
}
|
|
||||||
registers[0] = commandBuffer[1];
|
|
||||||
|
|
||||||
rawPacket = commandBuffer;
|
|
||||||
rawPacketLen = size;
|
|
||||||
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::setOperatingMode(const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) {
|
|
||||||
triggerEvent(CHANGE_OF_SETUP_PARAMETER);
|
|
||||||
if (commandDataLen != 1) {
|
|
||||||
return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS;
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (commandData[0]) {
|
|
||||||
case MGMLIS3MDL::LOW:
|
|
||||||
registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0));
|
|
||||||
registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0));
|
|
||||||
break;
|
|
||||||
case MGMLIS3MDL::MEDIUM:
|
|
||||||
registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0);
|
|
||||||
registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0);
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MGMLIS3MDL::HIGH:
|
|
||||||
registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0));
|
|
||||||
registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0));
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MGMLIS3MDL::ULTRA:
|
|
||||||
registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0);
|
|
||||||
registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0);
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
return prepareCtrlRegisterWrite();
|
|
||||||
}
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::fillCommandAndReplyMap() {
|
|
||||||
/*
|
|
||||||
* Regarding ArduinoBoard:
|
|
||||||
* Actually SPI answers directly, but as commanding ArduinoBoard the
|
|
||||||
* communication could be delayed
|
|
||||||
* SPI always has to be triggered, so there could be no periodic answer of
|
|
||||||
* the device, the device has to asked with a command, so periodic is zero.
|
|
||||||
*
|
|
||||||
* We dont read single registers, we just expect special
|
|
||||||
* reply from he Readall_MGM
|
|
||||||
*/
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset);
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1);
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1);
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1);
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1);
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1);
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::prepareCtrlRegisterWrite() {
|
|
||||||
commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true);
|
|
||||||
|
|
||||||
for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) {
|
|
||||||
commandBuffer[i + 1] = registers[i];
|
|
||||||
}
|
|
||||||
rawPacket = commandBuffer;
|
|
||||||
rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1;
|
|
||||||
|
|
||||||
/* We dont have to check if this is working because we just did it */
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::doTransition(Mode_t modeFrom, Submode_t subModeFrom) {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t MGMHandlerLIS3MDL::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
|
||||||
return 20000;
|
|
||||||
}
|
|
||||||
|
|
||||||
void MGMHandlerLIS3MDL::modeChanged(void) {
|
|
||||||
internalState = InternalState::STATE_NONE;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MGMHandlerLIS3MDL::initializeLocalDataPool(
|
|
||||||
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
|
|
||||||
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X,
|
|
||||||
new PoolEntry<float>({0.0}));
|
|
||||||
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y,
|
|
||||||
new PoolEntry<float>({0.0}));
|
|
||||||
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z,
|
|
||||||
new PoolEntry<float>({0.0}));
|
|
||||||
localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS,
|
|
||||||
new PoolEntry<float>({0.0}));
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
@ -1,165 +0,0 @@
|
|||||||
#ifndef MISSION_DEVICES_MGMLIS3MDLHANDLER_H_
|
|
||||||
#define MISSION_DEVICES_MGMLIS3MDLHANDLER_H_
|
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
|
||||||
#include "devicedefinitions/MGMHandlerLIS3Definitions.h"
|
|
||||||
#include "events/subsystemIdRanges.h"
|
|
||||||
|
|
||||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
|
||||||
|
|
||||||
class PeriodicOperationDivider;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Device handler object for the LIS3MDL 3-axis magnetometer
|
|
||||||
* by STMicroeletronics
|
|
||||||
* @details
|
|
||||||
* Datasheet can be found online by googling LIS3MDL.
|
|
||||||
* Flight manual:
|
|
||||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/LIS3MDL_MGM
|
|
||||||
* @author L. Loidold, R. Mueller
|
|
||||||
*/
|
|
||||||
class MGMHandlerLIS3MDL: public DeviceHandlerBase {
|
|
||||||
public:
|
|
||||||
enum class CommunicationStep {
|
|
||||||
DATA,
|
|
||||||
TEMPERATURE
|
|
||||||
};
|
|
||||||
|
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL;
|
|
||||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL;
|
|
||||||
//Notifies a command to change the setup parameters
|
|
||||||
static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW);
|
|
||||||
|
|
||||||
MGMHandlerLIS3MDL(uint32_t objectId, object_id_t deviceCommunication,
|
|
||||||
CookieIF* comCookie);
|
|
||||||
virtual ~MGMHandlerLIS3MDL();
|
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
/** DeviceHandlerBase overrides */
|
|
||||||
void doShutDown() override;
|
|
||||||
void doStartUp() override;
|
|
||||||
void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
|
|
||||||
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
|
||||||
ReturnValue_t buildCommandFromCommand(
|
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) override;
|
|
||||||
ReturnValue_t buildTransitionDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) override;
|
|
||||||
ReturnValue_t buildNormalDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) override;
|
|
||||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
|
||||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
|
|
||||||
const uint8_t *packet) override;
|
|
||||||
void fillCommandAndReplyMap() override;
|
|
||||||
void modeChanged(void) override;
|
|
||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
|
||||||
LocalDataPoolManager &poolManager) override;
|
|
||||||
|
|
||||||
private:
|
|
||||||
MGMLIS3MDL::MgmPrimaryDataset dataset;
|
|
||||||
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* Device specific commands and variables */
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/**
|
|
||||||
* Sets the read bit for the command
|
|
||||||
* @param single command to set the read-bit at
|
|
||||||
* @param boolean to select a continuous read bit, default = false
|
|
||||||
*/
|
|
||||||
uint8_t readCommand(uint8_t command, bool continuousCom = false);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Sets the write bit for the command
|
|
||||||
* @param single command to set the write-bit at
|
|
||||||
* @param boolean to select a continuous write bit, default = false
|
|
||||||
*/
|
|
||||||
uint8_t writeCommand(uint8_t command, bool continuousCom = false);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This Method gets the full scale for the measurement range
|
|
||||||
* e.g.: +- 4 gauss. See p.25 datasheet.
|
|
||||||
* @return The ReturnValue does not contain the sign of the value
|
|
||||||
*/
|
|
||||||
MGMLIS3MDL::Sensitivies getSensitivity(uint8_t ctrlReg2);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* The 16 bit value needs to be multiplied with a sensitivity factor
|
|
||||||
* which depends on the sensitivity configuration
|
|
||||||
*
|
|
||||||
* @param sens Configured sensitivity of the LIS3 device
|
|
||||||
* @return Multiplication factor to get the sensor value from raw data.
|
|
||||||
*/
|
|
||||||
float getSensitivityFactor(MGMLIS3MDL::Sensitivies sens);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This Command detects the device ID
|
|
||||||
*/
|
|
||||||
ReturnValue_t identifyDevice();
|
|
||||||
|
|
||||||
virtual void setupMgm();
|
|
||||||
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* Non normal commands */
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/**
|
|
||||||
* Enables/Disables the integrated Temperaturesensor
|
|
||||||
* @param commandData On or Off
|
|
||||||
* @param length of the commandData: has to be 1
|
|
||||||
*/
|
|
||||||
virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData,
|
|
||||||
size_t commandDataLen);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Sets the accuracy of the measurement of the axis. The noise is changing.
|
|
||||||
* @param commandData LOW, MEDIUM, HIGH, ULTRA
|
|
||||||
* @param length of the command, has to be 1
|
|
||||||
*/
|
|
||||||
virtual ReturnValue_t setOperatingMode(const uint8_t *commandData,
|
|
||||||
size_t commandDataLen);
|
|
||||||
|
|
||||||
|
|
||||||
//Length a sindgle command SPI answer
|
|
||||||
static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2;
|
|
||||||
|
|
||||||
//Single SPIcommand has 2 bytes, first for adress, second for content
|
|
||||||
size_t singleComandSize = 2;
|
|
||||||
//has the size for all adresses of the lis3mdl + the continous write bit
|
|
||||||
uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1];
|
|
||||||
|
|
||||||
/**
|
|
||||||
* We want to save the registers we set, so we dont have to read the
|
|
||||||
* registers when we want to change something.
|
|
||||||
* --> everytime we change set a register we have to save it
|
|
||||||
*/
|
|
||||||
uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS];
|
|
||||||
|
|
||||||
uint8_t statusRegister = 0;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* We always update all registers together, so this method updates
|
|
||||||
* the rawpacket and rawpacketLen, so we just manipulate the local
|
|
||||||
* saved register
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
ReturnValue_t prepareCtrlRegisterWrite();
|
|
||||||
|
|
||||||
enum class InternalState {
|
|
||||||
STATE_NONE,
|
|
||||||
STATE_FIRST_CONTACT,
|
|
||||||
STATE_SETUP,
|
|
||||||
STATE_CHECK_REGISTERS,
|
|
||||||
STATE_NORMAL
|
|
||||||
};
|
|
||||||
|
|
||||||
InternalState internalState = InternalState::STATE_NONE;
|
|
||||||
CommunicationStep communicationStep = CommunicationStep::DATA;
|
|
||||||
bool commandExecuted = false;
|
|
||||||
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1
|
|
||||||
PeriodicOperationDivider* debugDivider;
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif /* MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ */
|
|
@ -1,3 +1,4 @@
|
|||||||
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
#include "P60DockHandler.h"
|
#include "P60DockHandler.h"
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
|
|
||||||
@ -27,15 +28,24 @@ void P60DockHandler::letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *
|
|||||||
|
|
||||||
#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_P60DOCK == 1
|
#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_P60DOCK == 1
|
||||||
p60dockHkTableDataset.read();
|
p60dockHkTableDataset.read();
|
||||||
sif::info << "P60 Dock: ACU VCC switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateAcuVcc.value) << std::endl;
|
sif::info << "P60 Dock: ACU VCC switch: " <<
|
||||||
sif::info << "P60 Dock: PDU1 VCC switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu1Vcc.value) << std::endl;
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateAcuVcc.value) << std::endl;
|
||||||
sif::info << "P60 Dock: PDU2 VCC switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu2Vcc.value) << std::endl;
|
sif::info << "P60 Dock: PDU1 VCC switch: " <<
|
||||||
sif::info << "P60 Dock: ACU VBAT switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateAcuVbat.value) << std::endl;
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu1Vcc.value) << std::endl;
|
||||||
sif::info << "P60 Dock: PDU1 VBAT switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu1Vbat.value) << std::endl;
|
sif::info << "P60 Dock: PDU2 VCC switch: " <<
|
||||||
sif::info << "P60 Dock: PDU2 VBAT switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu2Vbat.value) << std::endl;
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu2Vcc.value) << std::endl;
|
||||||
sif::info << "P60 Dock: Stack VBAT switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStackVbat.value) << std::endl;
|
sif::info << "P60 Dock: ACU VBAT switch: " <<
|
||||||
sif::info << "P60 Dock: Stack 3V3 switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStack3V3.value) << std::endl;
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateAcuVbat.value) << std::endl;
|
||||||
sif::info << "P60 Dock: Stack 5V switch: " << static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStack5V.value) << std::endl;
|
sif::info << "P60 Dock: PDU1 VBAT switch: " <<
|
||||||
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu1Vbat.value) << std::endl;
|
||||||
|
sif::info << "P60 Dock: PDU2 VBAT switch: " <<
|
||||||
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStatePdu2Vbat.value) << std::endl;
|
||||||
|
sif::info << "P60 Dock: Stack VBAT switch: " <<
|
||||||
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStackVbat.value) << std::endl;
|
||||||
|
sif::info << "P60 Dock: Stack 3V3 switch: " <<
|
||||||
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStack3V3.value) << std::endl;
|
||||||
|
sif::info << "P60 Dock: Stack 5V switch: " <<
|
||||||
|
static_cast<unsigned int>(p60dockHkTableDataset.outputEnableStateStack5V.value) << std::endl;
|
||||||
|
|
||||||
float temperatureC = p60dockHkTableDataset.temperature1.value * 0.1;
|
float temperatureC = p60dockHkTableDataset.temperature1.value * 0.1;
|
||||||
sif::info << "P60 Dock: Temperature 1: " << temperatureC << " °C" << std::endl;
|
sif::info << "P60 Dock: Temperature 1: " << temperatureC << " °C" << std::endl;
|
||||||
@ -395,3 +405,76 @@ ReturnValue_t P60DockHandler::initializeLocalDataPool(
|
|||||||
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
ReturnValue_t P60DockHandler::printStatus(DeviceCommandId_t cmd) {
|
||||||
|
switch(cmd) {
|
||||||
|
case(GOMSPACE::PRINT_SWITCH_V_I): {
|
||||||
|
PoolReadGuard pg(&p60dockHkTableDataset);
|
||||||
|
ReturnValue_t readResult = pg.getReadResult();
|
||||||
|
if(readResult != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "Reading PDU1 HK table failed!" << std::endl;
|
||||||
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
|
}
|
||||||
|
printHkTable();
|
||||||
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
|
}
|
||||||
|
default: {
|
||||||
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void P60DockHandler::printHkTable() {
|
||||||
|
sif::info << "P60 Dock Info: SwitchState, Currents [mA], Voltages [mV]" << std::endl;
|
||||||
|
|
||||||
|
sif::info << std::setw(30) << std::left << "ACU VCC" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStateAcuVcc.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentAcuVcc.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltageAcuVcc.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "ACU VBAT" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStateAcuVbat.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentAcuVbat.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltageAcuVbat.value << std::endl;
|
||||||
|
|
||||||
|
sif::info << std::setw(30) << std::left << "PDU1 VCC" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStatePdu1Vcc.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentPdu1Vcc.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltagePdu1Vcc.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "PDU1 VBAT" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStatePdu1Vbat.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentPdu1Vbat.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltagePdu1Vbat.value << std::endl;
|
||||||
|
|
||||||
|
sif::info << std::setw(30) << std::left << "PDU2 VCC" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStatePdu2Vcc.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentPdu2Vcc.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltagePdu2Vcc.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "PDU2 VBAT" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStatePdu2Vbat.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentPdu2Vbat.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltagePdu2Vbat.value << std::endl;
|
||||||
|
|
||||||
|
sif::info << std::setw(30) << std::left << "Stack VBAT" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStateStackVbat.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentStackVbat.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltageStackVbat.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Stack 3V3" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStateStack3V3.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentStack3V3.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltageStack3V3.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Stack 5V" << std::dec << "| " <<
|
||||||
|
unsigned(p60dockHkTableDataset.outputEnableStateStack5V.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
p60dockHkTableDataset.currentStack5V.value << ", " << std::setw(5) <<
|
||||||
|
p60dockHkTableDataset.voltageStack5V.value << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
@ -26,6 +26,14 @@ protected:
|
|||||||
|
|
||||||
virtual void letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
virtual void letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This command handles printing the HK table to the console. This is useful for debugging
|
||||||
|
* purposes
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
ReturnValue_t printStatus(DeviceCommandId_t cmd) override;
|
||||||
|
|
||||||
|
void printHkTable();
|
||||||
private:
|
private:
|
||||||
P60Dock::HkTableDataset p60dockHkTableDataset;
|
P60Dock::HkTableDataset p60dockHkTableDataset;
|
||||||
|
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
#include <fsfw/datapool/PoolReadGuard.h>
|
#include "OBSWConfig.h"
|
||||||
#include "PDU1Handler.h"
|
#include "PDU1Handler.h"
|
||||||
#include <mission/devices/devicedefinitions/GomSpacePackets.h>
|
|
||||||
#include <OBSWConfig.h>
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
|
|
||||||
PDU1Handler::PDU1Handler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) :
|
PDU1Handler::PDU1Handler(object_id_t objectId, object_id_t comIF, CookieIF * comCookie) :
|
||||||
GomspaceDeviceHandler(objectId, comIF, comCookie, PDU::MAX_CONFIGTABLE_ADDRESS,
|
GomspaceDeviceHandler(objectId, comIF, comCookie, PDU::MAX_CONFIGTABLE_ADDRESS,
|
||||||
@ -72,27 +72,6 @@ void PDU1Handler::letChildHandleHkReply(DeviceCommandId_t id, const uint8_t *pac
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void PDU1Handler::printOutputSwitchStates() {
|
|
||||||
sif::info << "PDU1 TCS Board switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledTCSBoard3V3.value) << std::endl;
|
|
||||||
sif::info << "PDU1 Syrlinks switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledSyrlinks.value) << std::endl;
|
|
||||||
sif::info << "PDU1 star tracker switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledStarTracker.value) << std::endl;
|
|
||||||
sif::info << "PDU1 MGT switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledMGT.value) << std::endl;
|
|
||||||
sif::info << "PDU1 SUS nominal switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledSUSNominal.value) << std::endl;
|
|
||||||
sif::info << "PDU1 solar cell experiment switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledSolarCellExp.value) << std::endl;
|
|
||||||
sif::info << "PDU1 PLOC switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledPLOC.value) << std::endl;
|
|
||||||
sif::info << "PDU1 ACS Side A switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledAcsBoardSideA.value) << std::endl;
|
|
||||||
sif::info << "PDU1 channel 8 switch: " <<
|
|
||||||
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledChannel8.value) << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PDU1Handler::parseHkTableReply(const uint8_t *packet) {
|
void PDU1Handler::parseHkTableReply(const uint8_t *packet) {
|
||||||
uint16_t dataOffset = 0;
|
uint16_t dataOffset = 0;
|
||||||
PoolReadGuard pg(&pdu1HkTableDataset);
|
PoolReadGuard pg(&pdu1HkTableDataset);
|
||||||
@ -356,14 +335,14 @@ ReturnValue_t PDU1Handler::initializeLocalDataPool(
|
|||||||
|
|
||||||
ReturnValue_t PDU1Handler::printStatus(DeviceCommandId_t cmd) {
|
ReturnValue_t PDU1Handler::printStatus(DeviceCommandId_t cmd) {
|
||||||
switch(cmd) {
|
switch(cmd) {
|
||||||
case(GOMSPACE::PRINT_OUT_ENB_STATUS): {
|
case(GOMSPACE::PRINT_SWITCH_V_I): {
|
||||||
PoolReadGuard pg(&pdu1HkTableDataset);
|
PoolReadGuard pg(&pdu1HkTableDataset);
|
||||||
ReturnValue_t readResult = pg.getReadResult();
|
ReturnValue_t readResult = pg.getReadResult();
|
||||||
if(readResult != HasReturnvaluesIF::RETURN_OK) {
|
if(readResult != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::warning << "Reading PDU1 HK table failed!" << std::endl;
|
sif::warning << "Reading PDU1 HK table failed!" << std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
printOutputSwitchStates();
|
printHkTable();
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
default: {
|
default: {
|
||||||
@ -371,3 +350,53 @@ ReturnValue_t PDU1Handler::printStatus(DeviceCommandId_t cmd) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PDU1Handler::printHkTable() {
|
||||||
|
sif::info << "PDU1 Info: SwitchState, Currents [mA], Voltages [mV]" << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "TCS Board" << std::dec << "| " <<
|
||||||
|
unsigned(pdu1HkTableDataset.outEnabledTCSBoard3V3.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutTCSBoard3V3.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutTCSBoard3V3.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Syrlinks" << std::dec << "| " <<
|
||||||
|
unsigned(pdu1HkTableDataset.outEnabledSyrlinks.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutSyrlinks.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutSyrlinks.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Star Tracker" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledStarTracker.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutStarTracker.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutStarTracker.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "MGT" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledMGT.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutMGT.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutMGT.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "SuS nominal" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledSUSNominal.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutSUSNominal.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutSUSNominal.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Solar Cell Experiment" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledSolarCellExp.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutSolarCellExp.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutSolarCellExp.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "PLOC" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledPLOC.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutPLOC.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutPLOC.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "ACS Side A" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledAcsBoardSideA.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutACSBoardSideA.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutACSBoardSideA.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Channel 8" << std::dec << "| " <<
|
||||||
|
static_cast<unsigned int>(pdu1HkTableDataset.outEnabledChannel8.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu1HkTableDataset.currentOutChannel8.value << ", " << std::setw(4) <<
|
||||||
|
pdu1HkTableDataset.voltageOutChannel8.value << std::right << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
#define MISSION_DEVICES_PDU1Handler_H_
|
#define MISSION_DEVICES_PDU1Handler_H_
|
||||||
|
|
||||||
#include "GomspaceDeviceHandler.h"
|
#include "GomspaceDeviceHandler.h"
|
||||||
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
|
#include "devicedefinitions/GomspaceDefinitions.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This is the device handler for the PDU1.
|
* @brief This is the device handler for the PDU1.
|
||||||
@ -38,7 +38,7 @@ private:
|
|||||||
/** Dataset for the housekeeping table of the PDU1 */
|
/** Dataset for the housekeeping table of the PDU1 */
|
||||||
PDU1::PDU1HkTableDataset pdu1HkTableDataset;
|
PDU1::PDU1HkTableDataset pdu1HkTableDataset;
|
||||||
|
|
||||||
void printOutputSwitchStates();
|
void printHkTable();
|
||||||
void parseHkTableReply(const uint8_t *packet);
|
void parseHkTableReply(const uint8_t *packet);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -312,14 +312,14 @@ ReturnValue_t PDU2Handler::initializeLocalDataPool(
|
|||||||
|
|
||||||
ReturnValue_t PDU2Handler::printStatus(DeviceCommandId_t cmd) {
|
ReturnValue_t PDU2Handler::printStatus(DeviceCommandId_t cmd) {
|
||||||
switch(cmd) {
|
switch(cmd) {
|
||||||
case(GOMSPACE::PRINT_OUT_ENB_STATUS): {
|
case(GOMSPACE::PRINT_SWITCH_V_I): {
|
||||||
PoolReadGuard pg(&pdu2HkTableDataset);
|
PoolReadGuard pg(&pdu2HkTableDataset);
|
||||||
ReturnValue_t readResult = pg.getReadResult();
|
ReturnValue_t readResult = pg.getReadResult();
|
||||||
if(readResult != HasReturnvaluesIF::RETURN_OK) {
|
if(readResult != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::warning << "Reading PDU2 HK table failed!" << std::endl;
|
sif::warning << "Reading PDU1 HK table failed!" << std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
printOutputSwitchStates();
|
printHkTable();
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
default: {
|
default: {
|
||||||
@ -328,23 +328,51 @@ ReturnValue_t PDU2Handler::printStatus(DeviceCommandId_t cmd) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PDU2Handler::printOutputSwitchStates() {
|
void PDU2Handler::printHkTable() {
|
||||||
sif::info << "PDU2 Q7S enable state: " <<
|
sif::info << "PDU2 Info: SwitchState, Currents [mA], Voltages [mV]" << std::endl;
|
||||||
unsigned(pdu2HkTableDataset.outEnabledQ7S.value) << std::endl;
|
sif::info << std::setw(30) << std::left << "Q7S" << std::dec << "| " <<
|
||||||
sif::info << "PDU2 Payload PCDU channel 1 enable state: "
|
unsigned(pdu2HkTableDataset.outEnabledQ7S.value) << ", " <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledPlPCDUCh1.value) << std::endl;
|
std::setw(4) << std::right <<
|
||||||
sif::info << "PDU2 reaction wheels enable state: "
|
pdu2HkTableDataset.currentOutQ7S.value << ", " << std::setw(4) <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledReactionWheels.value) << std::endl;
|
pdu2HkTableDataset.voltageOutQ7S.value << std::endl;
|
||||||
sif::info << "PDU2 TCS Board 8V heater input enable state: "
|
sif::info << std::setw(30) << std::left << "Payload PCDU Channel 1" << std::dec << "| " <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledTCSBoardHeaterIn.value) << std::endl;
|
unsigned(pdu2HkTableDataset.outEnabledPlPCDUCh1.value) << ", " <<
|
||||||
sif::info << "PDU2 redundant SUS group enable state: "
|
std::setw(4) << std::right <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledSUSRedundant.value) << std::endl;
|
pdu2HkTableDataset.currentOutPayloadPCDUCh1.value << ", " << std::setw(4) <<
|
||||||
sif::info << "PDU2 deployment mechanism enable state: "
|
pdu2HkTableDataset.voltageOutPayloadPCDUCh1.value << std::endl;
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledDeplMechanism.value) << std::endl;
|
sif::info << std::setw(30) << std::left << "Reaction Wheels" << std::dec << "| " <<
|
||||||
sif::info << "PDU2 PCDU channel 6 enable state: "
|
unsigned(pdu2HkTableDataset.outEnabledReactionWheels.value) << ", " <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledPlPCDUCh6.value) << std::endl;
|
std::setw(4) << std::right <<
|
||||||
sif::info << "PDU2 ACS board side B enable state: "
|
pdu2HkTableDataset.currentOutReactionWheels.value << ", " << std::setw(4) <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledAcsBoardSideB.value) << std::endl;
|
pdu2HkTableDataset.voltageOutReactionWheels.value << std::endl;
|
||||||
sif::info << "PDU2 payload camera enable state: "
|
sif::info << std::setw(30) << std::left << "TCS Board 8V heater input" << std::dec << "| " <<
|
||||||
<< unsigned(pdu2HkTableDataset.outEnabledPayloadCamera.value) << std::endl;
|
unsigned(pdu2HkTableDataset.outEnabledTCSBoardHeaterIn.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutTCSBoardHeaterIn.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutTCSBoardHeaterIn.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Redundant SUS group" << std::dec << "| " <<
|
||||||
|
unsigned(pdu2HkTableDataset.outEnabledSUSRedundant.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutSUSRedundant.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutSUSRedundant.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Deployment mechanism" << std::dec << "| " <<
|
||||||
|
unsigned(pdu2HkTableDataset.outEnabledDeplMechanism.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutDeplMechanism.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutDeplMechanism.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Payload PCDU Channel 6" << std::dec << "| " <<
|
||||||
|
unsigned(pdu2HkTableDataset.outEnabledPlPCDUCh6.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutPayloadPCDUCh6.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutPayloadPCDUCh6.value<< std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "ACS Board Side B" << std::dec << "| " <<
|
||||||
|
unsigned(pdu2HkTableDataset.outEnabledAcsBoardSideB.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutACSBoardSideB.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutACSBoardSideB.value << std::endl;
|
||||||
|
sif::info << std::setw(30) << std::left << "Payload Camera enable state" << std::dec << "| " <<
|
||||||
|
unsigned(pdu2HkTableDataset.outEnabledPayloadCamera.value) << ", " <<
|
||||||
|
std::setw(4) << std::right <<
|
||||||
|
pdu2HkTableDataset.currentOutPayloadCamera.value << ", " << std::setw(4) <<
|
||||||
|
pdu2HkTableDataset.voltageOutPayloadCamera.value << std::right << std::endl;
|
||||||
}
|
}
|
||||||
|
@ -39,7 +39,8 @@ private:
|
|||||||
/** Dataset for the housekeeping table of the PDU2 */
|
/** Dataset for the housekeeping table of the PDU2 */
|
||||||
PDU2::PDU2HkTableDataset pdu2HkTableDataset;
|
PDU2::PDU2HkTableDataset pdu2HkTableDataset;
|
||||||
|
|
||||||
void printOutputSwitchStates();
|
void printHkTable();
|
||||||
|
|
||||||
void parseHkTableReply(const uint8_t *packet);
|
void parseHkTableReply(const uint8_t *packet);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -9,7 +9,7 @@
|
|||||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_GOMSPACEDEFINITIONS_H_
|
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_GOMSPACEDEFINITIONS_H_
|
||||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_GOMSPACEDEFINITIONS_H_
|
#define MISSION_DEVICES_DEVICEDEFINITIONS_GOMSPACEDEFINITIONS_H_
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <cstdint>
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
||||||
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
||||||
#include <fsfw/datapoollocal/LocalPoolVariable.h>
|
#include <fsfw/datapoollocal/LocalPoolVariable.h>
|
||||||
@ -33,7 +33,9 @@ static const DeviceCommandId_t GNDWDT_RESET = 9; //!< [EXPORT] : [COMMAND]
|
|||||||
static const DeviceCommandId_t PARAM_GET = 0; //!< [EXPORT] : [COMMAND]
|
static const DeviceCommandId_t PARAM_GET = 0; //!< [EXPORT] : [COMMAND]
|
||||||
static const DeviceCommandId_t PARAM_SET = 255; //!< [EXPORT] : [COMMAND]
|
static const DeviceCommandId_t PARAM_SET = 255; //!< [EXPORT] : [COMMAND]
|
||||||
static const DeviceCommandId_t REQUEST_HK_TABLE = 16; //!< [EXPORT] : [COMMAND]
|
static const DeviceCommandId_t REQUEST_HK_TABLE = 16; //!< [EXPORT] : [COMMAND]
|
||||||
static const DeviceCommandId_t PRINT_OUT_ENB_STATUS = 17; //!< [EXPORT] : [COMMAND]
|
//!< [EXPORT] : [COMMAND] Print switch states, voltages and currents to the console
|
||||||
|
static const DeviceCommandId_t PRINT_SWITCH_V_I = 32;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -377,6 +379,9 @@ static const uint16_t HK_TABLE_REPLY_SIZE = 407;
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This class defines a dataset for the hk table of the P60 Dock.
|
* @brief This class defines a dataset for the hk table of the P60 Dock.
|
||||||
|
* @details
|
||||||
|
* The GS port and X3 are not required for EIVE. X3 is another slot on the P60 dock and
|
||||||
|
* GS is required for a module from Gomspace which is not used.
|
||||||
*/
|
*/
|
||||||
class HkTableDataset:
|
class HkTableDataset:
|
||||||
public StaticLocalDataSet<HK_TABLE_ENTRIES> {
|
public StaticLocalDataSet<HK_TABLE_ENTRIES> {
|
||||||
|
@ -1,178 +0,0 @@
|
|||||||
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERLIS3DEFINITIONS_H_
|
|
||||||
#define MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERLIS3DEFINITIONS_H_
|
|
||||||
|
|
||||||
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
|
|
||||||
#include <fsfw/datapoollocal/LocalPoolVariable.h>
|
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
|
|
||||||
#include <cstdint>
|
|
||||||
|
|
||||||
namespace MGMLIS3MDL {
|
|
||||||
|
|
||||||
enum Set {
|
|
||||||
ON, OFF
|
|
||||||
};
|
|
||||||
enum OpMode {
|
|
||||||
LOW, MEDIUM, HIGH, ULTRA
|
|
||||||
};
|
|
||||||
|
|
||||||
enum Sensitivies: uint8_t {
|
|
||||||
GAUSS_4 = 4,
|
|
||||||
GAUSS_8 = 8,
|
|
||||||
GAUSS_12 = 12,
|
|
||||||
GAUSS_16 = 16
|
|
||||||
};
|
|
||||||
|
|
||||||
/* Actually 15, we just round up a bit */
|
|
||||||
static constexpr size_t MAX_BUFFER_SIZE = 16;
|
|
||||||
|
|
||||||
/* Field data register scaling */
|
|
||||||
static constexpr uint8_t GAUSS_TO_MICROTESLA_FACTOR = 100;
|
|
||||||
static constexpr float FIELD_LSB_PER_GAUSS_4_SENS = 1.0 / 6842.0;
|
|
||||||
static constexpr float FIELD_LSB_PER_GAUSS_8_SENS = 1.0 / 3421.0;
|
|
||||||
static constexpr float FIELD_LSB_PER_GAUSS_12_SENS = 1.0 / 2281.0;
|
|
||||||
static constexpr float FIELD_LSB_PER_GAUSS_16_SENS = 1.0 / 1711.0;
|
|
||||||
|
|
||||||
static const DeviceCommandId_t READ_CONFIG_AND_DATA = 0x00;
|
|
||||||
static const DeviceCommandId_t SETUP_MGM = 0x01;
|
|
||||||
static const DeviceCommandId_t READ_TEMPERATURE = 0x02;
|
|
||||||
static const DeviceCommandId_t IDENTIFY_DEVICE = 0x03;
|
|
||||||
static const DeviceCommandId_t TEMP_SENSOR_ENABLE = 0x04;
|
|
||||||
static const DeviceCommandId_t ACCURACY_OP_MODE_SET = 0x05;
|
|
||||||
|
|
||||||
/* Number of all control registers */
|
|
||||||
static const uint8_t NR_OF_CTRL_REGISTERS = 5;
|
|
||||||
/* Number of registers in the MGM */
|
|
||||||
static const uint8_t NR_OF_REGISTERS = 19;
|
|
||||||
/* Total number of adresses for all registers */
|
|
||||||
static const uint8_t TOTAL_NR_OF_ADRESSES = 52;
|
|
||||||
static const uint8_t NR_OF_DATA_AND_CFG_REGISTERS = 14;
|
|
||||||
static const uint8_t TEMPERATURE_REPLY_LEN = 3;
|
|
||||||
static const uint8_t SETUP_REPLY_LEN = 6;
|
|
||||||
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* Register adresses */
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* Register adress returns identifier of device with default 0b00111101 */
|
|
||||||
static const uint8_t IDENTIFY_DEVICE_REG_ADDR = 0b00001111;
|
|
||||||
static const uint8_t DEVICE_ID = 0b00111101; // Identifier for Device
|
|
||||||
|
|
||||||
/* Register adress to access register 1 */
|
|
||||||
static const uint8_t CTRL_REG1 = 0b00100000;
|
|
||||||
/* Register adress to access register 2 */
|
|
||||||
static const uint8_t CTRL_REG2 = 0b00100001;
|
|
||||||
/* Register adress to access register 3 */
|
|
||||||
static const uint8_t CTRL_REG3 = 0b00100010;
|
|
||||||
/* Register adress to access register 4 */
|
|
||||||
static const uint8_t CTRL_REG4 = 0b00100011;
|
|
||||||
/* Register adress to access register 5 */
|
|
||||||
static const uint8_t CTRL_REG5 = 0b00100100;
|
|
||||||
|
|
||||||
/* Register adress to access status register */
|
|
||||||
static const uint8_t STATUS_REG_IDX = 8;
|
|
||||||
static const uint8_t STATUS_REG = 0b00100111;
|
|
||||||
|
|
||||||
/* Register adress to access low byte of x-axis */
|
|
||||||
static const uint8_t X_LOWBYTE_IDX = 9;
|
|
||||||
static const uint8_t X_LOWBYTE = 0b00101000;
|
|
||||||
/* Register adress to access high byte of x-axis */
|
|
||||||
static const uint8_t X_HIGHBYTE_IDX = 10;
|
|
||||||
static const uint8_t X_HIGHBYTE = 0b00101001;
|
|
||||||
/* Register adress to access low byte of y-axis */
|
|
||||||
static const uint8_t Y_LOWBYTE_IDX = 11;
|
|
||||||
static const uint8_t Y_LOWBYTE = 0b00101010;
|
|
||||||
/* Register adress to access high byte of y-axis */
|
|
||||||
static const uint8_t Y_HIGHBYTE_IDX = 12;
|
|
||||||
static const uint8_t Y_HIGHBYTE = 0b00101011;
|
|
||||||
/* Register adress to access low byte of z-axis */
|
|
||||||
static const uint8_t Z_LOWBYTE_IDX = 13;
|
|
||||||
static const uint8_t Z_LOWBYTE = 0b00101100;
|
|
||||||
/* Register adress to access high byte of z-axis */
|
|
||||||
static const uint8_t Z_HIGHBYTE_IDX = 14;
|
|
||||||
static const uint8_t Z_HIGHBYTE = 0b00101101;
|
|
||||||
|
|
||||||
/* Register adress to access low byte of temperature sensor */
|
|
||||||
static const uint8_t TEMP_LOWBYTE = 0b00101110;
|
|
||||||
/* Register adress to access high byte of temperature sensor */
|
|
||||||
static const uint8_t TEMP_HIGHBYTE = 0b00101111;
|
|
||||||
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* Initialize Setup Register set bits */
|
|
||||||
/*------------------------------------------------------------------------*/
|
|
||||||
/* General transfer bits */
|
|
||||||
// Read=1 / Write=0 Bit
|
|
||||||
static const uint8_t RW_BIT = 7;
|
|
||||||
// Continous Read/Write Bit, increment adress
|
|
||||||
static const uint8_t MS_BIT = 6;
|
|
||||||
|
|
||||||
/* CTRL_REG1 bits */
|
|
||||||
static const uint8_t ST = 0; // Self test enable bit, enabled = 1
|
|
||||||
// Enable rates higher than 80 Hz enabled = 1
|
|
||||||
static const uint8_t FAST_ODR = 1;
|
|
||||||
static const uint8_t DO0 = 2; // Output data rate bit 2
|
|
||||||
static const uint8_t DO1 = 3; // Output data rate bit 3
|
|
||||||
static const uint8_t DO2 = 4; // Output data rate bit 4
|
|
||||||
static const uint8_t OM0 = 5; // XY operating mode bit 5
|
|
||||||
static const uint8_t OM1 = 6; // XY operating mode bit 6
|
|
||||||
static const uint8_t TEMP_EN = 7; // Temperature sensor enable enabled = 1
|
|
||||||
static const uint8_t CTRL_REG1_DEFAULT = (1 << TEMP_EN) | (1 << OM1) |
|
|
||||||
(1 << DO0) | (1 << DO1) | (1 << DO2);
|
|
||||||
|
|
||||||
/* CTRL_REG2 bits */
|
|
||||||
//reset configuration registers and user registers
|
|
||||||
static const uint8_t SOFT_RST = 2;
|
|
||||||
static const uint8_t REBOOT = 3; //reboot memory content
|
|
||||||
static const uint8_t FSO = 5; //full-scale selection bit 5
|
|
||||||
static const uint8_t FS1 = 6; //full-scale selection bit 6
|
|
||||||
static const uint8_t CTRL_REG2_DEFAULT = 0;
|
|
||||||
|
|
||||||
/* CTRL_REG3 bits */
|
|
||||||
static const uint8_t MD0 = 0; //Operating mode bit 0
|
|
||||||
static const uint8_t MD1 = 1; //Operating mode bit 1
|
|
||||||
//SPI serial interface mode selection enabled = 3-wire-mode
|
|
||||||
static const uint8_t SIM = 2;
|
|
||||||
static const uint8_t LP = 5; //low-power mode
|
|
||||||
static const uint8_t CTRL_REG3_DEFAULT = 0;
|
|
||||||
|
|
||||||
/* CTRL_REG4 bits */
|
|
||||||
//big/little endian data selection enabled = MSb at lower adress
|
|
||||||
static const uint8_t BLE = 1;
|
|
||||||
static const uint8_t OMZ0 = 2; //Z operating mode bit 2
|
|
||||||
static const uint8_t OMZ1 = 3; //Z operating mode bit 3
|
|
||||||
static const uint8_t CTRL_REG4_DEFAULT = (1 << OMZ1);
|
|
||||||
|
|
||||||
/* CTRL_REG5 bits */
|
|
||||||
static const uint8_t BDU = 6; //Block data update
|
|
||||||
static const uint8_t FAST_READ = 7; //Fast read enabled = 1
|
|
||||||
static const uint8_t CTRL_REG5_DEFAULT = 0;
|
|
||||||
|
|
||||||
static const uint32_t MGM_DATA_SET_ID = READ_CONFIG_AND_DATA;
|
|
||||||
|
|
||||||
enum MgmPoolIds: lp_id_t {
|
|
||||||
FIELD_STRENGTH_X,
|
|
||||||
FIELD_STRENGTH_Y,
|
|
||||||
FIELD_STRENGTH_Z,
|
|
||||||
TEMPERATURE_CELCIUS
|
|
||||||
};
|
|
||||||
|
|
||||||
class MgmPrimaryDataset: public StaticLocalDataSet<5> {
|
|
||||||
public:
|
|
||||||
MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner):
|
|
||||||
StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {}
|
|
||||||
|
|
||||||
MgmPrimaryDataset(object_id_t mgmId):
|
|
||||||
StaticLocalDataSet(sid_t(mgmId, MGM_DATA_SET_ID)) {}
|
|
||||||
|
|
||||||
lp_var_t<float> fieldStrengthX = lp_var_t<float>(sid.objectId,
|
|
||||||
FIELD_STRENGTH_X, this);
|
|
||||||
lp_var_t<float> fieldStrengthY = lp_var_t<float>(sid.objectId,
|
|
||||||
FIELD_STRENGTH_Y, this);
|
|
||||||
lp_var_t<float> fieldStrengthZ = lp_var_t<float>(sid.objectId,
|
|
||||||
FIELD_STRENGTH_Z, this);
|
|
||||||
lp_var_t<float> temperature = lp_var_t<float>(sid.objectId,
|
|
||||||
TEMPERATURE_CELCIUS, this);
|
|
||||||
};
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERLIS3DEFINITIONS_H_ */
|
|
2
tmtc
2
tmtc
@ -1 +1 @@
|
|||||||
Subproject commit b3bc1fe28c73d51f0b8319cf67705807596e5518
|
Subproject commit 53bf65083889af10f77c3899972b1153ea835f3c
|
Loading…
Reference in New Issue
Block a user