working SUS in externally clocked mode

This commit is contained in:
Jakob Meier 2021-05-09 16:48:55 +02:00
parent 906c813e4c
commit 189bdb7c90
6 changed files with 170 additions and 129 deletions

View File

@ -209,43 +209,43 @@ void ObjectFactory::produce(){
SpiCookie* spiCookieSus1 = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, SpiCookie* spiCookieSus1 = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus2 = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, SpiCookie* spiCookieSus2 = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus3 = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, SpiCookie* spiCookieSus3 = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus4 = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, SpiCookie* spiCookieSus4 = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus5 = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, SpiCookie* spiCookieSus5 = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus6 = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, SpiCookie* spiCookieSus6 = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus7 = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, SpiCookie* spiCookieSus7 = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus8 = new SpiCookie(addresses::SUS_8, gpio::NO_GPIO, SpiCookie* spiCookieSus8 = new SpiCookie(addresses::SUS_8, gpio::NO_GPIO,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus9 = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, SpiCookie* spiCookieSus9 = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus10 = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, SpiCookie* spiCookieSus10 = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus11 = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, SpiCookie* spiCookieSus11 = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus12 = new SpiCookie(addresses::SUS_12, gpioIds::CS_SUS_12, SpiCookie* spiCookieSus12 = new SpiCookie(addresses::SUS_12, gpioIds::CS_SUS_12,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SpiCookie* spiCookieSus13 = new SpiCookie(addresses::SUS_13, gpioIds::CS_SUS_13, SpiCookie* spiCookieSus13 = new SpiCookie(addresses::SUS_13, gpioIds::CS_SUS_13,
std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE, std::string("/dev/spidev2.0"), SUS::MAX_CMD_SIZE, spi::DEFAULT_MAX_1227_MODE,
spi::DEFAULT_MAX_1227_SPEED); SUS::SUS_MAX_1227_SPEED);
SusHandler* sus1 = new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus1, gpioComIF, SusHandler* sus1 = new SusHandler(objects::SUS_1, objects::SPI_COM_IF, spiCookieSus1, gpioComIF,
gpioIds::CS_SUS_1); gpioIds::CS_SUS_1);

View File

@ -20,8 +20,7 @@ static constexpr spi::SpiModes DEFAULT_RM3100_MODE = spi::SpiModes::MODE_3;
static constexpr uint32_t DEFAULT_L3G_SPEED = 3'900'000; static constexpr uint32_t DEFAULT_L3G_SPEED = 3'900'000;
static constexpr spi::SpiModes DEFAULT_L3G_MODE = spi::SpiModes::MODE_3; static constexpr spi::SpiModes DEFAULT_L3G_MODE = spi::SpiModes::MODE_3;
//static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 3'900'000; static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 3'900'000;
static constexpr uint32_t DEFAULT_MAX_1227_SPEED = 1000000;
static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_0; static constexpr spi::SpiModes DEFAULT_MAX_1227_MODE = spi::SpiModes::MODE_0;
} }

View File

@ -157,11 +157,47 @@ ReturnValue_t pst::pollingSequenceInitDefault(FixedTimeslotTaskIF *thisSequence)
// thisSequence->addSlot(objects::SUS_1, length * 0.6, DeviceHandlerIF::SEND_READ); // thisSequence->addSlot(objects::SUS_1, length * 0.6, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::SUS_1, length * 0.8, DeviceHandlerIF::GET_READ); // thisSequence->addSlot(objects::SUS_1, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION); if (length != 3) {
thisSequence->addSlot(objects::SUS_8, length * 0.2, DeviceHandlerIF::SEND_WRITE); sif::waring << "pollingSequenceInitDefault: Frequency changed. Make sure timing critical "
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_WRITE); << "SUS sensors still produce correct values" << std::endl;
thisSequence->addSlot(objects::SUS_8, length * 0.6, DeviceHandlerIF::SEND_READ); }
thisSequence->addSlot(objects::SUS_8, length * 0.8, DeviceHandlerIF::GET_READ);
/**
* The sun sensor will be shutdown as soon as the chip select is pulled high. Thus all
* requests to a sun sensor must be performed consecutively. Another reason for calling multiple
* device handler cycles is that some ADC conversions need a small delay before the results can
* be read.
* One sun sensor communication sequence also blocks the SPI bus. So other devices can not be
* inserted between the device handler cycles of one SUS.
*/
/* Write setup */
thisSequence->addSlot(objects::SUS_8, length * 0.991, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.992, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.993, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.994, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.995, DeviceHandlerIF::GET_READ);
/* Request temperature */
thisSequence->addSlot(objects::SUS_8, length * 0.996, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.997, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.998, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.999, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.9, DeviceHandlerIF::GET_READ);
/* Read temperature */
thisSequence->addSlot(objects::SUS_8, length * 0.901, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.902, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.903, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.904, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.905, DeviceHandlerIF::GET_READ);
/* Request and read ADC conversions */
thisSequence->addSlot(objects::SUS_8, length * 0.906, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0.907, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.908, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.909, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.91, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION); // thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::SUS_11, length * 0.2, DeviceHandlerIF::SEND_WRITE); // thisSequence->addSlot(objects::SUS_11, length * 0.2, DeviceHandlerIF::SEND_WRITE);

