tmtc update
This commit is contained in:
commit
870dd717e4
@ -66,6 +66,7 @@ set(LIB_ARCSEC wire)
|
|||||||
set(THIRD_PARTY_FOLDER thirdparty)
|
set(THIRD_PARTY_FOLDER thirdparty)
|
||||||
set(LIB_CXX_FS -lstdc++fs)
|
set(LIB_CXX_FS -lstdc++fs)
|
||||||
set(LIB_CATCH2 Catch2)
|
set(LIB_CATCH2 Catch2)
|
||||||
|
set(LIB_GPS gps)
|
||||||
set(LIB_JSON_NAME nlohmann_json::nlohmann_json)
|
set(LIB_JSON_NAME nlohmann_json::nlohmann_json)
|
||||||
|
|
||||||
# Set path names
|
# Set path names
|
||||||
@ -221,6 +222,7 @@ if((NOT BUILD_Q7S_SIMPLE_MODE) AND (NOT EIVE_BUILD_WATCHDOG))
|
|||||||
if(TGT_BSP MATCHES "arm/q7s")
|
if(TGT_BSP MATCHES "arm/q7s")
|
||||||
target_link_libraries(${TARGET_NAME} PRIVATE
|
target_link_libraries(${TARGET_NAME} PRIVATE
|
||||||
${LIB_ARCSEC}
|
${LIB_ARCSEC}
|
||||||
|
${LIB_GPS}
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
endif()
|
endif()
|
||||||
|
3
Justfile
3
Justfile
@ -5,5 +5,8 @@ default: q7s-debug-make
|
|||||||
q7s-debug-make:
|
q7s-debug-make:
|
||||||
{{python_script}} -o linux -g make -b debug -t "arm/q7s" -l build-Debug-Q7S
|
{{python_script}} -o linux -g make -b debug -t "arm/q7s" -l build-Debug-Q7S
|
||||||
|
|
||||||
|
q7s-release-make:
|
||||||
|
{{python_script}} -o linux -g make -b release -t "arm/q7s" -l build-Release-Q7S
|
||||||
|
|
||||||
q7s-debug-ninja:
|
q7s-debug-ninja:
|
||||||
{{python_script}} -o linux -g ninja -b debug -t "arm/q7s" -l build-Debug-Q7S
|
{{python_script}} -o linux -g ninja -b debug -t "arm/q7s" -l build-Debug-Q7S
|
||||||
|
21
README.md
21
README.md
@ -1045,26 +1045,7 @@ cat file.bin | hexdump -v -n X
|
|||||||
|
|
||||||
## Preparation of a fresh rootfs and SD card
|
## Preparation of a fresh rootfs and SD card
|
||||||
|
|
||||||
This section summarizes important changes between a fresh rootfs and the current
|
See [q7s-package repository README](https://egit.irs.uni-stuttgart.de/eive/q7s-package)
|
||||||
EIVE implementation
|
|
||||||
|
|
||||||
### rootfs
|
|
||||||
|
|
||||||
- Mount point `/mnt/sd0` created for SD card 0. Created with `mkdir`
|
|
||||||
- Mount point `/mnt/sd1` created for SD card 1. Created with `mkdir`
|
|
||||||
- Folder `scripts` in `/home/root` folder.
|
|
||||||
- `scripts` folder currently contains a few shell helper scripts
|
|
||||||
- Folder `profile.d` in `/etc` folder which contains the `path-set.sh` script
|
|
||||||
which is sourced at software startup
|
|
||||||
- Library `libwire.so` in `/usr/lib` folder
|
|
||||||
|
|
||||||
### SD Cards
|
|
||||||
|
|
||||||
- Folder `bin` for binaries, for example the OBSW
|
|
||||||
- Folder `misc` for miscellaneous files. Contains `ls` for directory listings
|
|
||||||
- Folder `tc` for telecommands
|
|
||||||
- Folder `tm` for telemetry
|
|
||||||
- Folder `xdi` for XDI components (e.g. for firmware or device tree updates)
|
|
||||||
|
|
||||||
# <a id="static-code-analysis"></a> Running cppcheck on the Software
|
# <a id="static-code-analysis"></a> Running cppcheck on the Software
|
||||||
|
|
||||||
|
@ -14,7 +14,7 @@
|
|||||||
#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/GyroADIS16507Handler.h"
|
#include "mission/devices/GyroADIS1650XHandler.h"
|
||||||
|
|
||||||
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
||||||
#include "fsfw/tmtcservices/CommandingServiceBase.h"
|
#include "fsfw/tmtcservices/CommandingServiceBase.h"
|
||||||
|
@ -12,17 +12,28 @@
|
|||||||
#include "test/DummyParameter.h"
|
#include "test/DummyParameter.h"
|
||||||
|
|
||||||
#include <nlohmann/json.hpp>
|
#include <nlohmann/json.hpp>
|
||||||
|
#include <gps.h>
|
||||||
|
#include <libgpsmm.h>
|
||||||
|
|
||||||
|
#include <ctime>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
#include <iomanip>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <cstdio>
|
#include <cstdio>
|
||||||
|
|
||||||
Q7STestTask::Q7STestTask(object_id_t objectId): TestTask(objectId) {
|
Q7STestTask::Q7STestTask(object_id_t objectId): TestTask(objectId) {
|
||||||
|
doTestSdCard = false;
|
||||||
|
doTestScratchApi = false;
|
||||||
|
doTestGps = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t Q7STestTask::performOneShotAction() {
|
ReturnValue_t Q7STestTask::performOneShotAction() {
|
||||||
//testSdCard();
|
if (doTestSdCard) {
|
||||||
//testScratchApi();
|
testSdCard();
|
||||||
|
}
|
||||||
|
if (doTestScratchApi) {
|
||||||
|
testScratchApi();
|
||||||
|
}
|
||||||
//testJsonLibDirect();
|
//testJsonLibDirect();
|
||||||
//testDummyParams();
|
//testDummyParams();
|
||||||
//testProtHandler();
|
//testProtHandler();
|
||||||
@ -31,6 +42,13 @@ ReturnValue_t Q7STestTask::performOneShotAction() {
|
|||||||
return TestTask::performOneShotAction();
|
return TestTask::performOneShotAction();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ReturnValue_t Q7STestTask::performPeriodicAction() {
|
||||||
|
if(doTestGps) {
|
||||||
|
testGpsDaemon();
|
||||||
|
}
|
||||||
|
return TestTask::performPeriodicAction();
|
||||||
|
}
|
||||||
|
|
||||||
void Q7STestTask::testSdCard() {
|
void Q7STestTask::testSdCard() {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
Stopwatch stopwatch;
|
Stopwatch stopwatch;
|
||||||
@ -224,6 +242,26 @@ void Q7STestTask::testProtHandler() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Q7STestTask::testGpsDaemon() {
|
||||||
|
gpsmm gpsmm(GPSD_SHARED_MEMORY, 0);
|
||||||
|
gps_data_t* gps;
|
||||||
|
gps = gpsmm.read();
|
||||||
|
if(gps == nullptr) {
|
||||||
|
sif::warning << "Q7STestTask: Reading GPS data failed" << std::endl;
|
||||||
|
}
|
||||||
|
sif::info << "-- Q7STestTask: GPS shared memory read test --" << std::endl;
|
||||||
|
time_t timeRaw = gps->fix.time.tv_sec;
|
||||||
|
std::tm* time = gmtime(&timeRaw);
|
||||||
|
sif::info << "Time: " << std::put_time(time, "%c %Z") << std::endl;
|
||||||
|
sif::info << "Visible satellites: " << gps->satellites_visible << std::endl;
|
||||||
|
sif::info << "Satellites used: " << gps->satellites_used << std::endl;
|
||||||
|
sif::info << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl;
|
||||||
|
sif::info << "Latitude: " << gps->fix.latitude << std::endl;
|
||||||
|
sif::info << "Longitude: " << gps->fix.longitude << std::endl;
|
||||||
|
sif::info << "Altitude(MSL): " << gps->fix.altMSL << std::endl;
|
||||||
|
sif::info << "Speed(m/s): " << gps->fix.speed << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) {
|
void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) {
|
||||||
auto fsHandler = ObjectManager::instance()->
|
auto fsHandler = ObjectManager::instance()->
|
||||||
get<FileSystemHandler>(objects::FILE_SYSTEM_HANDLER);
|
get<FileSystemHandler>(objects::FILE_SYSTEM_HANDLER);
|
||||||
|
@ -9,8 +9,15 @@ public:
|
|||||||
|
|
||||||
ReturnValue_t initialize() override;
|
ReturnValue_t initialize() override;
|
||||||
private:
|
private:
|
||||||
|
bool doTestSdCard = false;
|
||||||
|
bool doTestScratchApi = false;
|
||||||
|
bool doTestGps = false;
|
||||||
|
|
||||||
CoreController* coreController = nullptr;
|
CoreController* coreController = nullptr;
|
||||||
ReturnValue_t performOneShotAction() override;
|
ReturnValue_t performOneShotAction() override;
|
||||||
|
ReturnValue_t performPeriodicAction() override;
|
||||||
|
|
||||||
|
void testGpsDaemon();
|
||||||
|
|
||||||
void testSdCard();
|
void testSdCard();
|
||||||
void fileTests();
|
void fileTests();
|
||||||
|
@ -117,6 +117,13 @@ void initmission::initTasks() {
|
|||||||
}
|
}
|
||||||
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
||||||
|
|
||||||
|
PeriodicTaskIF* acsCtrl = factory->createPeriodicTask(
|
||||||
|
"ACS_CTRL", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||||
|
result = acsCtrl->addComponent(objects::GPS_CONTROLLER);
|
||||||
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("ACS_CTRL", objects::GPS_CONTROLLER);
|
||||||
|
}
|
||||||
|
|
||||||
# if BOARD_TE0720 == 0
|
# if BOARD_TE0720 == 0
|
||||||
// FS task, task interval does not matter because it runs in permanent loop, priority low
|
// FS task, task interval does not matter because it runs in permanent loop, priority low
|
||||||
// because it is a non-essential background task
|
// because it is a non-essential background task
|
||||||
@ -202,6 +209,8 @@ void initmission::initTasks() {
|
|||||||
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
acsCtrl->startTask();
|
||||||
|
|
||||||
sif::info << "Tasks started.." << std::endl;
|
sif::info << "Tasks started.." << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -449,14 +449,14 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComI
|
|||||||
gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
||||||
|
|
||||||
consumer.str("");
|
consumer.str("");
|
||||||
consumer << "0x" << std::hex << objects::GPS0_HANDLER;
|
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
|
||||||
// GNSS reset pins are active low
|
// GNSS reset pins are active low
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_0, consumer.str(), gpio::DIR_OUT,
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_0, consumer.str(), gpio::DIR_OUT,
|
||||||
gpio::HIGH);
|
gpio::HIGH);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_NRESET, gpio);
|
||||||
|
|
||||||
consumer.str("");
|
consumer.str("");
|
||||||
consumer << "0x" << std::hex << objects::GPS1_HANDLER;
|
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_1, consumer.str(), gpio::DIR_OUT,
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::RESET_GNSS_1, consumer.str(), gpio::DIR_OUT,
|
||||||
gpio::HIGH);
|
gpio::HIGH);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_NRESET, gpio);
|
||||||
@ -476,13 +476,13 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComI
|
|||||||
|
|
||||||
// Enable pins for GNSS
|
// Enable pins for GNSS
|
||||||
consumer.str("");
|
consumer.str("");
|
||||||
consumer << "0x" << std::hex << objects::GPS0_HANDLER;
|
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_0_ENABLE, consumer.str(),
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_0_ENABLE, consumer.str(),
|
||||||
gpio::DIR_OUT, gpio::LOW);
|
gpio::DIR_OUT, gpio::LOW);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_ENABLE, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_0_ENABLE, gpio);
|
||||||
|
|
||||||
consumer.str("");
|
consumer.str("");
|
||||||
consumer << "0x" << std::hex << objects::GPS1_HANDLER;
|
consumer << "0x" << std::hex << objects::GPS_CONTROLLER;
|
||||||
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_1_ENABLE, consumer.str(), gpio::DIR_OUT,
|
gpio = new GpiodRegularByLineName(q7s::gpioNames::GNSS_1_ENABLE, consumer.str(), gpio::DIR_OUT,
|
||||||
gpio::LOW);
|
gpio::LOW);
|
||||||
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_ENABLE, gpio);
|
gpioCookieAcsBoard->addGpio(gpioIds::GNSS_1_ENABLE, gpio);
|
||||||
@ -570,14 +570,9 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF *gpioComIF, UartComI
|
|||||||
resetArgsGnss0.gnss1 = false;
|
resetArgsGnss0.gnss1 = false;
|
||||||
resetArgsGnss0.gpioComIF = gpioComIF;
|
resetArgsGnss0.gpioComIF = gpioComIF;
|
||||||
resetArgsGnss0.waitPeriodMs = 100;
|
resetArgsGnss0.waitPeriodMs = 100;
|
||||||
auto uartCookieGps0 = new UartCookie(objects::GPS0_HANDLER, q7s::UART_GNSS_DEV,
|
auto gpsHandler0 = new GPSHyperionHandler(objects::GPS_CONTROLLER, objects::NO_OBJECT,
|
||||||
UartModes::CANONICAL, uart::GNSS_BAUD, uart::HYPERION_GPS_REPLY_MAX_BUFFER);
|
debugGps);
|
||||||
uartCookieGps0->setToFlushInput(true);
|
|
||||||
uartCookieGps0->setReadCycles(6);
|
|
||||||
auto gpsHandler0 = new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF,
|
|
||||||
uartCookieGps0, debugGps);
|
|
||||||
gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0);
|
gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0);
|
||||||
gpsHandler0->setStartUpImmediately();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createHeaterComponents() {
|
void ObjectFactory::createHeaterComponents() {
|
||||||
@ -867,7 +862,6 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF) {
|
|||||||
rwHandler1->setStartUpImmediately();
|
rwHandler1->setStartUpImmediately();
|
||||||
#endif
|
#endif
|
||||||
rw1SpiCookie->setCallbackArgs(rwHandler1);
|
rw1SpiCookie->setCallbackArgs(rwHandler1);
|
||||||
rwHandler1->setStartUpImmediately();
|
|
||||||
|
|
||||||
auto rwHandler2 = new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF,
|
auto rwHandler2 = new RwHandler(objects::RW2, objects::SPI_COM_IF, rw2SpiCookie, gpioComIF,
|
||||||
gpioIds::EN_RW2);
|
gpioIds::EN_RW2);
|
||||||
|
@ -634,7 +634,7 @@ ReturnValue_t StrHelper::checkFlashActionReply(uint8_t region_, uint32_t address
|
|||||||
<< std::endl;
|
<< std::endl;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
uint16_t length;
|
uint16_t length = 0;
|
||||||
size = sizeof(length);
|
size = sizeof(length);
|
||||||
const uint8_t* lengthData = data + LENGTH_OFFSET;
|
const uint8_t* lengthData = data + LENGTH_OFFSET;
|
||||||
result = SerializeAdapter::deSerialize(&length, lengthData, &size,
|
result = SerializeAdapter::deSerialize(&length, lengthData, &size,
|
||||||
|
@ -79,8 +79,7 @@ enum commonObjects: uint32_t {
|
|||||||
SUS_12 = 0x44120043,
|
SUS_12 = 0x44120043,
|
||||||
SUS_13 = 0x44120044,
|
SUS_13 = 0x44120044,
|
||||||
|
|
||||||
GPS0_HANDLER = 0x44130045,
|
GPS_CONTROLLER = 0x44130045,
|
||||||
GPS1_HANDLER = 0x44130146,
|
|
||||||
|
|
||||||
RW1 = 0x44120047,
|
RW1 = 0x44120047,
|
||||||
RW2 = 0x44120148,
|
RW2 = 0x44120148,
|
||||||
|
@ -297,31 +297,31 @@ void SpiTestClass::acsInit() {
|
|||||||
GpiodRegularByChip* gpio = nullptr;
|
GpiodRegularByChip* gpio = nullptr;
|
||||||
std::string rpiGpioName = "gpiochip0";
|
std::string rpiGpioName = "gpiochip0";
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3",
|
gpio = new GpiodRegularByChip(rpiGpioName, mgm0Lis3mdlChipSelect, "MGM_0_LIS3",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_0_LIS3_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100",
|
gpio = new GpiodRegularByChip(rpiGpioName, mgm1Rm3100ChipSelect, "MGM_1_RM3100",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_1_RM3100_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS",
|
gpio = new GpiodRegularByChip(rpiGpioName, gyro0AdisChipSelect, "GYRO_0_ADIS",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_0_ADIS_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G",
|
gpio = new GpiodRegularByChip(rpiGpioName, gyro1L3gd20ChipSelect, "GYRO_1_L3G",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_1_L3G_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G",
|
gpio = new GpiodRegularByChip(rpiGpioName, gyro3L3gd20ChipSelect, "GYRO_2_L3G",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
gpioCookie->addGpio(gpioIds::GYRO_3_L3G_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3",
|
gpio = new GpiodRegularByChip(rpiGpioName, mgm2Lis3mdlChipSelect, "MGM_2_LIS3",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_2_LIS3_CS, gpio);
|
||||||
|
|
||||||
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100",
|
gpio = new GpiodRegularByChip(rpiGpioName, mgm3Rm3100ChipSelect, "MGM_3_RM3100",
|
||||||
gpio::DIR_OUT, 1);
|
gpio::DIR_OUT, gpio::HIGH);
|
||||||
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
gpioCookie->addGpio(gpioIds::MGM_3_RM3100_CS, gpio);
|
||||||
#elif defined(XIPHOS_Q7S)
|
#elif defined(XIPHOS_Q7S)
|
||||||
GpiodRegularByLineName* gpio = nullptr;
|
GpiodRegularByLineName* gpio = nullptr;
|
||||||
|
@ -47,8 +47,6 @@ debugging. */
|
|||||||
#define OBSW_ADD_PLOC_MPSOC 0
|
#define OBSW_ADD_PLOC_MPSOC 0
|
||||||
#define OBSW_ADD_SUN_SENSORS 0
|
#define OBSW_ADD_SUN_SENSORS 0
|
||||||
#define OBSW_ADD_ACS_BOARD 0
|
#define OBSW_ADD_ACS_BOARD 0
|
||||||
#define OBSW_ADD_GPS_0 0
|
|
||||||
#define OBSW_ADD_GPS_1 0
|
|
||||||
#define OBSW_ADD_RW 0
|
#define OBSW_ADD_RW 0
|
||||||
#define OBSW_ADD_RTD_DEVICES 0
|
#define OBSW_ADD_RTD_DEVICES 0
|
||||||
#define OBSW_ADD_TMP_DEVICES 0
|
#define OBSW_ADD_TMP_DEVICES 0
|
||||||
@ -109,7 +107,7 @@ debugging. */
|
|||||||
#define OBSW_DEBUG_STARTRACKER 0
|
#define OBSW_DEBUG_STARTRACKER 0
|
||||||
#define OBSW_DEBUG_PLOC_MPSOC 0
|
#define OBSW_DEBUG_PLOC_MPSOC 0
|
||||||
#define OBSW_DEBUG_PLOC_SUPERVISOR 0
|
#define OBSW_DEBUG_PLOC_SUPERVISOR 0
|
||||||
#define OBSW_DEBUG_PDEC_HANDLER 1
|
#define OBSW_DEBUG_PDEC_HANDLER 0
|
||||||
|
|
||||||
/*******************************************************************/
|
/*******************************************************************/
|
||||||
/** Hardcoded */
|
/** Hardcoded */
|
||||||
|
@ -614,38 +614,6 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
|
|||||||
DeviceHandlerIF::GET_READ);
|
DeviceHandlerIF::GET_READ);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if OBSW_ADD_ACS_BOARD == 1
|
|
||||||
|
|
||||||
#if OBSW_ADD_GPS_0 == 1
|
|
||||||
uartPstEmpty = false;
|
|
||||||
thisSequence->addSlot(objects::GPS0_HANDLER, length * 0,
|
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
|
||||||
thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.2,
|
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
|
||||||
thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.4,
|
|
||||||
DeviceHandlerIF::GET_WRITE);
|
|
||||||
thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.6,
|
|
||||||
DeviceHandlerIF::SEND_READ);
|
|
||||||
thisSequence->addSlot(objects::GPS0_HANDLER, length * 0.8,
|
|
||||||
DeviceHandlerIF::GET_READ);
|
|
||||||
#endif /* OBSW_ADD_GPS_0 == 1 */
|
|
||||||
|
|
||||||
#if OBSW_ADD_GPS_1 == 1
|
|
||||||
uartPstEmpty = false;
|
|
||||||
thisSequence->addSlot(objects::GPS1_HANDLER, length * 0,
|
|
||||||
DeviceHandlerIF::PERFORM_OPERATION);
|
|
||||||
thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.2,
|
|
||||||
DeviceHandlerIF::SEND_WRITE);
|
|
||||||
thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.4,
|
|
||||||
DeviceHandlerIF::GET_WRITE);
|
|
||||||
thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.6,
|
|
||||||
DeviceHandlerIF::SEND_READ);
|
|
||||||
thisSequence->addSlot(objects::GPS1_HANDLER, length * 0.8,
|
|
||||||
DeviceHandlerIF::GET_READ);
|
|
||||||
#endif /* OBSW_ADD_GPS_1 == 1 */
|
|
||||||
|
|
||||||
#endif /* OBSW_ADD_ACS_BOARD == 1 */
|
|
||||||
|
|
||||||
#if OBSW_ADD_STAR_TRACKER == 1
|
#if OBSW_ADD_STAR_TRACKER == 1
|
||||||
uartPstEmpty = false;
|
uartPstEmpty = false;
|
||||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||||
|
@ -4,57 +4,44 @@
|
|||||||
#include "fsfw/datapool/PoolReadGuard.h"
|
#include "fsfw/datapool/PoolReadGuard.h"
|
||||||
#include "fsfw/timemanager/Clock.h"
|
#include "fsfw/timemanager/Clock.h"
|
||||||
|
|
||||||
#include "lwgps/lwgps.h"
|
#ifdef FSFW_OSAL_LINUX
|
||||||
|
#include <gps.h>
|
||||||
|
#include <libgpsmm.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
|
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
GPSHyperionHandler::GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication,
|
GPSHyperionHandler::GPSHyperionHandler(object_id_t objectId, object_id_t parentId,
|
||||||
CookieIF *comCookie, bool debugHyperionGps):
|
bool debugHyperionGps):
|
||||||
DeviceHandlerBase(objectId, deviceCommunication, comCookie), gpsSet(this),
|
ExtendedControllerBase(objectId, objects::NO_OBJECT), gpsSet(this),
|
||||||
debugHyperionGps(debugHyperionGps) {
|
debugHyperionGps(debugHyperionGps) {
|
||||||
lwgps_init(&gpsData);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
GPSHyperionHandler::~GPSHyperionHandler() {}
|
GPSHyperionHandler::~GPSHyperionHandler() {}
|
||||||
|
|
||||||
void GPSHyperionHandler::doStartUp() {
|
void GPSHyperionHandler::performControlOperation() {
|
||||||
if(internalState == InternalStates::NONE) {
|
#ifdef FSFW_OSAL_LINUX
|
||||||
commandExecuted = false;
|
readGpsDataFromGpsd();
|
||||||
internalState = InternalStates::WAIT_FIRST_MESSAGE;
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if(internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
LocalPoolDataSetBase* GPSHyperionHandler::getDataSetHandle(sid_t sid) {
|
||||||
if(commandExecuted) {
|
return nullptr;
|
||||||
internalState = InternalStates::IDLE;
|
|
||||||
setMode(MODE_ON);
|
|
||||||
commandExecuted = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPSHyperionHandler::doShutDown() {
|
ReturnValue_t GPSHyperionHandler::checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
internalState = InternalStates::NONE;
|
uint32_t *msToReachTheMode) {
|
||||||
commandExecuted = false;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
setMode(_MODE_POWER_DOWN);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::buildTransitionDeviceCommand(DeviceCommandId_t *id) {
|
ReturnValue_t GPSHyperionHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
return NOTHING_TO_SEND;
|
const uint8_t *data, size_t size) {
|
||||||
}
|
switch(actionId) {
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::buildNormalDeviceCommand(DeviceCommandId_t *id) {
|
|
||||||
return NOTHING_TO_SEND;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::buildCommandFromCommand(
|
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) {
|
|
||||||
// By default, send nothing
|
|
||||||
rawPacketLen = 0;
|
|
||||||
switch(deviceCommand) {
|
|
||||||
case(GpsHyperion::TRIGGER_RESET_PIN): {
|
case(GpsHyperion::TRIGGER_RESET_PIN): {
|
||||||
if(resetCallback != nullptr) {
|
if(resetCallback != nullptr) {
|
||||||
PoolReadGuard pg(&gpsSet);
|
PoolReadGuard pg(&gpsSet);
|
||||||
@ -69,99 +56,6 @@ ReturnValue_t GPSHyperionHandler::buildCommandFromCommand(
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::scanForReply(const uint8_t *start, size_t len,
|
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) {
|
|
||||||
// Pass data to GPS library
|
|
||||||
if(len > 0) {
|
|
||||||
// sif::debug << "GPSHandler::scanForReply: Received " << len << " bytes" << std::endl;
|
|
||||||
if (internalState == InternalStates::WAIT_FIRST_MESSAGE) {
|
|
||||||
// TODO: Check whether data is valid by checking whether NMEA start string is valid?
|
|
||||||
commandExecuted = true;
|
|
||||||
}
|
|
||||||
int result = lwgps_process(&gpsData, start, len);
|
|
||||||
if(result != 1) {
|
|
||||||
sif::warning << "GPSHandler::scanForReply: Issue processing GPS data with lwgps"
|
|
||||||
<< std::endl;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// The data from the device will generally be read all at once. Therefore, we
|
|
||||||
// can set all field here
|
|
||||||
PoolReadGuard pg(&gpsSet);
|
|
||||||
if(pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
#if FSFW_VERBOSE_LEVEL >= 1
|
|
||||||
sif::warning << "GPSHyperionHandler::scanForReply: Reading dataset failed"
|
|
||||||
<< std::endl;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
// Print messages
|
|
||||||
if(gpsData.is_valid) {
|
|
||||||
// Set all entries valid now, set invalid on case basis if values are sanitized
|
|
||||||
gpsSet.setValidity(true, true);
|
|
||||||
}
|
|
||||||
// Negative latitude -> South direction
|
|
||||||
gpsSet.latitude.value = gpsData.latitude;
|
|
||||||
// Negative longitude -> West direction
|
|
||||||
gpsSet.longitude.value = gpsData.longitude;
|
|
||||||
if(gpsData.altitude > 600000.0 or gpsData.altitude < 400000.0) {
|
|
||||||
gpsSet.altitude.setValid(false);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
gpsSet.altitude.setValid(true);
|
|
||||||
gpsSet.altitude.value = gpsData.altitude;
|
|
||||||
}
|
|
||||||
gpsSet.fixMode.value = gpsData.fix_mode;
|
|
||||||
gpsSet.satInUse.value = gpsData.sats_in_use;
|
|
||||||
Clock::TimeOfDay_t timeStruct = {};
|
|
||||||
timeStruct.day = gpsData.date;
|
|
||||||
timeStruct.hour = gpsData.hours;
|
|
||||||
timeStruct.minute = gpsData.minutes;
|
|
||||||
timeStruct.month = gpsData.month;
|
|
||||||
timeStruct.second = gpsData.seconds;
|
|
||||||
// Convert two-digit year to full year (AD)
|
|
||||||
timeStruct.year = gpsData.year + 2000;
|
|
||||||
timeval timeval = {};
|
|
||||||
Clock::convertTimeOfDayToTimeval(&timeStruct, &timeval);
|
|
||||||
gpsSet.year = timeStruct.year;
|
|
||||||
gpsSet.month = gpsData.month;
|
|
||||||
gpsSet.day = gpsData.date;
|
|
||||||
gpsSet.hours = gpsData.hours;
|
|
||||||
gpsSet.minutes = gpsData.minutes;
|
|
||||||
gpsSet.seconds = gpsData.seconds;
|
|
||||||
gpsSet.unixSeconds = timeval.tv_sec;
|
|
||||||
if(debugHyperionGps) {
|
|
||||||
sif::info << "GPS Data" << std::endl;
|
|
||||||
printf("Valid status: %d\n", gpsData.is_valid);
|
|
||||||
printf("Latitude: %f degrees\n", gpsData.latitude);
|
|
||||||
printf("Longitude: %f degrees\n", gpsData.longitude);
|
|
||||||
printf("Altitude: %f meters\n", gpsData.altitude);
|
|
||||||
}
|
|
||||||
#if FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV == 1
|
|
||||||
std::string filename = "/mnt/sd0/gps_log.txt";
|
|
||||||
std::ofstream gpsFile;
|
|
||||||
if(not std::filesystem::exists(filename)) {
|
|
||||||
gpsFile.open(filename, std::ofstream::out);
|
|
||||||
}
|
|
||||||
gpsFile.open(filename, std::ofstream::out | std::ofstream::app);
|
|
||||||
gpsFile.write("\n", 1);
|
|
||||||
gpsFile.write(reinterpret_cast<const char*>(start), len);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
*foundLen = len;
|
|
||||||
*foundId = GpsHyperion::GPS_REPLY;
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|
||||||
const uint8_t *packet) {
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t GPSHyperionHandler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
|
||||||
return 5000;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::initializeLocalDataPool(
|
ReturnValue_t GPSHyperionHandler::initializeLocalDataPool(
|
||||||
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
|
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
|
||||||
localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry<double>({0.0}));
|
localDataPoolMap.emplace(GpsHyperion::ALTITUDE, new PoolEntry<double>({0.0}));
|
||||||
@ -180,35 +74,108 @@ ReturnValue_t GPSHyperionHandler::initializeLocalDataPool(
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPSHyperionHandler::fillCommandAndReplyMap() {
|
|
||||||
// Reply length does not matter, packets should always arrive periodically
|
|
||||||
insertInReplyMap(GpsHyperion::GPS_REPLY, 4, &gpsSet, 0, true);
|
|
||||||
insertInCommandMap(GpsHyperion::TRIGGER_RESET_PIN);
|
|
||||||
}
|
|
||||||
|
|
||||||
void GPSHyperionHandler::modeChanged() {
|
|
||||||
internalState = InternalStates::NONE;
|
|
||||||
}
|
|
||||||
|
|
||||||
void GPSHyperionHandler::setResetPinTriggerFunction(gpioResetFunction_t resetCallback,
|
void GPSHyperionHandler::setResetPinTriggerFunction(gpioResetFunction_t resetCallback,
|
||||||
void *args) {
|
void *args) {
|
||||||
this->resetCallback = resetCallback;
|
this->resetCallback = resetCallback;
|
||||||
resetCallbackArgs = args;
|
resetCallbackArgs = args;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GPSHyperionHandler::debugInterface(uint8_t positionTracker, object_id_t objectId,
|
|
||||||
uint32_t parameter) {
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::initialize() {
|
ReturnValue_t GPSHyperionHandler::initialize() {
|
||||||
ReturnValue_t result = DeviceHandlerBase::initialize();
|
ReturnValue_t result = ExtendedControllerBase::initialize();
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
// Enable reply immediately for now
|
return result;
|
||||||
return updatePeriodicReply(true, GpsHyperion::GPS_REPLY);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t GPSHyperionHandler::acceptExternalDeviceCommands() {
|
ReturnValue_t GPSHyperionHandler::handleCommandMessage(CommandMessage *message) {
|
||||||
return DeviceHandlerBase::acceptExternalDeviceCommands();
|
return ExtendedControllerBase::handleCommandMessage(message);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef FSFW_OSAL_LINUX
|
||||||
|
void GPSHyperionHandler::readGpsDataFromGpsd() {
|
||||||
|
// The data from the device will generally be read all at once. Therefore, we
|
||||||
|
// can set all field here
|
||||||
|
gpsmm gpsmm(GPSD_SHARED_MEMORY, 0);
|
||||||
|
gps_data_t* gps;
|
||||||
|
gps = gpsmm.read();
|
||||||
|
if(gps == nullptr) {
|
||||||
|
sif::warning << "Q7STestTask: Reading GPS data failed" << std::endl;
|
||||||
|
}
|
||||||
|
PoolReadGuard pg(&gpsSet);
|
||||||
|
if(pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
#if FSFW_VERBOSE_LEVEL >= 1
|
||||||
|
sif::warning << "GPSHyperionHandler::scanForReply: Reading dataset failed"
|
||||||
|
<< std::endl;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
// Print messages
|
||||||
|
if((gps->set & MODE_SET) != MODE_SET) {
|
||||||
|
// Could not even set mode
|
||||||
|
gpsSet.setValidity(false, true);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(gps->satellites_used > 0) {
|
||||||
|
gpsSet.setValidity(true, true);
|
||||||
|
}
|
||||||
|
|
||||||
|
gpsSet.satInUse.value = gps->satellites_used;
|
||||||
|
gpsSet.satInView.value = gps->satellites_visible;
|
||||||
|
|
||||||
|
// 0: Not seen, 1: No fix, 2: 2D-Fix, 3: 3D-Fix
|
||||||
|
gpsSet.fixMode = gps->fix.mode;
|
||||||
|
if(std::isfinite(gps->fix.latitude)) {
|
||||||
|
// Negative latitude -> South direction
|
||||||
|
gpsSet.latitude.value = gps->fix.latitude;
|
||||||
|
} else {
|
||||||
|
gpsSet.latitude.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::isfinite(gps->fix.longitude)) {
|
||||||
|
// Negative longitude -> West direction
|
||||||
|
gpsSet.longitude.value = gps->fix.longitude;
|
||||||
|
} else {
|
||||||
|
gpsSet.longitude.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::isfinite(gps->fix.altitude)) {
|
||||||
|
gpsSet.altitude.value = gps->fix.altitude;
|
||||||
|
} else {
|
||||||
|
gpsSet.altitude.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::isfinite(gps->fix.speed)) {
|
||||||
|
gpsSet.speed.value = gps->fix.speed;
|
||||||
|
} else {
|
||||||
|
gpsSet.speed.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
gpsSet.unixSeconds.value = gps->fix.time.tv_sec;
|
||||||
|
timeval time = {};
|
||||||
|
time.tv_sec = gpsSet.unixSeconds.value;
|
||||||
|
time.tv_usec = gps->fix.time.tv_nsec / 1000;
|
||||||
|
Clock::TimeOfDay_t timeOfDay = {};
|
||||||
|
Clock::convertTimevalToTimeOfDay(&time, &timeOfDay);
|
||||||
|
gpsSet.year = timeOfDay.year;
|
||||||
|
gpsSet.month = timeOfDay.month;
|
||||||
|
gpsSet.day = timeOfDay.day;
|
||||||
|
gpsSet.hours = timeOfDay.hour;
|
||||||
|
gpsSet.minutes = timeOfDay.minute;
|
||||||
|
gpsSet.seconds = timeOfDay.second;
|
||||||
|
if(debugHyperionGps) {
|
||||||
|
sif::info << "-- Hyperion GPS Data --" << std::endl;
|
||||||
|
time_t timeRaw = gps->fix.time.tv_sec;
|
||||||
|
std::tm* time = gmtime(&timeRaw);
|
||||||
|
std::cout << "Time: " << std::put_time(time, "%c %Z") << std::endl;
|
||||||
|
std::cout << "Visible satellites: " << gps->satellites_visible << std::endl;
|
||||||
|
std::cout << "Satellites used: " << gps->satellites_used << std::endl;
|
||||||
|
std::cout << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl;
|
||||||
|
std::cout << "Latitude: " << gps->fix.latitude << std::endl;
|
||||||
|
std::cout << "Longitude: " << gps->fix.longitude << std::endl;
|
||||||
|
std::cout << "Altitude(MSL): " << gps->fix.altMSL << std::endl;
|
||||||
|
std::cout << "Speed(m/s): " << gps->fix.speed << std::endl;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -3,8 +3,8 @@
|
|||||||
|
|
||||||
#include "fsfw/FSFW.h"
|
#include "fsfw/FSFW.h"
|
||||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||||
|
#include "fsfw/controller/ExtendedControllerBase.h"
|
||||||
#include "devicedefinitions/GPSDefinitions.h"
|
#include "devicedefinitions/GPSDefinitions.h"
|
||||||
#include "lwgps/lwgps.h"
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Device handler for the Hyperion HT-GPS200 device
|
* @brief Device handler for the Hyperion HT-GPS200 device
|
||||||
@ -12,58 +12,38 @@
|
|||||||
* Flight manual:
|
* Flight manual:
|
||||||
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/Hyperion_HT-GPS200
|
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/Hyperion_HT-GPS200
|
||||||
*/
|
*/
|
||||||
class GPSHyperionHandler: public DeviceHandlerBase {
|
class GPSHyperionHandler: public ExtendedControllerBase {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
GPSHyperionHandler(object_id_t objectId, object_id_t deviceCommunication,
|
GPSHyperionHandler(object_id_t objectId, object_id_t parentId,
|
||||||
CookieIF* comCookie, bool debugHyperionGps = false);
|
bool debugHyperionGps = false);
|
||||||
virtual ~GPSHyperionHandler();
|
virtual ~GPSHyperionHandler();
|
||||||
|
|
||||||
using gpioResetFunction_t = ReturnValue_t (*) (void* args);
|
using gpioResetFunction_t = ReturnValue_t (*) (void* args);
|
||||||
|
|
||||||
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void*args);
|
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void*args);
|
||||||
ReturnValue_t acceptExternalDeviceCommands() override;
|
ReturnValue_t handleCommandMessage(CommandMessage *message) override;
|
||||||
|
void performControlOperation() override;
|
||||||
|
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
|
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
|
||||||
|
uint32_t *msToReachTheMode) override;
|
||||||
|
ReturnValue_t executeAction(ActionId_t actionId,
|
||||||
|
MessageQueueId_t commandedBy, const uint8_t* data,
|
||||||
|
size_t size) override;
|
||||||
ReturnValue_t initialize() override;
|
ReturnValue_t initialize() override;
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
gpioResetFunction_t resetCallback = nullptr;
|
gpioResetFunction_t resetCallback = nullptr;
|
||||||
void* resetCallbackArgs = nullptr;
|
void* resetCallbackArgs = nullptr;
|
||||||
|
|
||||||
enum class InternalStates {
|
|
||||||
NONE,
|
|
||||||
WAIT_FIRST_MESSAGE,
|
|
||||||
IDLE
|
|
||||||
};
|
|
||||||
InternalStates internalState = InternalStates::NONE;
|
|
||||||
bool commandExecuted = false;
|
|
||||||
|
|
||||||
/* DeviceHandlerBase overrides */
|
|
||||||
ReturnValue_t buildTransitionDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) override;
|
|
||||||
void doStartUp() override;
|
|
||||||
void doShutDown() override;
|
|
||||||
ReturnValue_t buildNormalDeviceCommand(
|
|
||||||
DeviceCommandId_t *id) override;
|
|
||||||
ReturnValue_t buildCommandFromCommand(
|
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) 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() override;
|
|
||||||
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
|
||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) override;
|
LocalDataPoolManager &poolManager) override;
|
||||||
virtual void debugInterface(uint8_t positionTracker = 0,
|
|
||||||
object_id_t objectId = 0, uint32_t parameter = 0) override;
|
|
||||||
private:
|
private:
|
||||||
lwgps_t gpsData = {};
|
|
||||||
GpsPrimaryDataset gpsSet;
|
GpsPrimaryDataset gpsSet;
|
||||||
bool debugHyperionGps = false;
|
bool debugHyperionGps = false;
|
||||||
|
|
||||||
|
void readGpsDataFromGpsd();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* MISSION_DEVICES_GPSHYPERIONHANDLER_H_ */
|
#endif /* MISSION_DEVICES_GPSHYPERIONHANDLER_H_ */
|
||||||
|
@ -61,10 +61,10 @@ private:
|
|||||||
|
|
||||||
std::string resetCommand = "<C04:5A5A:FF41>";
|
std::string resetCommand = "<C04:5A5A:FF41>";
|
||||||
std::string readRxStatusRegCommand = "<E00::825B>";
|
std::string readRxStatusRegCommand = "<E00::825B>";
|
||||||
std::string setTxModeStandby = "<W04:0040:2B9E>";
|
std::string setTxModeStandby = "<W04:4000:7E58>";
|
||||||
/** W - write, 04 - 4 bytes in data field, 01 - value, 40 register to write value */
|
/** W - write, 04 - 4 bytes in data field, 01 - value, 40 register to write value */
|
||||||
std::string setTxModeModulation = "<W04:0140:5D2A>";
|
std::string setTxModeModulation = "<W04:4001:4D69>";
|
||||||
std::string setTxModeCw = "<W04:1040:81CF>";
|
std::string setTxModeCw = "<W04:4010:4968>";
|
||||||
std::string readTxStatus = "<R02:40:7555>";
|
std::string readTxStatus = "<R02:40:7555>";
|
||||||
std::string readTxWaveform = "<R02:44:B991>";
|
std::string readTxWaveform = "<R02:44:B991>";
|
||||||
std::string readTxAgcValueHighByte = "<R02:46:DFF3>";
|
std::string readTxAgcValueHighByte = "<R02:46:DFF3>";
|
||||||
|
@ -15,15 +15,17 @@ enum GpsPoolIds: lp_id_t {
|
|||||||
LATITUDE = 0,
|
LATITUDE = 0,
|
||||||
LONGITUDE = 1,
|
LONGITUDE = 1,
|
||||||
ALTITUDE = 2,
|
ALTITUDE = 2,
|
||||||
FIX_MODE = 3,
|
SPEED = 3,
|
||||||
SATS_IN_USE = 4,
|
FIX_MODE = 4,
|
||||||
UNIX_SECONDS = 5,
|
SATS_IN_USE = 5,
|
||||||
YEAR = 6,
|
SATS_IN_VIEW = 6,
|
||||||
MONTH = 7,
|
UNIX_SECONDS = 7,
|
||||||
DAY = 8,
|
YEAR = 8,
|
||||||
HOURS = 9,
|
MONTH = 9,
|
||||||
MINUTES = 10,
|
DAY = 10,
|
||||||
SECONDS = 11
|
HOURS = 11,
|
||||||
|
MINUTES = 12,
|
||||||
|
SECONDS = 13
|
||||||
};
|
};
|
||||||
|
|
||||||
enum GpsFixModes: uint8_t {
|
enum GpsFixModes: uint8_t {
|
||||||
@ -47,8 +49,10 @@ public:
|
|||||||
lp_var_t<double> longitude = lp_var_t<double>(sid.objectId,
|
lp_var_t<double> longitude = lp_var_t<double>(sid.objectId,
|
||||||
GpsHyperion::LONGITUDE, this);
|
GpsHyperion::LONGITUDE, this);
|
||||||
lp_var_t<double> altitude = lp_var_t<double>(sid.objectId, GpsHyperion::ALTITUDE, this);
|
lp_var_t<double> altitude = lp_var_t<double>(sid.objectId, GpsHyperion::ALTITUDE, this);
|
||||||
|
lp_var_t<double> speed = lp_var_t<double>(sid.objectId, GpsHyperion::SPEED, this);
|
||||||
lp_var_t<uint8_t> fixMode = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::FIX_MODE, this);
|
lp_var_t<uint8_t> fixMode = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::FIX_MODE, this);
|
||||||
lp_var_t<uint8_t> satInUse = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SATS_IN_USE, this);
|
lp_var_t<uint8_t> satInUse = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SATS_IN_USE, this);
|
||||||
|
lp_var_t<uint8_t> satInView = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::SATS_IN_VIEW, this);
|
||||||
lp_var_t<uint16_t> year = lp_var_t<uint16_t>(sid.objectId, GpsHyperion::YEAR, this);
|
lp_var_t<uint16_t> year = lp_var_t<uint16_t>(sid.objectId, GpsHyperion::YEAR, this);
|
||||||
lp_var_t<uint8_t> month = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::MONTH, this);
|
lp_var_t<uint8_t> month = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::MONTH, this);
|
||||||
lp_var_t<uint8_t> day = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::DAY, this);
|
lp_var_t<uint8_t> day = lp_var_t<uint8_t>(sid.objectId, GpsHyperion::DAY, this);
|
||||||
|
@ -21,7 +21,7 @@ namespace SYRLINKS {
|
|||||||
static const DeviceCommandId_t READ_TX_AGC_VALUE_LOW_BYTE = 0x0A;
|
static const DeviceCommandId_t READ_TX_AGC_VALUE_LOW_BYTE = 0x0A;
|
||||||
|
|
||||||
/** Size of a simple transmission success response */
|
/** Size of a simple transmission success response */
|
||||||
static const uint8_t ACK_SIZE = 11;
|
static const uint8_t ACK_SIZE = 12;
|
||||||
static const uint8_t SIZE_CRC_AND_TERMINATION = 5;
|
static const uint8_t SIZE_CRC_AND_TERMINATION = 5;
|
||||||
/** The size of the header with the message identifier and the payload size field */
|
/** The size of the header with the message identifier and the payload size field */
|
||||||
static const uint8_t MESSAGE_HEADER_SIZE = 5;
|
static const uint8_t MESSAGE_HEADER_SIZE = 5;
|
||||||
|
8
scripts/rpi-port.sh
Executable file
8
scripts/rpi-port.sh
Executable file
@ -0,0 +1,8 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
echo "-L 1538:raspberrypi.local:1538 for Raspberry Pi connect with TCF agent"
|
||||||
|
echo "-L 1539:raspberrypi.local:22 for Raspberry Pi file transfers"
|
||||||
|
|
||||||
|
ssh -L 1538:raspberrypi.local:1534 \
|
||||||
|
-L 1539:raspberrypi.local:22 \
|
||||||
|
eive@2001:7c0:2018:1099:babe:0:e1fe:f1a5 \
|
||||||
|
-t 'CONSOLE_PREFIX="[RPi Tunnel]" /bin/bash'
|
Loading…
Reference in New Issue
Block a user