GPIO hal update
All checks were successful
EIVE/eive-obsw/pipeline/head This commit looks good

This commit is contained in:
Robin Müller 2022-02-28 15:47:34 +01:00
parent 6b88c525b2
commit 54640147c1
No known key found for this signature in database
GPG Key ID: 11D4952C8CCEF814
6 changed files with 178 additions and 162 deletions

View File

@ -12,6 +12,7 @@ namespace gpioCallbacks {
GpioIF* gpioComInterface;
void initSpiCsDecoder(GpioIF* gpioComIF) {
using namespace gpio;
ReturnValue_t result;
if (gpioComIF == nullptr) {
@ -26,29 +27,29 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
GpiodRegularByLineName* spiMuxBit = nullptr;
/** Setting mux bit 1 to low will disable IC21 on the interface board */
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_0_PIN, "SPI Mux Bit 1",
gpio::DIR_OUT, gpio::HIGH);
Direction::OUT, Levels::HIGH);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_0, spiMuxBit);
/** Setting mux bit 2 to low disables IC1 on the TCS board */
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_1_PIN, "SPI Mux Bit 2",
gpio::DIR_OUT, gpio::HIGH);
Direction::OUT, Levels::HIGH);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit);
/** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_2_PIN, "SPI Mux Bit 3",
gpio::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit);
/** The following gpios can take arbitrary initial values */
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_3_PIN, "SPI Mux Bit 4",
gpio::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit);
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_4_PIN, "SPI Mux Bit 5",
gpio::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_4, spiMuxBit);
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_5_PIN, "SPI Mux Bit 6",
gpio::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_5, spiMuxBit);
GpiodRegularByLineName* enRwDecoder =
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_CS, "EN_RW_CS", gpio::DIR_OUT, gpio::HIGH);
GpiodRegularByLineName* enRwDecoder = new GpiodRegularByLineName(
q7s::gpioNames::EN_RW_CS, "EN_RW_CS", Direction::OUT, Levels::HIGH);
spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder);
result = gpioComInterface->addGpios(spiMuxGpios);
@ -60,6 +61,7 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value,
void* args) {
using namespace gpio;
if (gpioComInterface == nullptr) {
sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder "
<< "to specify gpioComIF" << std::endl;
@ -71,7 +73,7 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Lev
return;
}
if (value == gpio::HIGH) {
if (value == Levels::HIGH) {
switch (gpioId) {
case (gpioIds::RTD_IC_3): {
disableDecoderTcsIc1();
@ -204,7 +206,7 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Lev
default:
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
}
} else if (value == gpio::LOW) {
} else if (value == Levels::LOW) {
switch (gpioId) {
case (gpioIds::RTD_IC_3): {
selectY7();

View File

@ -266,7 +266,7 @@ void initmission::createPstTasks(TaskFactory& factory,
sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl;
}
taskVec.push_back(gomSpacePstTask);
#else /* BOARD_TE7020 == 0 */
#else /* BOARD_TE7020 == 0 */
FixedTimeslotTaskIF* pollingSequenceTaskTE0720 = factory.createFixedTimeslotTask(
"PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0, missedDeadlineFunc);
result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720);

View File

@ -288,14 +288,15 @@ void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF) {
}
void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) {
using namespace gpio;
GpioCookie* gpioCookieRadSensor = new GpioCookie;
std::stringstream consumer;
consumer << "0x" << std::hex << objects::RAD_SENSOR;
GpiodRegularByLineName* gpio = new GpiodRegularByLineName(
q7s::gpioNames::RAD_SENSOR_CHIP_SELECT, consumer.str(), gpio::DIR_OUT, gpio::HIGH);
q7s::gpioNames::RAD_SENSOR_CHIP_SELECT, consumer.str(), Direction::OUT, Levels::HIGH);
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_RADFET, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_RADFET, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieRadSensor->addGpio(gpioIds::ENABLE_RADFET, gpio);
gpioComIF->addGpios(gpioCookieRadSensor);
@ -312,43 +313,44 @@ void ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) {
}
void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) {
using namespace gpio;
GpioCookie* gpioCookieSus = new GpioCookie();
GpioCallback* susgpio = nullptr;
susgpio = new GpioCallback("Chip select SUS 0", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 0", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_0, susgpio);
susgpio = new GpioCallback("Chip select SUS 1", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 1", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_1, susgpio);
susgpio = new GpioCallback("Chip select SUS 2", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 2", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_2, susgpio);
susgpio = new GpioCallback("Chip select SUS 3", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 3", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_3, susgpio);
susgpio = new GpioCallback("Chip select SUS 4", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 4", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_4, susgpio);
susgpio = new GpioCallback("Chip select SUS 5", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 5", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_5, susgpio);
susgpio = new GpioCallback("Chip select SUS 6", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 6", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_6, susgpio);
susgpio = new GpioCallback("Chip select SUS 7", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 7", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_7, susgpio);
susgpio = new GpioCallback("Chip select SUS 8", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 8", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_8, susgpio);
susgpio = new GpioCallback("Chip select SUS 9", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 9", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_9, susgpio);
susgpio = new GpioCallback("Chip select SUS 10", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 10", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_10, susgpio);
susgpio = new GpioCallback("Chip select SUS 11", gpio::DIR_OUT, gpio::HIGH,
susgpio = new GpioCallback("Chip select SUS 11", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio);
@ -472,101 +474,102 @@ void ObjectFactory::createSunSensorComponents(LinuxLibgpioIF* gpioComIF, SpiComI
}
void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF) {
using namespace gpio;
GpioCookie* gpioCookieAcsBoard = new GpioCookie();
std::stringstream consumer;
GpiodRegularByLineName* gpio = nullptr;
consumer << "0x" << std::hex << objects::GYRO_0_ADIS_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GYRO_1_L3G_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GYRO_2_ADIS_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GYRO_3_L3G_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::MGM_0_LIS3_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::MGM_1_RM3100_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::MGM_2_LIS3_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::MGM_3_RM3100_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_3_CS, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_3_CS, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
// GNSS reset pins are active low
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_0, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_0, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_1, consumer.str(), gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_1, consumer.str(), Direction::OUT,
Levels::HIGH);
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GYRO_0_ADIS_HANDLER;
// Enable pins must be pulled low for regular operations
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GYRO_2_ADIS_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ENABLE, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ENABLE, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieAcsBoard->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
// Enable pins for GNSS
consumer.str("");
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_0_ENABLE, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_0_ENABLE, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_ENABLE, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_1_ENABLE, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_1_ENABLE, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_ENABLE, gpio);
// Select pin. 0 for GPS side A, 1 for GPS side B
consumer.str("");
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_SELECT, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_SELECT, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_SELECT, gpio);
gpioComIF->addGpios(gpioCookieAcsBoard);
@ -693,43 +696,44 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI
}
void ObjectFactory::createHeaterComponents() {
using namespace gpio;
GpioCookie* heaterGpiosCookie = new GpioCookie;
GpiodRegularByLineName* gpio = nullptr;
std::stringstream consumer;
consumer << "0x" << std::hex << objects::HEATER_HANDLER;
/* Pin H2-11 on stack connector */
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_0, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_0, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_0, gpio);
/* Pin H2-12 on stack connector */
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_1, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_1, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_1, gpio);
/* Pin H2-13 on stack connector */
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_2, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_2, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_2, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_3, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_3, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_3, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_4, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_4, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_4, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_5, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_5, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_5, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_6, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_6, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_6, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_7, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::HEATER_7, consumer.str(), Direction::OUT,
Levels::LOW);
heaterGpiosCookie->addGpio(gpioIds::HEATER_7, gpio);
new HeaterHandler(objects::HEATER_HANDLER, objects::GPIO_IF, heaterGpiosCookie,
@ -737,16 +741,17 @@ void ObjectFactory::createHeaterComponents() {
}
void ObjectFactory::createSolarArrayDeploymentComponents() {
using namespace gpio;
GpioCookie* solarArrayDeplCookie = new GpioCookie;
GpiodRegularByLineName* gpio = nullptr;
std::stringstream consumer;
consumer << "0x" << std::hex << objects::SOLAR_ARRAY_DEPL_HANDLER;
gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_0, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_0, consumer.str(), Direction::OUT,
Levels::LOW);
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA1, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_1, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::SA_DPL_PIN_1, consumer.str(), Direction::OUT,
Levels::LOW);
solarArrayDeplCookie->addGpio(gpioIds::DEPLSA2, gpio);
// TODO: Find out burn time. For now set to 1000 ms.
@ -766,54 +771,55 @@ void ObjectFactory::createSyrlinksComponents() {
}
void ObjectFactory::createRtdComponents(LinuxLibgpioIF* gpioComIF) {
using namespace gpio;
GpioCookie* rtdGpioCookie = new GpioCookie;
GpioCallback* gpioRtdIc0 = new GpioCallback("Chip select RTD IC0", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc0 = new GpioCallback("Chip select RTD IC0", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_3, gpioRtdIc0);
GpioCallback* gpioRtdIc1 = new GpioCallback("Chip select RTD IC1", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc1 = new GpioCallback("Chip select RTD IC1", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_4, gpioRtdIc1);
GpioCallback* gpioRtdIc2 = new GpioCallback("Chip select RTD IC2", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc2 = new GpioCallback("Chip select RTD IC2", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_5, gpioRtdIc2);
GpioCallback* gpioRtdIc3 = new GpioCallback("Chip select RTD IC3", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc3 = new GpioCallback("Chip select RTD IC3", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_6, gpioRtdIc3);
GpioCallback* gpioRtdIc4 = new GpioCallback("Chip select RTD IC4", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc4 = new GpioCallback("Chip select RTD IC4", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_7, gpioRtdIc4);
GpioCallback* gpioRtdIc5 = new GpioCallback("Chip select RTD IC5", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc5 = new GpioCallback("Chip select RTD IC5", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_8, gpioRtdIc5);
GpioCallback* gpioRtdIc6 = new GpioCallback("Chip select RTD IC6", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc6 = new GpioCallback("Chip select RTD IC6", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_9, gpioRtdIc6);
GpioCallback* gpioRtdIc7 = new GpioCallback("Chip select RTD IC7", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc7 = new GpioCallback("Chip select RTD IC7", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_10, gpioRtdIc7);
GpioCallback* gpioRtdIc8 = new GpioCallback("Chip select RTD IC8", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc8 = new GpioCallback("Chip select RTD IC8", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_11, gpioRtdIc8);
GpioCallback* gpioRtdIc9 = new GpioCallback("Chip select RTD IC9", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc9 = new GpioCallback("Chip select RTD IC9", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_12, gpioRtdIc9);
GpioCallback* gpioRtdIc10 = new GpioCallback("Chip select RTD IC10", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc10 = new GpioCallback("Chip select RTD IC10", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_13, gpioRtdIc10);
GpioCallback* gpioRtdIc11 = new GpioCallback("Chip select RTD IC11", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc11 = new GpioCallback("Chip select RTD IC11", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_14, gpioRtdIc11);
GpioCallback* gpioRtdIc12 = new GpioCallback("Chip select RTD IC12", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc12 = new GpioCallback("Chip select RTD IC12", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_15, gpioRtdIc12);
GpioCallback* gpioRtdIc13 = new GpioCallback("Chip select RTD IC13", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc13 = new GpioCallback("Chip select RTD IC13", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_16, gpioRtdIc13);
GpioCallback* gpioRtdIc14 = new GpioCallback("Chip select RTD IC14", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc14 = new GpioCallback("Chip select RTD IC14", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_17, gpioRtdIc14);
GpioCallback* gpioRtdIc15 = new GpioCallback("Chip select RTD IC15", gpio::DIR_OUT, gpio::HIGH,
GpioCallback* gpioRtdIc15 = new GpioCallback("Chip select RTD IC15", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_18, gpioRtdIc15);
@ -958,40 +964,45 @@ void ObjectFactory::createRtdComponents(LinuxLibgpioIF* gpioComIF) {
}
void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
using namespace gpio;
GpioCookie* gpioCookieRw = new GpioCookie;
GpioCallback* csRw1 = new GpioCallback("Chip select reaction wheel 1", gpio::DIR_OUT, gpio::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
GpioCallback* csRw1 =
new GpioCallback("Chip select reaction wheel 1", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieRw->addGpio(gpioIds::CS_RW1, csRw1);
GpioCallback* csRw2 = new GpioCallback("Chip select reaction wheel 2", gpio::DIR_OUT, gpio::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
GpioCallback* csRw2 =
new GpioCallback("Chip select reaction wheel 2", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieRw->addGpio(gpioIds::CS_RW2, csRw2);
GpioCallback* csRw3 = new GpioCallback("Chip select reaction wheel 3", gpio::DIR_OUT, gpio::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
GpioCallback* csRw3 =
new GpioCallback("Chip select reaction wheel 3", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieRw->addGpio(gpioIds::CS_RW3, csRw3);
GpioCallback* csRw4 = new GpioCallback("Chip select reaction wheel 4", gpio::DIR_OUT, gpio::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
GpioCallback* csRw4 =
new GpioCallback("Chip select reaction wheel 4", Direction::OUT, Levels::HIGH,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieRw->addGpio(gpioIds::CS_RW4, csRw4);
std::stringstream consumer;
GpiodRegularByLineName* gpio = nullptr;
consumer << "0x" << std::hex << objects::RW1;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_1, consumer.str(), gpio::DIR_OUT, gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_1, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieRw->addGpio(gpioIds::EN_RW1, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::RW2;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_2, consumer.str(), gpio::DIR_OUT, gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_2, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieRw->addGpio(gpioIds::EN_RW2, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::RW3;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_3, consumer.str(), gpio::DIR_OUT, gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_3, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieRw->addGpio(gpioIds::EN_RW3, gpio);
consumer.str("");
consumer << "0x" << std::hex << objects::RW4;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_4, consumer.str(), gpio::DIR_OUT, gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_4, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookieRw->addGpio(gpioIds::EN_RW4, gpio);
gpioComIF->addGpios(gpioCookieRw);
@ -1043,6 +1054,7 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
}
void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
using namespace gpio;
// GPIO definitions of signals connected to the virtual channel interfaces of the PTME IP Core
GpioCookie* gpioCookiePtmeIp = new GpioCookie;
GpiodRegularByLineName* gpio = nullptr;
@ -1120,8 +1132,8 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
consumer.str("");
consumer << "0x" << std::hex << objects::PDEC_HANDLER;
// GPIO also low after linux boot (specified by device-tree)
gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::PDEC_RESET, consumer.str(), Direction::OUT,
Levels::LOW);
gpioCookiePdec->addGpio(gpioIds::PDEC_RESET, gpio);
gpioComIF->addGpios(gpioCookiePdec);
@ -1132,18 +1144,18 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
#if BOARD_TE0720 == 0
GpioCookie* gpioRS485Chip = new GpioCookie;
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_CLOCK, "RS485 Transceiver",
gpio::Direction::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_CLOCK, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_TX_DATA, "RS485 Transceiver",
gpio::Direction::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
gpioRS485Chip->addGpio(gpioIds::RS485_EN_TX_DATA, gpio);
// Default configuration enables RX channels (RXEN = LOW)
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_CLOCK, "RS485 Transceiver",
gpio::Direction::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_CLOCK, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::RS485_EN_RX_DATA, "RS485 Transceiver",
gpio::Direction::DIR_OUT, gpio::LOW);
Direction::OUT, Levels::LOW);
gpioRS485Chip->addGpio(gpioIds::RS485_EN_RX_DATA, gpio);
gpioComIF->addGpios(gpioRS485Chip);
@ -1151,44 +1163,45 @@ void ObjectFactory::createCcsdsComponents(LinuxLibgpioIF* gpioComIF) {
}
void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF) {
using namespace gpio;
// Create all GPIO components first
GpioCookie* plPcduGpios = new GpioCookie;
GpiodRegularByLineName* gpio = nullptr;
std::string consumer;
// Switch pins are active high
consumer = "PLPCDU_ENB_VBAT_0";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT0, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT0, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_VBAT0, gpio);
consumer = "PLPCDU_ENB_VBAT_1";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT1, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_VBAT1, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_VBAT1, gpio);
consumer = "PLPCDU_ENB_DRO";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_DRO, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_DRO, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_DRO, gpio);
consumer = "PLPCDU_ENB_HPA";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_HPA, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_HPA, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_HPA, gpio);
consumer = "PLPCDU_ENB_MPA";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_MPA, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_MPA, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_MPA, gpio);
consumer = "PLPCDU_ENB_X8";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_X8, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_X8, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_X8, gpio);
consumer = "PLPCDU_ENB_TX";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_TX, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ENABLE_TX, consumer, Direction::OUT,
gpio::Levels::LOW);
plPcduGpios->addGpio(gpioIds::PLPCDU_ENB_TX, gpio);
// Chip select pin is active low
consumer = "PLPCDU_ADC_CS";
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ADC_CS, consumer, gpio::DIR_OUT,
gpio = new GpiodRegularByLineName(q7s::gpioNames::PL_PCDU_ADC_CS, consumer, Direction::OUT,
gpio::Levels::HIGH);
plPcduGpios->addGpio(gpioIds::PLPCDU_ADC_CS, gpio);
gpioComIF->addGpios(plPcduGpios);
@ -1202,10 +1215,10 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) {
#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1
#if OBSW_TEST_GPIO_OPEN_BYLABEL == 1
/* Configure MIO0 as input */
GpiodRegular* testGpio = new GpiodRegular("MIO0", gpio::DIR_OUT, 0, "/amba_pl/gpio@41200000", 0);
GpiodRegular* testGpio = new GpiodRegular("MIO0", Direction::OUT, 0, "/amba_pl/gpio@41200000", 0);
#elif OBSW_TEST_GPIO_OPEN_BY_LINE_NAME
GpiodRegularByLineName* testGpio =
new GpiodRegularByLineName("test-name", "gpio-test", gpio::DIR_OUT, 0);
new GpiodRegularByLineName("test-name", "gpio-test", Direction::OUT, 0);
#else
/* Configure MIO0 as input */
GpiodRegular* testGpio = new GpiodRegular("gpiochip0", 0, "MIO0", gpio::IN, 0);
@ -1218,7 +1231,7 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) {
#if BOARD_TE0720 == 1 && OBSW_TEST_SUS == 1
GpioCookie* gpioCookieSus = new GpioCookie;
GpiodRegular* chipSelectSus = new GpiodRegular(
std::string("gpiochip1"), 9, std::string("Chip Select Sus Sensor"), gpio::DIR_OUT, 1);
std::string("gpiochip1"), 9, std::string("Chip Select Sus Sensor"), Direction::OUT, 1);
gpioCookieSus->addGpio(gpioIds::CS_SUS_0, chipSelectSus);
gpioComIF->addGpios(gpioCookieSus);
@ -1247,7 +1260,7 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) {
#if BOARD_TE0720 == 1 && OBSW_TEST_RAD_SENSOR == 1
GpioCookie* gpioCookieRadSensor = new GpioCookie;
GpiodRegular* chipSelectRadSensor = new GpiodRegular(
std::string("gpiochip1"), 0, std::string("Chip select radiation sensor"), gpio::DIR_OUT, 1);
std::string("gpiochip1"), 0, std::string("Chip select radiation sensor"), Direction::OUT, 1);
gpioCookieRadSensor->addGpio(gpioIds::CS_RAD_SENSOR, chipSelectRadSensor);
gpioComIF->addGpios(gpioCookieRadSensor);

2
fsfw

@ -1 +1 @@
Subproject commit eacb4ac4079ff2bf5e0648626332e59046a409da
Subproject commit 2d9216ba19f1931225daa5b6b6f244a48c09f1b9

View File

@ -640,72 +640,73 @@ void SpiTestClass::max1227PlPcduTest(int fd) {
}
void SpiTestClass::acsInit() {
using namespace gpio;
GpioCookie *gpioCookie = new GpioCookie();
#ifdef RASPBERRY_PI
GpiodRegularByChip *gpio = nullptr;
std::string rpiGpioName = "gpiochip0";
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
#elif defined(XIPHOS_Q7S)
GpiodRegularByLineName *gpio = nullptr;
gpio =
new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, "MGM_0_LIS3", gpio::DIR_OUT, gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_0_CS, "MGM_0_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_1_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_1_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
gpio =
new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, "MGM_2_LIS3", gpio::DIR_OUT, gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_2_CS, "MGM_2_LIS3", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_3_RM3100", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::MGM_1_CS, "MGM_3_RM3100", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, "GYRO_0_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ADIS_CS, "GYRO_0_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, "GYRO_1_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_1_L3G_CS, "GYRO_1_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, "GYRO_2_ADIS", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_2_ADIS_CS, "GYRO_2_ADIS", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_2_ADIS_CS, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, "GYRO_3_L3G", gpio::DIR_OUT,
gpio::HIGH);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_3_L3G_CS, "GYRO_3_L3G", Direction::OUT,
Levels::HIGH);
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
// Enable pins must be pulled low for regular operations
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_0_ENABLE", gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_0_ENABLE", Direction::OUT,
Levels::LOW);
gpioCookie->addGpio(gpioIds::GYRO_0_ENABLE, gpio);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_2_ENABLE", gpio::DIR_OUT,
gpio::LOW);
gpio = new GpiodRegularByLineName(q7s::gpioNames::GYRO_0_ENABLE, "GYRO_2_ENABLE", Direction::OUT,
Levels::LOW);
gpioCookie->addGpio(gpioIds::GYRO_2_ENABLE, gpio);
#endif
if (gpioIF != nullptr) {

2
tmtc

@ -1 +1 @@
Subproject commit 85b5c756ea395155eff5b7cc2f4777ce62e45aa7
Subproject commit 56d414d9fc0d6b05f967c47a0bd124fc06de2ad3