View File

@ -9,6 +9,9 @@ SusHandler::SusHandler(object_id_t objectId, object_id_t comIF, CookieIF * comCo
if (comCookie == NULL) { if (comCookie == NULL) {
sif::error << "SusHandler: Invalid com cookie" << std::endl; sif::error << "SusHandler: Invalid com cookie" << std::endl;
} }
if (gpioComIF == NULL) {
sif::error << "SusHandler: Invalid GpioComIF" << std::endl;
}
} }
SusHandler::~SusHandler() { SusHandler::~SusHandler() {
@ -16,13 +19,11 @@ SusHandler::~SusHandler() {
void SusHandler::doStartUp(){ void SusHandler::doStartUp(){
if (internalState == InternalState::CONFIGURED) {
#if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1 #if OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP == 1
setMode(MODE_NORMAL); setMode(MODE_NORMAL);
#else #else
setMode(_MODE_TO_ON); setMode(_MODE_TO_ON);
#endif #endif
}
} }
void SusHandler::doShutDown(){ void SusHandler::doShutDown(){
@ -33,34 +34,26 @@ ReturnValue_t SusHandler::buildNormalDeviceCommand(
DeviceCommandId_t * id) { DeviceCommandId_t * id) {
if (communicationStep == CommunicationStep::WRITE_SETUP) { if (communicationStep == CommunicationStep::WRITE_SETUP) {
*id = SUS::WRITE_SETUP; *id = SUS::WRITE_SETUP;
communicationStep = CommunicationStep::REQUEST_TEMP; communicationStep = CommunicationStep::REQUEST_TEMPERATURE;
// communicationStep = CommunicationStep::PERFORM_CONVERSIONS;
} }
else if (communicationStep == CommunicationStep::PERFORM_CONVERSIONS) { else if (communicationStep == CommunicationStep::REQUEST_TEMPERATURE) {
*id = SUS::PERFORM_CONVERSIONS; *id = SUS::REQUEST_TEMPERATURE;
communicationStep = CommunicationStep::READ_TEMPERATURE;
}
else if (communicationStep == CommunicationStep::READ_TEMPERATURE) {
*id = SUS::READ_TEMPERATURE;
communicationStep = CommunicationStep::READ_CHANNELS;
}
else if (communicationStep == CommunicationStep::READ_CHANNELS) {
*id = SUS::READ_CHANNELS;
communicationStep = CommunicationStep::WRITE_SETUP; communicationStep = CommunicationStep::WRITE_SETUP;
// communicationStep = CommunicationStep::PERFORM_CONVERSIONS;
}
else if (communicationStep == CommunicationStep::REQUEST_TEMP) {
*id = SUS::RQUEST_TEMP;
communicationStep = CommunicationStep::READ_TEMP;
}
else if (communicationStep == CommunicationStep::READ_TEMP) {
*id = SUS::READ_TEMP;
communicationStep = CommunicationStep::PERFORM_CONVERSIONS;
} }
return buildCommandFromCommand(*id, nullptr, 0); return buildCommandFromCommand(*id, nullptr, 0);
} }
ReturnValue_t SusHandler::buildTransitionDeviceCommand( ReturnValue_t SusHandler::buildTransitionDeviceCommand(
DeviceCommandId_t * id){ DeviceCommandId_t * id){
if (internalState == InternalState::SETUP) { return HasReturnvaluesIF::RETURN_OK;
*id = SUS::WRITE_SETUP;
}
else {
return HasReturnvaluesIF::RETURN_OK;
}
return buildCommandFromCommand(*id, nullptr, 0);
} }
ReturnValue_t SusHandler::buildCommandFromCommand( ReturnValue_t SusHandler::buildCommandFromCommand(
@ -68,59 +61,46 @@ ReturnValue_t SusHandler::buildCommandFromCommand(
size_t commandDataLen) { size_t commandDataLen) {
switch(deviceCommand) { switch(deviceCommand) {
case(SUS::WRITE_SETUP): { case(SUS::WRITE_SETUP): {
/**
* The sun sensor ADC is shutdown when CS is pulled high, so each time requesting a
* measurement the setup has to be rewritten. There must also be a little delay between
* the transmission of the setup byte and the first conversion. Thus the conversion
* will be performed in an extra step.
*/
//TODO: Protect spi bus with mutex
gpioComIF->pullLow(chipSelectId); gpioComIF->pullLow(chipSelectId);
cmdBuffer[0] = SUS::SETUP_DEFINITION; cmdBuffer[0] = SUS::SETUP_DEFINITION;
rawPacket = cmdBuffer; rawPacket = cmdBuffer;
rawPacketLen = 1; rawPacketLen = 1;
internalState = InternalState::CONFIGURED;
return RETURN_OK; return RETURN_OK;
} }
case(SUS::PERFORM_CONVERSIONS): { case(SUS::READ_CHANNELS): {
// gpioComIF->pullLow(chipSelectId);
std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
/** cmdBuffer[0] = SUS::CONVERT_DIFF_CHANNEL_0;
* The sun sensor ADC is shutdown when CS is pulled high so each time requesting a cmdBuffer[1] = SUS::DUMMY_BYTE;
* measurement the setup has to be rewritten cmdBuffer[2] = SUS::CONVERT_DIFF_CHANNEL_1;
*/ cmdBuffer[3] = SUS::DUMMY_BYTE;
// cmdBuffer[0] = SUS::RESET_FIFO; cmdBuffer[4] = SUS::CONVERT_DIFF_CHANNEL_2;
cmdBuffer[0] = SUS::SETUP_DEFINITION; cmdBuffer[5] = SUS::DUMMY_BYTE;
// wirte one dummy byte here cmdBuffer[6] = SUS::CONVERT_DIFF_CHANNEL_3;
// cmdBuffer[2] = SUS::CONVERT_TEMPERATURE; cmdBuffer[7] = SUS::DUMMY_BYTE;
cmdBuffer[1] = SUS::CONVERT_DIFF_CHANNEL_0; cmdBuffer[8] = SUS::CONVERT_DIFF_CHANNEL_4;
cmdBuffer[2] = SUS::DUMMY_BYTE; cmdBuffer[9] = SUS::DUMMY_BYTE;
cmdBuffer[3] = SUS::CONVERT_DIFF_CHANNEL_1; cmdBuffer[10] = SUS::CONVERT_DIFF_CHANNEL_5;
cmdBuffer[4] = SUS::DUMMY_BYTE; cmdBuffer[11] = SUS::DUMMY_BYTE;
cmdBuffer[5] = SUS::CONVERT_DIFF_CHANNEL_2;
cmdBuffer[6] = SUS::DUMMY_BYTE;
cmdBuffer[7] = SUS::CONVERT_DIFF_CHANNEL_3;
cmdBuffer[8] = SUS::DUMMY_BYTE;
cmdBuffer[9] = SUS::CONVERT_DIFF_CHANNEL_4;
cmdBuffer[10] = SUS::DUMMY_BYTE;
cmdBuffer[11] = SUS::CONVERT_DIFF_CHANNEL_5;
cmdBuffer[12] = SUS::DUMMY_BYTE; cmdBuffer[12] = SUS::DUMMY_BYTE;
cmdBuffer[13] = SUS::DUMMY_BYTE;
// cmdBuffer[0] = SUS::SETUP_DEFINITION;
// cmdBuffer[1] = SUS::UNIPOLAR_CONFIG;
// cmdBuffer[2] = SUS::CONVERT_TEMPERATURE;
// cmdBuffer[26] = SUS::CONVERT_DIFF_CHANNEL_0_1;
// cmdBuffer[28] = SUS::CONVERT_DIFF_CHANNEL_2_3;
// cmdBuffer[30] = SUS::CONVERT_DIFF_CHANNEL_4_5;
rawPacket = cmdBuffer; rawPacket = cmdBuffer;
// rawPacketLen = SUS::SIZE_PERFORM_CONVERSIONS; rawPacketLen = SUS::SIZE_READ_CHANNELS;
rawPacketLen = 14;
return RETURN_OK; return RETURN_OK;
} }
case(SUS::RQUEST_TEMP): { case(SUS::REQUEST_TEMPERATURE): {
// gpioComIF->pullLow(chipSelectId);
std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
// cmdBuffer[0] = SUS::RESET_FIFO;
// cmdBuffer[1] = SUS::SETUP_DEFINITION;
cmdBuffer[0] = SUS::CONVERT_TEMPERATURE; cmdBuffer[0] = SUS::CONVERT_TEMPERATURE;
rawPacket = cmdBuffer; rawPacket = cmdBuffer;
rawPacketLen = 1; rawPacketLen = 1;
return RETURN_OK; return RETURN_OK;
} }
case(SUS::READ_TEMP): { case(SUS::READ_TEMPERATURE): {
std::memset(cmdBuffer, 0, sizeof(cmdBuffer)); std::memset(cmdBuffer, 0, sizeof(cmdBuffer));
rawPacket = cmdBuffer; rawPacket = cmdBuffer;
rawPacketLen = 24; rawPacketLen = 24;
@ -134,12 +114,10 @@ ReturnValue_t SusHandler::buildCommandFromCommand(
void SusHandler::fillCommandAndReplyMap() { void SusHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(SUS::WRITE_SETUP); this->insertInCommandMap(SUS::WRITE_SETUP);
// this->insertInCommandAndReplyMap(SUS::READ_TEMP, 1, &dataset, SUS::SIZE_PERFORM_CONVERSIONS); this->insertInCommandMap(SUS::REQUEST_TEMPERATURE);
this->insertInCommandAndReplyMap(SUS::PERFORM_CONVERSIONS, 1, &dataset, SUS::SIZE_PERFORM_CONVERSIONS); this->insertInCommandAndReplyMap(SUS::READ_CHANNELS, 1, &dataset, SUS::SIZE_READ_CHANNELS);
this->insertInCommandAndReplyMap(SUS::READ_TEMP, 1, nullptr, SUS::SIZE_PERFORM_CONVERSIONS); this->insertInCommandAndReplyMap(SUS::READ_TEMPERATURE, 1, nullptr,
// this->insertInCommandAndReplyMap(SUS::PERFORM_CONVERSIONS, 1, &dataset, SUS::SIZE_READ_TEMPERATURE);
// SUS::SIZE_PERFORM_CONVERSIONS);
this->insertInCommandMap(SUS::RQUEST_TEMP);
} }
ReturnValue_t SusHandler::scanForReply(const uint8_t *start, ReturnValue_t SusHandler::scanForReply(const uint8_t *start,
@ -152,27 +130,42 @@ ReturnValue_t SusHandler::scanForReply(const uint8_t *start,
ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id, ReturnValue_t SusHandler::interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) { const uint8_t *packet) {
switch (id) { switch (id) {
case SUS::PERFORM_CONVERSIONS: { case SUS::READ_CHANNELS: {
gpioComIF->pullHigh(chipSelectId);
PoolReadGuard readSet(&dataset); PoolReadGuard readSet(&dataset);
dataset.temperatureCelcius = (*(packet + 25) << 8 | *(packet + 26)) * 0.125; dataset.ain0 = (*(packet + 1) << 8 | *(packet + 2));
dataset.diffScanChannel0_1 = (*(packet + 29) << 8 | *(packet + 30)); dataset.ain1 = (*(packet + 3) << 8 | *(packet + 4));
dataset.diffScanChannel2_3 = (*(packet + 31) << 8 | *(packet + 32)); dataset.ain2 = (*(packet + 5) << 8 | *(packet + 6));
dataset.diffScanChannel4_5 = (*(packet + 33) << 8 | *(packet + 34)); dataset.ain3 = (*(packet + 7) << 8 | *(packet + 8));
dataset.ain4 = (*(packet + 9) << 8 | *(packet + 10));
dataset.ain5 = (*(packet + 11) << 8 | *(packet + 12));
#if OBSW_VERBOSE_LEVEL >= 1 && DEBUG_SUS #if OBSW_VERBOSE_LEVEL >= 1 && DEBUG_SUS
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", temperature: " sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN0: "
<< dataset.temperatureCelcius << " °C" << std::endl; << std::dec << dataset.ain0 << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 0/1: " sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN1: "
<< dataset.diffScanChannel0_1 << std::endl; << std::dec << dataset.ain1 << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 2/3: " sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN2: "
<< dataset.diffScanChannel2_3 << std::endl; << std::dec << dataset.ain2 << std::endl;
sif::info << "SUS with object id " << std::hex << this->getObjectId() << ", channel 4/5: " sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN3: "
<< dataset.diffScanChannel4_5 << std::endl; << std::dec << dataset.ain3 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN4: "
<< std::dec << dataset.ain4 << std::endl;
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", AIN5: "
<< std::dec << dataset.ain5 << std::endl;
#endif #endif
/**
* Reading the channel conversion results is the last communication step in one SUS
* sequence. SPI bus can now be released again.
*/
gpioComIF->pullHigh(chipSelectId);
break; break;
} }
case SUS::READ_TEMP: { case SUS::READ_TEMPERATURE: {
// gpioComIF->pullHigh(chipSelectId); PoolReadGuard readSet(&dataset);
dataset.temperatureCelcius = (*(packet + 22) << 8 | *(packet + 23)) * 0.125;
#if OBSW_VERBOSE_LEVEL >= 1 && DEBUG_SUS
sif::info << "SUS object id 0x" << std::hex << this->getObjectId() << ", temperature: "
<< dataset.temperatureCelcius << " °C" << std::endl;
#endif
break; break;
} }
default: { default: {
@ -189,15 +182,18 @@ void SusHandler::setNormalDatapoolEntriesInvalid(){
} }
uint32_t SusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){ uint32_t SusHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){
return 5000; return 1000;
} }
ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) { LocalDataPoolManager& poolManager) {
localDataPoolMap.emplace(SUS::TEMPERATURE_C, new PoolEntry<float>( { 0.0 })); localDataPoolMap.emplace(SUS::TEMPERATURE_C, new PoolEntry<float>( { 0.0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_0_1, new PoolEntry<uint16_t>( { 0 })); localDataPoolMap.emplace(SUS::AIN0, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_2_3, new PoolEntry<uint16_t>( { 0 })); localDataPoolMap.emplace(SUS::AIN1, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::DIFF_SCAN_CHANNEL_4_5, new PoolEntry<uint16_t>( { 0 })); localDataPoolMap.emplace(SUS::AIN2, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN3, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN4, new PoolEntry<uint16_t>( { 0 }));
localDataPoolMap.emplace(SUS::AIN5, new PoolEntry<uint16_t>( { 0 }));
return HasReturnvaluesIF::RETURN_OK; return HasReturnvaluesIF::RETURN_OK;
} }

View File

@ -41,15 +41,10 @@ protected:
private: private:
enum class CommunicationStep { enum class CommunicationStep {
PERFORM_CONVERSIONS, WRITE_SETUP,
REQUEST_TEMP, REQUEST_TEMPERATURE,
READ_TEMP, READ_TEMPERATURE,
WRITE_SETUP READ_CHANNELS
};
enum class InternalState {
SETUP,
CONFIGURED
}; };
LinuxLibgpioIF* gpioComIF = nullptr; LinuxLibgpioIF* gpioComIF = nullptr;
@ -59,7 +54,6 @@ private:
SUS::SusDataset dataset; SUS::SusDataset dataset;
uint8_t cmdBuffer[SUS::MAX_CMD_SIZE]; uint8_t cmdBuffer[SUS::MAX_CMD_SIZE];
InternalState internalState = InternalState::SETUP;
CommunicationStep communicationStep = CommunicationStep::WRITE_SETUP; CommunicationStep communicationStep = CommunicationStep::WRITE_SETUP;
}; };

View File

@ -3,6 +3,12 @@
namespace SUS { namespace SUS {
/**
* The MAX1227 in externally clocked mode did not properly work with frequencies higher than
* 1 MHz.
*/
static const uint32_t SUS_MAX_1227_SPEED = 1000000;
static const DeviceCommandId_t NONE = 0x0; // Set when no command is pending static const DeviceCommandId_t NONE = 0x0; // Set when no command is pending
/** /**
@ -10,9 +16,9 @@ namespace SUS {
* temperature sensor. * temperature sensor.
*/ */
static const DeviceCommandId_t WRITE_SETUP = 0x1; static const DeviceCommandId_t WRITE_SETUP = 0x1;
static const DeviceCommandId_t PERFORM_CONVERSIONS = 0x2; static const DeviceCommandId_t READ_CHANNELS = 0x2;
static const DeviceCommandId_t READ_TEMP = 0x3; static const DeviceCommandId_t READ_TEMPERATURE = 0x3;
static const DeviceCommandId_t RQUEST_TEMP = 0x4; static const DeviceCommandId_t REQUEST_TEMPERATURE = 0x4;
/** /**
* @brief This is the configuration byte which will be written to the setup register after * @brief This is the configuration byte which will be written to the setup register after
@ -47,21 +53,28 @@ namespace SUS {
static const uint8_t DUMMY_BYTE = 0x0; static const uint8_t DUMMY_BYTE = 0x0;
static const uint8_t SUS_DATA_SET_ID = PERFORM_CONVERSIONS; static const uint8_t SUS_DATA_SET_ID = READ_CHANNELS;
static const uint8_t SIZE_PERFORM_CONVERSIONS = 34; /** Size of data replies */
static const uint8_t SIZE_READ_CHANNELS = 13;
static const uint8_t SIZE_READ_TEMPERATURE = 25;
static const uint8_t MAX_CMD_SIZE = SIZE_PERFORM_CONVERSIONS; static const uint8_t MAX_CMD_SIZE = SIZE_READ_TEMPERATURE;
static const uint8_t POOL_ENTRIES = 7;
enum Max1227PoolIds: lp_id_t { enum Max1227PoolIds: lp_id_t {
TEMPERATURE_C, TEMPERATURE_C,
DIFF_SCAN_CHANNEL_0_1, AIN0,
DIFF_SCAN_CHANNEL_2_3, AIN1,
DIFF_SCAN_CHANNEL_4_5, AIN2,
AIN3,
AIN4,
AIN5,
}; };
class SusDataset: public StaticLocalDataSet<sizeof(float)> { class SusDataset: public StaticLocalDataSet<POOL_ENTRIES> {
public: public:
SusDataset(HasLocalDataPoolIF* owner) : SusDataset(HasLocalDataPoolIF* owner) :
@ -73,9 +86,12 @@ public:
} }
lp_var_t<float> temperatureCelcius = lp_var_t<float>(sid.objectId, TEMPERATURE_C, this); lp_var_t<float> temperatureCelcius = lp_var_t<float>(sid.objectId, TEMPERATURE_C, this);
lp_var_t<uint16_t> diffScanChannel0_1 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_0_1, this); lp_var_t<uint16_t> ain0 = lp_var_t<uint16_t>(sid.objectId, AIN0, this);
lp_var_t<uint16_t> diffScanChannel2_3 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_2_3, this); lp_var_t<uint16_t> ain1 = lp_var_t<uint16_t>(sid.objectId, AIN1, this);
lp_var_t<uint16_t> diffScanChannel4_5 = lp_var_t<uint16_t>(sid.objectId, DIFF_SCAN_CHANNEL_4_5, this); lp_var_t<uint16_t> ain2 = lp_var_t<uint16_t>(sid.objectId, AIN2, this);
lp_var_t<uint16_t> ain3 = lp_var_t<uint16_t>(sid.objectId, AIN3, this);
lp_var_t<uint16_t> ain4 = lp_var_t<uint16_t>(sid.objectId, AIN4, this);
lp_var_t<uint16_t> ain5 = lp_var_t<uint16_t>(sid.objectId, AIN5, this);
}; };
} }