PCDU switch callback #128
8
.clang-format
Normal file
8
.clang-format
Normal file
@ -0,0 +1,8 @@
|
|||||||
|
---
|
||||||
|
BasedOnStyle: Google
|
||||||
|
IndentWidth: 2
|
||||||
|
---
|
||||||
|
Language: Cpp
|
||||||
|
ColumnLimit: 100
|
||||||
|
ReflowComments: true
|
||||||
|
---
|
@ -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
|
||||||
|
65
README.md
65
README.md
@ -11,14 +11,15 @@
|
|||||||
4. [Useful and Common Host Commands](#host-commands)
|
4. [Useful and Common Host Commands](#host-commands)
|
||||||
5. [Setting up Prerequisites](#set-up-prereq)
|
5. [Setting up Prerequisites](#set-up-prereq)
|
||||||
6. [Remote Debugging](#remote-debugging)
|
6. [Remote Debugging](#remote-debugging)
|
||||||
7. [TMTC testing](#tmtc-testing)
|
6. [Remote Reset](#remote-reset)
|
||||||
8. [Direct Debugging](#direct-debugging)
|
8. [TMTC testing](#tmtc-testing)
|
||||||
9. [Transfering Files to the Q7S](#file-transfer)
|
9. [Direct Debugging](#direct-debugging)
|
||||||
10. [Q7S OBC](#q7s)
|
10. [Transfering Files to the Q7S](#file-transfer)
|
||||||
11. [Static Code Analysis](#static-code-analysis)
|
11. [Q7S OBC](#q7s)
|
||||||
12. [Eclipse](#eclipse)
|
12. [Static Code Analysis](#static-code-analysis)
|
||||||
13. [Running the OBSW on a Raspberry Pi](#rpi)
|
13. [Eclipse](#eclipse)
|
||||||
14. [FSFW](#fsfw)
|
14. [Running the OBSW on a Raspberry Pi](#rpi)
|
||||||
|
15. [FSFW](#fsfw)
|
||||||
|
|
||||||
# <a id="general"></a> General information
|
# <a id="general"></a> General information
|
||||||
|
|
||||||
@ -535,10 +536,10 @@ ssh root@192.168.133.10
|
|||||||
```
|
```
|
||||||
|
|
||||||
If this has not been done yet, you can access the serial
|
If this has not been done yet, you can access the serial
|
||||||
console of the Q7S like this to set it
|
console of the Q7S like this
|
||||||
|
|
||||||
```sh
|
```sh
|
||||||
picocom -b 115200 /dev/ttyUSB0
|
picocom -b 115200 /dev/q7sSerial
|
||||||
```
|
```
|
||||||
|
|
||||||
The flatsat has the aliases and shell scripts `q7s_ssh` and `q7s_serial` for this task as well.
|
The flatsat has the aliases and shell scripts `q7s_ssh` and `q7s_serial` for this task as well.
|
||||||
@ -575,6 +576,29 @@ alias or shell script to do this quickly.
|
|||||||
Note: When now setting up a debug session in the Xilinx SDK or Eclipse, the host must be set
|
Note: When now setting up a debug session in the Xilinx SDK or Eclipse, the host must be set
|
||||||
to localhost instead of the IP address of the Q7S.
|
to localhost instead of the IP address of the Q7S.
|
||||||
|
|
||||||
|
# <a id="remote-reset"></a> Remote Reset
|
||||||
|
1. Launch xilinx hardware server on flatsat with alias
|
||||||
|
````
|
||||||
|
launch-hwserver-xilinx
|
||||||
|
````
|
||||||
|
2. On host PC start xsc
|
||||||
|
3. In xsct console type the follwing command to connect to the hardware server (replace </flatsat-pc-ip-address/> with the IP address of the flatsat PC. Can be found out with ifconfig)
|
||||||
|
````
|
||||||
|
connect -url tcp:</flatsat-pc-ip-address/>:3121
|
||||||
|
````
|
||||||
|
4. The following command will list all available devices
|
||||||
|
````
|
||||||
|
targets
|
||||||
|
````
|
||||||
|
5. Connect to the APU of the Q7S
|
||||||
|
````
|
||||||
|
target </APU-number/>
|
||||||
|
````
|
||||||
|
6. Perform reset
|
||||||
|
````
|
||||||
|
rst
|
||||||
|
````
|
||||||
|
|
||||||
# <a id="tmtc-testing"></a> TMTC testing
|
# <a id="tmtc-testing"></a> TMTC testing
|
||||||
|
|
||||||
The OBSW supports sending PUS TM packets via TCP or the PDEC IP Core which transmits the data as
|
The OBSW supports sending PUS TM packets via TCP or the PDEC IP Core which transmits the data as
|
||||||
@ -1021,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
|
||||||
|
|
||||||
|
11
apply-clang-format.sh
Executable file
11
apply-clang-format.sh
Executable file
@ -0,0 +1,11 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
if [[ ! -f README.md ]]; then
|
||||||
|
cd ..
|
||||||
|
fi
|
||||||
|
|
||||||
|
find ./mission -iname *.h o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
||||||
|
find ./linux -iname *.h -o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
||||||
|
find ./bsp_q7s -iname *.h -o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
||||||
|
find ./bsp_linux_board -iname *.h -o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
||||||
|
find ./bsp_hosted -iname *.h -o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
||||||
|
find ./test -iname *.h -o -iname *.cpp -o -iname *.c | xargs clang-format --style=file -i
|
@ -1,20 +1,19 @@
|
|||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "ObjectFactory.h"
|
|
||||||
|
|
||||||
#include <OBSWConfig.h>
|
#include <OBSWConfig.h>
|
||||||
|
#include <fsfw/objectmanager/ObjectManager.h>
|
||||||
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
||||||
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
|
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
|
||||||
#include <fsfw/objectmanager/ObjectManager.h>
|
|
||||||
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
|
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
|
||||||
#include <fsfw/tasks/PeriodicTaskIF.h>
|
#include <fsfw/tasks/PeriodicTaskIF.h>
|
||||||
#include <fsfw/tasks/TaskFactory.h>
|
#include <fsfw/tasks/TaskFactory.h>
|
||||||
|
|
||||||
#include <mission/utility/InitMission.h>
|
#include <mission/utility/InitMission.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "ObjectFactory.h"
|
||||||
|
|
||||||
#ifdef LINUX
|
#ifdef LINUX
|
||||||
ServiceInterfaceStream sif::debug("DEBUG");
|
ServiceInterfaceStream sif::debug("DEBUG");
|
||||||
ServiceInterfaceStream sif::info("INFO");
|
ServiceInterfaceStream sif::info("INFO");
|
||||||
@ -27,7 +26,7 @@ ServiceInterfaceStream sif::warning("WARNING", true);
|
|||||||
ServiceInterfaceStream sif::error("ERROR", true, false, true);
|
ServiceInterfaceStream sif::error("ERROR", true, false, true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
ObjectManagerIF *objectManager = nullptr;
|
ObjectManagerIF* objectManager = nullptr;
|
||||||
|
|
||||||
void initmission::initMission() {
|
void initmission::initMission() {
|
||||||
sif::info << "Building global objects.." << std::endl;
|
sif::info << "Building global objects.." << std::endl;
|
||||||
@ -42,30 +41,29 @@ void initmission::initMission() {
|
|||||||
|
|
||||||
void initmission::initTasks() {
|
void initmission::initTasks() {
|
||||||
TaskFactory* factory = TaskFactory::instance();
|
TaskFactory* factory = TaskFactory::instance();
|
||||||
if(factory == nullptr) {
|
if (factory == nullptr) {
|
||||||
/* Should never happen ! */
|
/* Should never happen ! */
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
||||||
void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline;
|
void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline;
|
||||||
#else
|
#else
|
||||||
void (*missedDeadlineFunc) (void) = nullptr;
|
void (*missedDeadlineFunc)(void) = nullptr;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* TMTC Distribution */
|
/* TMTC Distribution */
|
||||||
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
||||||
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
ReturnValue_t result = tmTcDistributor->addComponent(
|
ReturnValue_t result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
objects::CCSDS_PACKET_DISTRIBUTOR);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -73,13 +71,13 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask(
|
PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask(
|
||||||
"TMTC_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"TMTC_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Add component UDP Unix Bridge failed" << std::endl;
|
sif::error << "Add component UDP Unix Bridge failed" << std::endl;
|
||||||
}
|
}
|
||||||
PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask(
|
PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask(
|
||||||
"UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Add component UDP Polling failed" << std::endl;
|
sif::error << "Add component UDP Polling failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -87,47 +85,47 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* pusVerification = factory->createPeriodicTask(
|
PeriodicTaskIF* pusVerification = factory->createPeriodicTask(
|
||||||
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusEvents = factory->createPeriodicTask(
|
PeriodicTaskIF* pusEvents = factory->createPeriodicTask(
|
||||||
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
result = pusVerification->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask(
|
PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask(
|
||||||
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
}
|
}
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask(
|
PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask(
|
||||||
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT);
|
initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS);
|
initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
}
|
}
|
||||||
|
|
||||||
PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask(
|
PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask(
|
||||||
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
||||||
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -135,7 +133,7 @@ void initmission::initTasks() {
|
|||||||
"TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
#if OBSW_ADD_TEST_CODE == 1
|
#if OBSW_ADD_TEST_CODE == 1
|
||||||
result = testTask->addComponent(objects::TEST_TASK);
|
result = testTask->addComponent(objects::TEST_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
||||||
}
|
}
|
||||||
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
||||||
|
@ -4,6 +4,6 @@
|
|||||||
namespace initmission {
|
namespace initmission {
|
||||||
void initMission();
|
void initMission();
|
||||||
void initTasks();
|
void initTasks();
|
||||||
};
|
}; // namespace initmission
|
||||||
|
|
||||||
#endif /* BSP_LINUX_INITMISSION_H_ */
|
#endif /* BSP_LINUX_INITMISSION_H_ */
|
||||||
|
@ -1,14 +1,14 @@
|
|||||||
#include "ObjectFactory.h"
|
#include "ObjectFactory.h"
|
||||||
#include "OBSWConfig.h"
|
|
||||||
|
#include <fsfw/tmtcservices/CommandingServiceBase.h>
|
||||||
|
#include <fsfw/tmtcservices/PusServiceBase.h>
|
||||||
|
#include <mission/core/GenericFactory.h>
|
||||||
|
#include <mission/utility/TmFunnel.h>
|
||||||
#include <objects/systemObjectList.h>
|
#include <objects/systemObjectList.h>
|
||||||
#include <tmtc/apid.h>
|
#include <tmtc/apid.h>
|
||||||
#include <tmtc/pusIds.h>
|
#include <tmtc/pusIds.h>
|
||||||
|
|
||||||
#include <fsfw/tmtcservices/CommandingServiceBase.h>
|
#include "OBSWConfig.h"
|
||||||
#include <fsfw/tmtcservices/PusServiceBase.h>
|
|
||||||
|
|
||||||
#include <mission/core/GenericFactory.h>
|
|
||||||
#include <mission/utility/TmFunnel.h>
|
|
||||||
|
|
||||||
#if OBSW_USE_TMTC_TCP_BRIDGE == 0
|
#if OBSW_USE_TMTC_TCP_BRIDGE == 0
|
||||||
#include "fsfw/osal/common/UdpTcPollingTask.h"
|
#include "fsfw/osal/common/UdpTcPollingTask.h"
|
||||||
@ -20,12 +20,11 @@
|
|||||||
|
|
||||||
#include <fsfw/tmtcpacket/pus/tm.h>
|
#include <fsfw/tmtcpacket/pus/tm.h>
|
||||||
|
|
||||||
|
|
||||||
#if OBSW_ADD_TEST_CODE == 1
|
#if OBSW_ADD_TEST_CODE == 1
|
||||||
#include <test/testtasks/TestTask.h>
|
#include <test/testtasks/TestTask.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void Factory::setStaticFrameworkObjectIds(){
|
void Factory::setStaticFrameworkObjectIds() {
|
||||||
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
||||||
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
||||||
|
|
||||||
@ -40,7 +39,7 @@ void Factory::setStaticFrameworkObjectIds(){
|
|||||||
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::produce(void* args){
|
void ObjectFactory::produce(void* args) {
|
||||||
Factory::setStaticFrameworkObjectIds();
|
Factory::setStaticFrameworkObjectIds();
|
||||||
ObjectFactory::produceGenericObjects();
|
ObjectFactory::produceGenericObjects();
|
||||||
|
|
||||||
|
@ -1,10 +1,9 @@
|
|||||||
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
||||||
#define BSP_LINUX_OBJECTFACTORY_H_
|
#define BSP_LINUX_OBJECTFACTORY_H_
|
||||||
|
|
||||||
|
|
||||||
namespace ObjectFactory {
|
namespace ObjectFactory {
|
||||||
void setStatics();
|
void setStatics();
|
||||||
void produce(void* args);
|
void produce(void* args);
|
||||||
};
|
}; // namespace ObjectFactory
|
||||||
|
|
||||||
#endif /* BSP_LINUX_OBJECTFACTORY_H_ */
|
#endif /* BSP_LINUX_OBJECTFACTORY_H_ */
|
||||||
|
@ -7,7 +7,8 @@ extern "C" void __gcov_flush();
|
|||||||
#else
|
#else
|
||||||
void __gcov_flush() {
|
void __gcov_flush() {
|
||||||
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
||||||
"coverage information is desired.\n" << std::flush;
|
"coverage information is desired.\n"
|
||||||
|
<< std::flush;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -3,13 +3,9 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
void printChar(const char* character, bool errStream) {
|
void printChar(const char* character, bool errStream) {
|
||||||
if(errStream) {
|
if (errStream) {
|
||||||
putc(*character, stderr);
|
putc(*character, stderr);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
putc(*character, stdout);
|
putc(*character, stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,32 +1,31 @@
|
|||||||
#include "ArduinoComIF.h"
|
#include "ArduinoComIF.h"
|
||||||
#include "ArduinoCookie.h"
|
|
||||||
|
|
||||||
#include <fsfw/globalfunctions/DleEncoder.h>
|
|
||||||
#include <fsfw/globalfunctions/CRC.h>
|
#include <fsfw/globalfunctions/CRC.h>
|
||||||
|
#include <fsfw/globalfunctions/DleEncoder.h>
|
||||||
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
|
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
|
||||||
|
|
||||||
|
#include "ArduinoCookie.h"
|
||||||
|
|
||||||
// This only works on Linux
|
// This only works on Linux
|
||||||
#ifdef LINUX
|
#ifdef LINUX
|
||||||
#include <termios.h>
|
|
||||||
#include <fcntl.h>
|
#include <fcntl.h>
|
||||||
|
#include <termios.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#elif WIN32
|
#elif WIN32
|
||||||
#include <windows.h>
|
|
||||||
#include <strsafe.h>
|
#include <strsafe.h>
|
||||||
|
#include <windows.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
|
|
||||||
ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF,
|
ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF, const char *serialDevice)
|
||||||
const char *serialDevice):
|
: rxBuffer(MAX_PACKET_SIZE * MAX_NUMBER_OF_SPI_DEVICES * 10, true), SystemObject(setObjectId) {
|
||||||
rxBuffer(MAX_PACKET_SIZE * MAX_NUMBER_OF_SPI_DEVICES*10, true),
|
|
||||||
SystemObject(setObjectId) {
|
|
||||||
#ifdef LINUX
|
#ifdef LINUX
|
||||||
initialized = false;
|
initialized = false;
|
||||||
serialPort = ::open("/dev/ttyUSB0", O_RDWR);
|
serialPort = ::open("/dev/ttyUSB0", O_RDWR);
|
||||||
|
|
||||||
if (serialPort < 0) {
|
if (serialPort < 0) {
|
||||||
//configuration error
|
// configuration error
|
||||||
printf("Error %i from open: %s\n", errno, strerror(errno));
|
printf("Error %i from open: %s\n", errno, strerror(errno));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -44,73 +43,64 @@ ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF,
|
|||||||
tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication
|
tty.c_cflag &= ~CSTOPB; // Clear stop field, only one stop bit used in communication
|
||||||
tty.c_cflag |= CS8; // 8 bits per byte
|
tty.c_cflag |= CS8; // 8 bits per byte
|
||||||
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
||||||
tty.c_lflag &= ~ICANON; //Disable Canonical Mode
|
tty.c_lflag &= ~ICANON; // Disable Canonical Mode
|
||||||
tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars)
|
tty.c_oflag &= ~OPOST; // Prevent special interpretation of output bytes (e.g. newline chars)
|
||||||
tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed
|
tty.c_oflag &= ~ONLCR; // Prevent conversion of newline to carriage return/line feed
|
||||||
tty.c_cc[VTIME] = 0; // Non Blocking
|
tty.c_cc[VTIME] = 0; // Non Blocking
|
||||||
tty.c_cc[VMIN] = 0;
|
tty.c_cc[VMIN] = 0;
|
||||||
|
|
||||||
cfsetispeed(&tty, B9600); //Baudrate
|
cfsetispeed(&tty, B9600); // Baudrate
|
||||||
|
|
||||||
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
||||||
//printf("Error %i from tcsetattr: %s\n", errno, strerror(errno));
|
// printf("Error %i from tcsetattr: %s\n", errno, strerror(errno));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
initialized = true;
|
initialized = true;
|
||||||
#elif WIN32
|
#elif WIN32
|
||||||
DCB serialParams = { 0 };
|
DCB serialParams = {0};
|
||||||
|
|
||||||
// we need to ask the COM port from the user.
|
// we need to ask the COM port from the user.
|
||||||
if(promptComIF) {
|
if (promptComIF) {
|
||||||
sif::info << "Please enter the COM port (c to cancel): " << std::flush;
|
sif::info << "Please enter the COM port (c to cancel): " << std::flush;
|
||||||
std::string comPort;
|
std::string comPort;
|
||||||
while(hCom == INVALID_HANDLE_VALUE) {
|
while (hCom == INVALID_HANDLE_VALUE) {
|
||||||
|
|
||||||
std::getline(std::cin, comPort);
|
std::getline(std::cin, comPort);
|
||||||
if(comPort[0] == 'c') {
|
if (comPort[0] == 'c') {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
const TCHAR *pcCommPort = comPort.c_str();
|
const TCHAR *pcCommPort = comPort.c_str();
|
||||||
hCom = CreateFileA(pcCommPort, //port name
|
hCom = CreateFileA(pcCommPort, // port name
|
||||||
GENERIC_READ | GENERIC_WRITE, //Read/Write
|
GENERIC_READ | GENERIC_WRITE, // Read/Write
|
||||||
0, // No Sharing
|
0, // No Sharing
|
||||||
NULL, // No Security
|
NULL, // No Security
|
||||||
OPEN_EXISTING,// Open existing port only
|
OPEN_EXISTING, // Open existing port only
|
||||||
0, // Non Overlapped I/O
|
0, // Non Overlapped I/O
|
||||||
NULL); // Null for Comm Devices
|
NULL); // Null for Comm Devices
|
||||||
|
|
||||||
if (hCom == INVALID_HANDLE_VALUE)
|
if (hCom == INVALID_HANDLE_VALUE) {
|
||||||
{
|
if (GetLastError() == 2) {
|
||||||
if(GetLastError() == 2) {
|
|
||||||
sif::error << "COM Port does not found!" << std::endl;
|
sif::error << "COM Port does not found!" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
TCHAR err[128];
|
TCHAR err[128];
|
||||||
FormatMessage(FORMAT_MESSAGE_FROM_SYSTEM, NULL,
|
FormatMessage(FORMAT_MESSAGE_FROM_SYSTEM, NULL, GetLastError(),
|
||||||
GetLastError(),
|
MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), err, sizeof(err), NULL);
|
||||||
MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
|
|
||||||
err, sizeof(err), NULL);
|
|
||||||
// Handle the error.
|
// Handle the error.
|
||||||
sif::info << "CreateFileA Error code: " << GetLastError()
|
sif::info << "CreateFileA Error code: " << GetLastError() << std::endl;
|
||||||
<< std::endl;
|
|
||||||
sif::error << err << std::flush;
|
sif::error << err << std::flush;
|
||||||
}
|
}
|
||||||
sif::info << "Please enter a valid COM port: " << std::flush;
|
sif::info << "Please enter a valid COM port: " << std::flush;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
serialParams.DCBlength = sizeof(serialParams);
|
serialParams.DCBlength = sizeof(serialParams);
|
||||||
if(baudRate == 9600) {
|
if (baudRate == 9600) {
|
||||||
serialParams.BaudRate = CBR_9600;
|
serialParams.BaudRate = CBR_9600;
|
||||||
}
|
}
|
||||||
if(baudRate == 115200) {
|
if (baudRate == 115200) {
|
||||||
serialParams.BaudRate = CBR_115200;
|
serialParams.BaudRate = CBR_115200;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
serialParams.BaudRate = baudRate;
|
serialParams.BaudRate = baudRate;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -119,7 +109,7 @@ ArduinoComIF::ArduinoComIF(object_id_t setObjectId, bool promptComIF,
|
|||||||
serialParams.StopBits = ONESTOPBIT;
|
serialParams.StopBits = ONESTOPBIT;
|
||||||
SetCommState(hCom, &serialParams);
|
SetCommState(hCom, &serialParams);
|
||||||
|
|
||||||
COMMTIMEOUTS timeout = { 0 };
|
COMMTIMEOUTS timeout = {0};
|
||||||
// This will set the read operation to be blocking until data is received
|
// This will set the read operation to be blocking until data is received
|
||||||
// and then read continuously until there is a gap of one millisecond.
|
// and then read continuously until there is a gap of one millisecond.
|
||||||
timeout.ReadIntervalTimeout = 1;
|
timeout.ReadIntervalTimeout = 1;
|
||||||
@ -139,36 +129,29 @@ ArduinoComIF::~ArduinoComIF() {
|
|||||||
CloseHandle(hCom);
|
CloseHandle(hCom);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
ReturnValue_t ArduinoComIF::initializeInterface(CookieIF * cookie) {
|
ReturnValue_t ArduinoComIF::initializeInterface(CookieIF *cookie) {
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t ArduinoComIF::sendMessage(CookieIF *cookie, const uint8_t *data,
|
ReturnValue_t ArduinoComIF::sendMessage(CookieIF *cookie, const uint8_t *data, size_t len) {
|
||||||
size_t len) {
|
ArduinoCookie *arduinoCookie = dynamic_cast<ArduinoCookie *>(cookie);
|
||||||
ArduinoCookie *arduinoCookie = dynamic_cast<ArduinoCookie*>(cookie);
|
|
||||||
if (arduinoCookie == nullptr) {
|
if (arduinoCookie == nullptr) {
|
||||||
return INVALID_COOKIE_TYPE;
|
return INVALID_COOKIE_TYPE;
|
||||||
}
|
}
|
||||||
|
|
||||||
return sendMessage(arduinoCookie->command, arduinoCookie->address, data,
|
return sendMessage(arduinoCookie->command, arduinoCookie->address, data, len);
|
||||||
len);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t ArduinoComIF::getSendSuccess(CookieIF *cookie) {
|
ReturnValue_t ArduinoComIF::getSendSuccess(CookieIF *cookie) { return RETURN_OK; }
|
||||||
|
|
||||||
|
ReturnValue_t ArduinoComIF::requestReceiveMessage(CookieIF *cookie, size_t requestLen) {
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t ArduinoComIF::requestReceiveMessage(CookieIF *cookie,
|
ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) {
|
||||||
size_t requestLen) {
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
|
|
||||||
uint8_t **buffer, size_t *size) {
|
|
||||||
|
|
||||||
handleSerialPortRx();
|
handleSerialPortRx();
|
||||||
|
|
||||||
ArduinoCookie *arduinoCookie = dynamic_cast<ArduinoCookie*>(cookie);
|
ArduinoCookie *arduinoCookie = dynamic_cast<ArduinoCookie *>(cookie);
|
||||||
if (arduinoCookie == nullptr) {
|
if (arduinoCookie == nullptr) {
|
||||||
return INVALID_COOKIE_TYPE;
|
return INVALID_COOKIE_TYPE;
|
||||||
}
|
}
|
||||||
@ -178,13 +161,13 @@ ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t ArduinoComIF::sendMessage(uint8_t command,
|
ReturnValue_t ArduinoComIF::sendMessage(uint8_t command, uint8_t address, const uint8_t *data,
|
||||||
uint8_t address, const uint8_t *data, size_t dataLen) {
|
size_t dataLen) {
|
||||||
if (dataLen > UINT16_MAX) {
|
if (dataLen > UINT16_MAX) {
|
||||||
return TOO_MUCH_DATA;
|
return TOO_MUCH_DATA;
|
||||||
}
|
}
|
||||||
|
|
||||||
//being conservative here
|
// being conservative here
|
||||||
uint8_t sendBuffer[(dataLen + 6) * 2 + 2];
|
uint8_t sendBuffer[(dataLen + 6) * 2 + 2];
|
||||||
|
|
||||||
sendBuffer[0] = DleEncoder::STX_CHAR;
|
sendBuffer[0] = DleEncoder::STX_CHAR;
|
||||||
@ -193,61 +176,59 @@ ReturnValue_t ArduinoComIF::sendMessage(uint8_t command,
|
|||||||
size_t remainingLen = sizeof(sendBuffer) - 1;
|
size_t remainingLen = sizeof(sendBuffer) - 1;
|
||||||
size_t encodedLen = 0;
|
size_t encodedLen = 0;
|
||||||
|
|
||||||
ReturnValue_t result = DleEncoder::encode(&command, 1, currentPosition,
|
ReturnValue_t result =
|
||||||
remainingLen, &encodedLen, false);
|
DleEncoder::encode(&command, 1, currentPosition, remainingLen, &encodedLen, false);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
currentPosition += encodedLen;
|
currentPosition += encodedLen;
|
||||||
remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen
|
remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen
|
||||||
|
|
||||||
result = DleEncoder::encode(&address, 1, currentPosition, remainingLen,
|
result = DleEncoder::encode(&address, 1, currentPosition, remainingLen, &encodedLen, false);
|
||||||
&encodedLen, false);
|
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
currentPosition += encodedLen;
|
currentPosition += encodedLen;
|
||||||
remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen
|
remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen
|
||||||
|
|
||||||
uint8_t temporaryBuffer[2];
|
uint8_t temporaryBuffer[2];
|
||||||
|
|
||||||
//note to Lukas: yes we _could_ use Serialize here, but for 16 bit it is a bit too much...
|
// note to Lukas: yes we _could_ use Serialize here, but for 16 bit it is a bit too much...
|
||||||
temporaryBuffer[0] = dataLen >> 8; //we checked dataLen above
|
temporaryBuffer[0] = dataLen >> 8; // we checked dataLen above
|
||||||
temporaryBuffer[1] = dataLen;
|
temporaryBuffer[1] = dataLen;
|
||||||
|
|
||||||
result = DleEncoder::encode(temporaryBuffer, 2, currentPosition,
|
result =
|
||||||
remainingLen, &encodedLen, false);
|
DleEncoder::encode(temporaryBuffer, 2, currentPosition, remainingLen, &encodedLen, false);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
currentPosition += encodedLen;
|
currentPosition += encodedLen;
|
||||||
remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen
|
remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen
|
||||||
|
|
||||||
//encoding the actual data
|
// encoding the actual data
|
||||||
result = DleEncoder::encode(data, dataLen, currentPosition, remainingLen,
|
result = DleEncoder::encode(data, dataLen, currentPosition, remainingLen, &encodedLen, false);
|
||||||
&encodedLen, false);
|
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
currentPosition += encodedLen;
|
currentPosition += encodedLen;
|
||||||
remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen
|
remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen
|
||||||
|
|
||||||
uint16_t crc = CRC::crc16ccitt(&command, 1);
|
uint16_t crc = CRC::crc16ccitt(&command, 1);
|
||||||
crc = CRC::crc16ccitt(&address, 1, crc);
|
crc = CRC::crc16ccitt(&address, 1, crc);
|
||||||
//fortunately the length is still there
|
// fortunately the length is still there
|
||||||
crc = CRC::crc16ccitt(temporaryBuffer, 2, crc);
|
crc = CRC::crc16ccitt(temporaryBuffer, 2, crc);
|
||||||
crc = CRC::crc16ccitt(data, dataLen, crc);
|
crc = CRC::crc16ccitt(data, dataLen, crc);
|
||||||
|
|
||||||
temporaryBuffer[0] = crc >> 8;
|
temporaryBuffer[0] = crc >> 8;
|
||||||
temporaryBuffer[1] = crc;
|
temporaryBuffer[1] = crc;
|
||||||
|
|
||||||
result = DleEncoder::encode(temporaryBuffer, 2, currentPosition,
|
result =
|
||||||
remainingLen, &encodedLen, false);
|
DleEncoder::encode(temporaryBuffer, 2, currentPosition, remainingLen, &encodedLen, false);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
currentPosition += encodedLen;
|
currentPosition += encodedLen;
|
||||||
remainingLen -= encodedLen; //DleEncoder will never return encodedLen > remainingLen
|
remainingLen -= encodedLen; // DleEncoder will never return encodedLen > remainingLen
|
||||||
|
|
||||||
if (remainingLen > 0) {
|
if (remainingLen > 0) {
|
||||||
*currentPosition = DleEncoder::ETX_CHAR;
|
*currentPosition = DleEncoder::ETX_CHAR;
|
||||||
@ -259,12 +240,12 @@ ReturnValue_t ArduinoComIF::sendMessage(uint8_t command,
|
|||||||
#ifdef LINUX
|
#ifdef LINUX
|
||||||
ssize_t writtenlen = ::write(serialPort, sendBuffer, encodedLen);
|
ssize_t writtenlen = ::write(serialPort, sendBuffer, encodedLen);
|
||||||
if (writtenlen < 0) {
|
if (writtenlen < 0) {
|
||||||
//we could try to find out what happened...
|
// we could try to find out what happened...
|
||||||
return RETURN_FAILED;
|
return RETURN_FAILED;
|
||||||
}
|
}
|
||||||
if (writtenlen != encodedLen) {
|
if (writtenlen != encodedLen) {
|
||||||
//the OS failed us, we do not try to block until everything is written, as
|
// the OS failed us, we do not try to block until everything is written, as
|
||||||
//we can not block the whole system here
|
// we can not block the whole system here
|
||||||
return RETURN_FAILED;
|
return RETURN_FAILED;
|
||||||
}
|
}
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
@ -279,8 +260,7 @@ void ArduinoComIF::handleSerialPortRx() {
|
|||||||
|
|
||||||
uint8_t dataFromSerial[availableSpace];
|
uint8_t dataFromSerial[availableSpace];
|
||||||
|
|
||||||
ssize_t bytesRead = read(serialPort, dataFromSerial,
|
ssize_t bytesRead = read(serialPort, dataFromSerial, sizeof(dataFromSerial));
|
||||||
sizeof(dataFromSerial));
|
|
||||||
|
|
||||||
if (bytesRead < 0) {
|
if (bytesRead < 0) {
|
||||||
return;
|
return;
|
||||||
@ -292,18 +272,17 @@ void ArduinoComIF::handleSerialPortRx() {
|
|||||||
|
|
||||||
uint32_t dataLenReceivedSoFar = 0;
|
uint32_t dataLenReceivedSoFar = 0;
|
||||||
|
|
||||||
rxBuffer.readData(dataReceivedSoFar, sizeof(dataReceivedSoFar), true,
|
rxBuffer.readData(dataReceivedSoFar, sizeof(dataReceivedSoFar), true, &dataLenReceivedSoFar);
|
||||||
&dataLenReceivedSoFar);
|
|
||||||
|
|
||||||
//look for STX
|
// look for STX
|
||||||
size_t firstSTXinRawData = 0;
|
size_t firstSTXinRawData = 0;
|
||||||
while ((firstSTXinRawData < dataLenReceivedSoFar)
|
while ((firstSTXinRawData < dataLenReceivedSoFar) &&
|
||||||
&& (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR)) {
|
(dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR)) {
|
||||||
firstSTXinRawData++;
|
firstSTXinRawData++;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR) {
|
if (dataReceivedSoFar[firstSTXinRawData] != DleEncoder::STX_CHAR) {
|
||||||
//there is no STX in our data, throw it away...
|
// there is no STX in our data, throw it away...
|
||||||
rxBuffer.deleteData(dataLenReceivedSoFar);
|
rxBuffer.deleteData(dataLenReceivedSoFar);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -313,10 +292,9 @@ void ArduinoComIF::handleSerialPortRx() {
|
|||||||
|
|
||||||
size_t readSize = 0;
|
size_t readSize = 0;
|
||||||
|
|
||||||
ReturnValue_t result = DleEncoder::decode(
|
ReturnValue_t result = DleEncoder::decode(dataReceivedSoFar + firstSTXinRawData,
|
||||||
dataReceivedSoFar + firstSTXinRawData,
|
dataLenReceivedSoFar - firstSTXinRawData, &readSize,
|
||||||
dataLenReceivedSoFar - firstSTXinRawData, &readSize, packet,
|
packet, sizeof(packet), &packetLen);
|
||||||
sizeof(packet), &packetLen);
|
|
||||||
|
|
||||||
size_t toDelete = firstSTXinRawData;
|
size_t toDelete = firstSTXinRawData;
|
||||||
if (result == HasReturnvaluesIF::RETURN_OK) {
|
if (result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
@ -327,20 +305,18 @@ void ArduinoComIF::handleSerialPortRx() {
|
|||||||
toDelete += readSize;
|
toDelete += readSize;
|
||||||
}
|
}
|
||||||
|
|
||||||
//remove Data which was processed
|
// remove Data which was processed
|
||||||
rxBuffer.deleteData(toDelete);
|
rxBuffer.deleteData(toDelete);
|
||||||
#elif WIN32
|
#elif WIN32
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void ArduinoComIF::setBaudrate(uint32_t baudRate) {
|
void ArduinoComIF::setBaudrate(uint32_t baudRate) { this->baudRate = baudRate; }
|
||||||
this->baudRate = baudRate;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ArduinoComIF::handlePacket(uint8_t *packet, size_t packetLen) {
|
void ArduinoComIF::handlePacket(uint8_t *packet, size_t packetLen) {
|
||||||
uint16_t crc = CRC::crc16ccitt(packet, packetLen);
|
uint16_t crc = CRC::crc16ccitt(packet, packetLen);
|
||||||
if (crc != 0) {
|
if (crc != 0) {
|
||||||
//CRC error
|
// CRC error
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -350,26 +326,25 @@ void ArduinoComIF::handlePacket(uint8_t *packet, size_t packetLen) {
|
|||||||
uint16_t size = (packet[2] << 8) + packet[3];
|
uint16_t size = (packet[2] << 8) + packet[3];
|
||||||
|
|
||||||
if (size != packetLen - 6) {
|
if (size != packetLen - 6) {
|
||||||
//Invalid Length
|
// Invalid Length
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (command) {
|
switch (command) {
|
||||||
case ArduinoCookie::SPI: {
|
case ArduinoCookie::SPI: {
|
||||||
//ArduinoCookie **itsComplicated;
|
// ArduinoCookie **itsComplicated;
|
||||||
auto findIter = spiMap.find(address);
|
auto findIter = spiMap.find(address);
|
||||||
if (findIter == spiMap.end()) {
|
if (findIter == spiMap.end()) {
|
||||||
//we do no know this address
|
// we do no know this address
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
ArduinoCookie& cookie = findIter->second;
|
ArduinoCookie &cookie = findIter->second;
|
||||||
if (packetLen > cookie.maxReplySize + 6) {
|
if (packetLen > cookie.maxReplySize + 6) {
|
||||||
packetLen = cookie.maxReplySize + 6;
|
packetLen = cookie.maxReplySize + 6;
|
||||||
}
|
}
|
||||||
std::memcpy(cookie.replyBuffer.data(), packet + 4, packetLen - 6);
|
std::memcpy(cookie.replyBuffer.data(), packet + 4, packetLen - 6);
|
||||||
cookie.receivedDataLen = packetLen - 6;
|
cookie.receivedDataLen = packetLen - 6;
|
||||||
}
|
} break;
|
||||||
break;
|
|
||||||
default:
|
default:
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -4,8 +4,8 @@
|
|||||||
#include <fsfw/container/FixedMap.h>
|
#include <fsfw/container/FixedMap.h>
|
||||||
#include <fsfw/container/SimpleRingBuffer.h>
|
#include <fsfw/container/SimpleRingBuffer.h>
|
||||||
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
|
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
|
||||||
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
|
||||||
#include <fsfw/objectmanager/SystemObject.h>
|
#include <fsfw/objectmanager/SystemObject.h>
|
||||||
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
|
|
||||||
#include <cstdint>
|
#include <cstdint>
|
||||||
#include <map>
|
#include <map>
|
||||||
@ -14,12 +14,11 @@
|
|||||||
#include <windows.h>
|
#include <windows.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//Forward declaration, so users don't peek
|
// Forward declaration, so users don't peek
|
||||||
class ArduinoCookie;
|
class ArduinoCookie;
|
||||||
|
|
||||||
class ArduinoComIF: public SystemObject,
|
class ArduinoComIF : public SystemObject, public DeviceCommunicationIF {
|
||||||
public DeviceCommunicationIF {
|
public:
|
||||||
public:
|
|
||||||
static const uint8_t MAX_NUMBER_OF_SPI_DEVICES = 8;
|
static const uint8_t MAX_NUMBER_OF_SPI_DEVICES = 8;
|
||||||
static const uint8_t MAX_PACKET_SIZE = 64;
|
static const uint8_t MAX_PACKET_SIZE = 64;
|
||||||
|
|
||||||
@ -33,16 +32,15 @@ public:
|
|||||||
virtual ~ArduinoComIF();
|
virtual ~ArduinoComIF();
|
||||||
|
|
||||||
/** DeviceCommunicationIF overrides */
|
/** DeviceCommunicationIF overrides */
|
||||||
virtual ReturnValue_t initializeInterface(CookieIF * cookie) override;
|
virtual ReturnValue_t initializeInterface(CookieIF *cookie) override;
|
||||||
virtual ReturnValue_t sendMessage(CookieIF *cookie,
|
virtual ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData,
|
||||||
const uint8_t * sendData, size_t sendLen) override;
|
size_t sendLen) override;
|
||||||
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) override;
|
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) override;
|
||||||
virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie,
|
virtual ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override;
|
||||||
size_t requestLen) override;
|
virtual ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
|
||||||
virtual ReturnValue_t readReceivedMessage(CookieIF *cookie,
|
size_t *size) override;
|
||||||
uint8_t **buffer, size_t *size) override;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#ifdef LINUX
|
#ifdef LINUX
|
||||||
#elif WIN32
|
#elif WIN32
|
||||||
HANDLE hCom = INVALID_HANDLE_VALUE;
|
HANDLE hCom = INVALID_HANDLE_VALUE;
|
||||||
@ -54,13 +52,12 @@ private:
|
|||||||
// Default baud rate is 9600 for now.
|
// Default baud rate is 9600 for now.
|
||||||
uint32_t baudRate = 9600;
|
uint32_t baudRate = 9600;
|
||||||
|
|
||||||
//used to know where to put the data if a reply is received
|
// used to know where to put the data if a reply is received
|
||||||
std::map<uint8_t, ArduinoCookie> spiMap;
|
std::map<uint8_t, ArduinoCookie> spiMap;
|
||||||
|
|
||||||
SimpleRingBuffer rxBuffer;
|
SimpleRingBuffer rxBuffer;
|
||||||
|
|
||||||
ReturnValue_t sendMessage(uint8_t command, uint8_t address,
|
ReturnValue_t sendMessage(uint8_t command, uint8_t address, const uint8_t *data, size_t dataLen);
|
||||||
const uint8_t *data, size_t dataLen);
|
|
||||||
void handleSerialPortRx();
|
void handleSerialPortRx();
|
||||||
|
|
||||||
void handlePacket(uint8_t *packet, size_t packetLen);
|
void handlePacket(uint8_t *packet, size_t packetLen);
|
||||||
|
@ -1,8 +1,8 @@
|
|||||||
#include <bsp_hosted/comIF/ArduinoCookie.h>
|
#include <bsp_hosted/comIF/ArduinoCookie.h>
|
||||||
|
|
||||||
ArduinoCookie::ArduinoCookie(Protocol_t protocol, uint8_t address,
|
ArduinoCookie::ArduinoCookie(Protocol_t protocol, uint8_t address, const size_t maxReplySize)
|
||||||
const size_t maxReplySize) :
|
: protocol(protocol),
|
||||||
protocol(protocol), command(protocol), address(address),
|
command(protocol),
|
||||||
maxReplySize(maxReplySize), replyBuffer(maxReplySize) {
|
address(address),
|
||||||
}
|
maxReplySize(maxReplySize),
|
||||||
|
replyBuffer(maxReplySize) {}
|
||||||
|
@ -2,18 +2,14 @@
|
|||||||
#define MISSION_ARDUINO_ARDUINOCOOKIE_H_
|
#define MISSION_ARDUINO_ARDUINOCOOKIE_H_
|
||||||
|
|
||||||
#include <fsfw/devicehandlers/CookieIF.h>
|
#include <fsfw/devicehandlers/CookieIF.h>
|
||||||
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
class ArduinoCookie: public CookieIF {
|
class ArduinoCookie : public CookieIF {
|
||||||
public:
|
public:
|
||||||
enum Protocol_t: uint8_t {
|
enum Protocol_t : uint8_t { INVALID, SPI, I2C };
|
||||||
INVALID,
|
|
||||||
SPI,
|
|
||||||
I2C
|
|
||||||
};
|
|
||||||
|
|
||||||
ArduinoCookie(Protocol_t protocol, uint8_t address,
|
ArduinoCookie(Protocol_t protocol, uint8_t address, const size_t maxReplySize);
|
||||||
const size_t maxReplySize);
|
|
||||||
|
|
||||||
Protocol_t protocol;
|
Protocol_t protocol;
|
||||||
uint8_t command;
|
uint8_t command;
|
||||||
@ -21,7 +17,6 @@ public:
|
|||||||
std::vector<uint8_t> replyBuffer;
|
std::vector<uint8_t> replyBuffer;
|
||||||
size_t receivedDataLen = 0;
|
size_t receivedDataLen = 0;
|
||||||
size_t maxReplySize;
|
size_t maxReplySize;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* MISSION_ARDUINO_ARDUINOCOOKIE_H_ */
|
#endif /* MISSION_ARDUINO_ARDUINOCOOKIE_H_ */
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
#define FSFWCONFIG_DEVICES_GPIOIDS_H_
|
#define FSFWCONFIG_DEVICES_GPIOIDS_H_
|
||||||
|
|
||||||
namespace gpioIds {
|
namespace gpioIds {
|
||||||
enum gpioId_t {
|
enum gpioId_t {
|
||||||
HEATER_0,
|
HEATER_0,
|
||||||
HEATER_1,
|
HEATER_1,
|
||||||
HEATER_2,
|
HEATER_2,
|
||||||
@ -48,10 +48,7 @@ namespace gpioIds {
|
|||||||
SPI_MUX_BIT_4,
|
SPI_MUX_BIT_4,
|
||||||
SPI_MUX_BIT_5,
|
SPI_MUX_BIT_5,
|
||||||
SPI_MUX_BIT_6
|
SPI_MUX_BIT_6
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */
|
#endif /* FSFWCONFIG_DEVICES_GPIOIDS_H_ */
|
||||||
|
@ -4,8 +4,8 @@
|
|||||||
#include <OBSWConfig.h>
|
#include <OBSWConfig.h>
|
||||||
|
|
||||||
namespace pcduSwitches {
|
namespace pcduSwitches {
|
||||||
/* Switches are uint8_t datatype and go from 0 to 255 */
|
/* Switches are uint8_t datatype and go from 0 to 255 */
|
||||||
enum SwitcherList {
|
enum SwitcherList {
|
||||||
Q7S,
|
Q7S,
|
||||||
PAYLOAD_PCDU_CH1,
|
PAYLOAD_PCDU_CH1,
|
||||||
RW,
|
RW,
|
||||||
@ -24,35 +24,34 @@ namespace pcduSwitches {
|
|||||||
PLOC,
|
PLOC,
|
||||||
ACS_BOARD_SIDE_A,
|
ACS_BOARD_SIDE_A,
|
||||||
NUMBER_OF_SWITCHES
|
NUMBER_OF_SWITCHES
|
||||||
};
|
};
|
||||||
|
|
||||||
static const uint8_t ON = 1;
|
static const uint8_t ON = 1;
|
||||||
static const uint8_t OFF = 0;
|
static const uint8_t OFF = 0;
|
||||||
|
|
||||||
/* Output states after reboot of the PDUs */
|
/* Output states after reboot of the PDUs */
|
||||||
static const uint8_t INIT_STATE_Q7S = ON;
|
static const uint8_t INIT_STATE_Q7S = ON;
|
||||||
static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF;
|
static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH1 = OFF;
|
||||||
static const uint8_t INIT_STATE_RW = OFF;
|
static const uint8_t INIT_STATE_RW = OFF;
|
||||||
#if BOARD_TE0720 == 1
|
#if BOARD_TE0720 == 1
|
||||||
/* Because the TE0720 is not connected to the PCDU, this switch is always on */
|
/* Because the TE0720 is not connected to the PCDU, this switch is always on */
|
||||||
static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON;
|
static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = ON;
|
||||||
#else
|
#else
|
||||||
static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF;
|
static const uint8_t INIT_STATE_TCS_BOARD_8V_HEATER_IN = OFF;
|
||||||
#endif
|
#endif
|
||||||
static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF;
|
static const uint8_t INIT_STATE_SUS_REDUNDANT = OFF;
|
||||||
static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF;
|
static const uint8_t INIT_STATE_DEPLOYMENT_MECHANISM = OFF;
|
||||||
static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF;
|
static const uint8_t INIT_STATE_PAYLOAD_PCDU_CH6 = OFF;
|
||||||
static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF;
|
static const uint8_t INIT_STATE_ACS_BOARD_SIDE_B = OFF;
|
||||||
static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF;
|
static const uint8_t INIT_STATE_PAYLOAD_CAMERA = OFF;
|
||||||
static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF;
|
static const uint8_t INIT_STATE_TCS_BOARD_3V3 = OFF;
|
||||||
static const uint8_t INIT_STATE_SYRLINKS = OFF;
|
static const uint8_t INIT_STATE_SYRLINKS = OFF;
|
||||||
static const uint8_t INIT_STATE_STAR_TRACKER = OFF;
|
static const uint8_t INIT_STATE_STAR_TRACKER = OFF;
|
||||||
static const uint8_t INIT_STATE_MGT = OFF;
|
static const uint8_t INIT_STATE_MGT = OFF;
|
||||||
static const uint8_t INIT_STATE_SUS_NOMINAL = OFF;
|
static const uint8_t INIT_STATE_SUS_NOMINAL = OFF;
|
||||||
static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF;
|
static const uint8_t INIT_STATE_SOLAR_CELL_EXP = OFF;
|
||||||
static const uint8_t INIT_STATE_PLOC = OFF;
|
static const uint8_t INIT_STATE_PLOC = OFF;
|
||||||
static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF;
|
static const uint8_t INIT_STATE_ACS_BOARD_SIDE_A = OFF;
|
||||||
}
|
} // namespace pcduSwitches
|
||||||
|
|
||||||
|
|
||||||
#endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */
|
#endif /* FSFWCONFIG_DEVICES_POWERSWITCHERLIST_H_ */
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
#define CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_
|
#define CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_
|
||||||
|
|
||||||
#include <common/config/commonSubsystemIds.h>
|
#include <common/config/commonSubsystemIds.h>
|
||||||
|
|
||||||
#include <cstdint>
|
#include <cstdint>
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -9,9 +10,7 @@
|
|||||||
* Numbers 0-80 are reserved for FSFW Subsystem IDs (framework/events/)
|
* Numbers 0-80 are reserved for FSFW Subsystem IDs (framework/events/)
|
||||||
*/
|
*/
|
||||||
namespace SUBSYSTEM_ID {
|
namespace SUBSYSTEM_ID {
|
||||||
enum: uint8_t {
|
enum : uint8_t { SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END };
|
||||||
SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END
|
|
||||||
};
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ */
|
#endif /* CONFIG_EVENTS_SUBSYSTEMIDRANGES_H_ */
|
||||||
|
@ -89,173 +89,173 @@ const char *ACK_FAILURE_STRING = "ACK_FAILURE";
|
|||||||
const char *EXE_FAILURE_STRING = "EXE_FAILURE";
|
const char *EXE_FAILURE_STRING = "EXE_FAILURE";
|
||||||
const char *CRC_FAILURE_EVENT_STRING = "CRC_FAILURE_EVENT";
|
const char *CRC_FAILURE_EVENT_STRING = "CRC_FAILURE_EVENT";
|
||||||
|
|
||||||
const char * translateEvents(Event event) {
|
const char *translateEvents(Event event) {
|
||||||
switch( (event & 0xffff) ) {
|
switch ((event & 0xffff)) {
|
||||||
case(2200):
|
case (2200):
|
||||||
return STORE_SEND_WRITE_FAILED_STRING;
|
return STORE_SEND_WRITE_FAILED_STRING;
|
||||||
case(2201):
|
case (2201):
|
||||||
return STORE_WRITE_FAILED_STRING;
|
return STORE_WRITE_FAILED_STRING;
|
||||||
case(2202):
|
case (2202):
|
||||||
return STORE_SEND_READ_FAILED_STRING;
|
return STORE_SEND_READ_FAILED_STRING;
|
||||||
case(2203):
|
case (2203):
|
||||||
return STORE_READ_FAILED_STRING;
|
return STORE_READ_FAILED_STRING;
|
||||||
case(2204):
|
case (2204):
|
||||||
return UNEXPECTED_MSG_STRING;
|
return UNEXPECTED_MSG_STRING;
|
||||||
case(2205):
|
case (2205):
|
||||||
return STORING_FAILED_STRING;
|
return STORING_FAILED_STRING;
|
||||||
case(2206):
|
case (2206):
|
||||||
return TM_DUMP_FAILED_STRING;
|
return TM_DUMP_FAILED_STRING;
|
||||||
case(2207):
|
case (2207):
|
||||||
return STORE_INIT_FAILED_STRING;
|
return STORE_INIT_FAILED_STRING;
|
||||||
case(2208):
|
case (2208):
|
||||||
return STORE_INIT_EMPTY_STRING;
|
return STORE_INIT_EMPTY_STRING;
|
||||||
case(2209):
|
case (2209):
|
||||||
return STORE_CONTENT_CORRUPTED_STRING;
|
return STORE_CONTENT_CORRUPTED_STRING;
|
||||||
case(2210):
|
case (2210):
|
||||||
return STORE_INITIALIZE_STRING;
|
return STORE_INITIALIZE_STRING;
|
||||||
case(2211):
|
case (2211):
|
||||||
return INIT_DONE_STRING;
|
return INIT_DONE_STRING;
|
||||||
case(2212):
|
case (2212):
|
||||||
return DUMP_FINISHED_STRING;
|
return DUMP_FINISHED_STRING;
|
||||||
case(2213):
|
case (2213):
|
||||||
return DELETION_FINISHED_STRING;
|
return DELETION_FINISHED_STRING;
|
||||||
case(2214):
|
case (2214):
|
||||||
return DELETION_FAILED_STRING;
|
return DELETION_FAILED_STRING;
|
||||||
case(2215):
|
case (2215):
|
||||||
return AUTO_CATALOGS_SENDING_FAILED_STRING;
|
return AUTO_CATALOGS_SENDING_FAILED_STRING;
|
||||||
case(2600):
|
case (2600):
|
||||||
return GET_DATA_FAILED_STRING;
|
return GET_DATA_FAILED_STRING;
|
||||||
case(2601):
|
case (2601):
|
||||||
return STORE_DATA_FAILED_STRING;
|
return STORE_DATA_FAILED_STRING;
|
||||||
case(2800):
|
case (2800):
|
||||||
return DEVICE_BUILDING_COMMAND_FAILED_STRING;
|
return DEVICE_BUILDING_COMMAND_FAILED_STRING;
|
||||||
case(2801):
|
case (2801):
|
||||||
return DEVICE_SENDING_COMMAND_FAILED_STRING;
|
return DEVICE_SENDING_COMMAND_FAILED_STRING;
|
||||||
case(2802):
|
case (2802):
|
||||||
return DEVICE_REQUESTING_REPLY_FAILED_STRING;
|
return DEVICE_REQUESTING_REPLY_FAILED_STRING;
|
||||||
case(2803):
|
case (2803):
|
||||||
return DEVICE_READING_REPLY_FAILED_STRING;
|
return DEVICE_READING_REPLY_FAILED_STRING;
|
||||||
case(2804):
|
case (2804):
|
||||||
return DEVICE_INTERPRETING_REPLY_FAILED_STRING;
|
return DEVICE_INTERPRETING_REPLY_FAILED_STRING;
|
||||||
case(2805):
|
case (2805):
|
||||||
return DEVICE_MISSED_REPLY_STRING;
|
return DEVICE_MISSED_REPLY_STRING;
|
||||||
case(2806):
|
case (2806):
|
||||||
return DEVICE_UNKNOWN_REPLY_STRING;
|
return DEVICE_UNKNOWN_REPLY_STRING;
|
||||||
case(2807):
|
case (2807):
|
||||||
return DEVICE_UNREQUESTED_REPLY_STRING;
|
return DEVICE_UNREQUESTED_REPLY_STRING;
|
||||||
case(2808):
|
case (2808):
|
||||||
return INVALID_DEVICE_COMMAND_STRING;
|
return INVALID_DEVICE_COMMAND_STRING;
|
||||||
case(2809):
|
case (2809):
|
||||||
return MONITORING_LIMIT_EXCEEDED_STRING;
|
return MONITORING_LIMIT_EXCEEDED_STRING;
|
||||||
case(2810):
|
case (2810):
|
||||||
return MONITORING_AMBIGUOUS_STRING;
|
return MONITORING_AMBIGUOUS_STRING;
|
||||||
case(4201):
|
case (4201):
|
||||||
return FUSE_CURRENT_HIGH_STRING;
|
return FUSE_CURRENT_HIGH_STRING;
|
||||||
case(4202):
|
case (4202):
|
||||||
return FUSE_WENT_OFF_STRING;
|
return FUSE_WENT_OFF_STRING;
|
||||||
case(4204):
|
case (4204):
|
||||||
return POWER_ABOVE_HIGH_LIMIT_STRING;
|
return POWER_ABOVE_HIGH_LIMIT_STRING;
|
||||||
case(4205):
|
case (4205):
|
||||||
return POWER_BELOW_LOW_LIMIT_STRING;
|
return POWER_BELOW_LOW_LIMIT_STRING;
|
||||||
case(4300):
|
case (4300):
|
||||||
return SWITCH_WENT_OFF_STRING;
|
return SWITCH_WENT_OFF_STRING;
|
||||||
case(5000):
|
case (5000):
|
||||||
return HEATER_ON_STRING;
|
return HEATER_ON_STRING;
|
||||||
case(5001):
|
case (5001):
|
||||||
return HEATER_OFF_STRING;
|
return HEATER_OFF_STRING;
|
||||||
case(5002):
|
case (5002):
|
||||||
return HEATER_TIMEOUT_STRING;
|
return HEATER_TIMEOUT_STRING;
|
||||||
case(5003):
|
case (5003):
|
||||||
return HEATER_STAYED_ON_STRING;
|
return HEATER_STAYED_ON_STRING;
|
||||||
case(5004):
|
case (5004):
|
||||||
return HEATER_STAYED_OFF_STRING;
|
return HEATER_STAYED_OFF_STRING;
|
||||||
case(5200):
|
case (5200):
|
||||||
return TEMP_SENSOR_HIGH_STRING;
|
return TEMP_SENSOR_HIGH_STRING;
|
||||||
case(5201):
|
case (5201):
|
||||||
return TEMP_SENSOR_LOW_STRING;
|
return TEMP_SENSOR_LOW_STRING;
|
||||||
case(5202):
|
case (5202):
|
||||||
return TEMP_SENSOR_GRADIENT_STRING;
|
return TEMP_SENSOR_GRADIENT_STRING;
|
||||||
case(5901):
|
case (5901):
|
||||||
return COMPONENT_TEMP_LOW_STRING;
|
return COMPONENT_TEMP_LOW_STRING;
|
||||||
case(5902):
|
case (5902):
|
||||||
return COMPONENT_TEMP_HIGH_STRING;
|
return COMPONENT_TEMP_HIGH_STRING;
|
||||||
case(5903):
|
case (5903):
|
||||||
return COMPONENT_TEMP_OOL_LOW_STRING;
|
return COMPONENT_TEMP_OOL_LOW_STRING;
|
||||||
case(5904):
|
case (5904):
|
||||||
return COMPONENT_TEMP_OOL_HIGH_STRING;
|
return COMPONENT_TEMP_OOL_HIGH_STRING;
|
||||||
case(5905):
|
case (5905):
|
||||||
return TEMP_NOT_IN_OP_RANGE_STRING;
|
return TEMP_NOT_IN_OP_RANGE_STRING;
|
||||||
case(7101):
|
case (7101):
|
||||||
return FDIR_CHANGED_STATE_STRING;
|
return FDIR_CHANGED_STATE_STRING;
|
||||||
case(7102):
|
case (7102):
|
||||||
return FDIR_STARTS_RECOVERY_STRING;
|
return FDIR_STARTS_RECOVERY_STRING;
|
||||||
case(7103):
|
case (7103):
|
||||||
return FDIR_TURNS_OFF_DEVICE_STRING;
|
return FDIR_TURNS_OFF_DEVICE_STRING;
|
||||||
case(7201):
|
case (7201):
|
||||||
return MONITOR_CHANGED_STATE_STRING;
|
return MONITOR_CHANGED_STATE_STRING;
|
||||||
case(7202):
|
case (7202):
|
||||||
return VALUE_BELOW_LOW_LIMIT_STRING;
|
return VALUE_BELOW_LOW_LIMIT_STRING;
|
||||||
case(7203):
|
case (7203):
|
||||||
return VALUE_ABOVE_HIGH_LIMIT_STRING;
|
return VALUE_ABOVE_HIGH_LIMIT_STRING;
|
||||||
case(7204):
|
case (7204):
|
||||||
return VALUE_OUT_OF_RANGE_STRING;
|
return VALUE_OUT_OF_RANGE_STRING;
|
||||||
case(7301):
|
case (7301):
|
||||||
return SWITCHING_TM_FAILED_STRING;
|
return SWITCHING_TM_FAILED_STRING;
|
||||||
case(7400):
|
case (7400):
|
||||||
return CHANGING_MODE_STRING;
|
return CHANGING_MODE_STRING;
|
||||||
case(7401):
|
case (7401):
|
||||||
return MODE_INFO_STRING;
|
return MODE_INFO_STRING;
|
||||||
case(7402):
|
case (7402):
|
||||||
return FALLBACK_FAILED_STRING;
|
return FALLBACK_FAILED_STRING;
|
||||||
case(7403):
|
case (7403):
|
||||||
return MODE_TRANSITION_FAILED_STRING;
|
return MODE_TRANSITION_FAILED_STRING;
|
||||||
case(7404):
|
case (7404):
|
||||||
return CANT_KEEP_MODE_STRING;
|
return CANT_KEEP_MODE_STRING;
|
||||||
case(7405):
|
case (7405):
|
||||||
return OBJECT_IN_INVALID_MODE_STRING;
|
return OBJECT_IN_INVALID_MODE_STRING;
|
||||||
case(7406):
|
case (7406):
|
||||||
return FORCING_MODE_STRING;
|
return FORCING_MODE_STRING;
|
||||||
case(7407):
|
case (7407):
|
||||||
return MODE_CMD_REJECTED_STRING;
|
return MODE_CMD_REJECTED_STRING;
|
||||||
case(7506):
|
case (7506):
|
||||||
return HEALTH_INFO_STRING;
|
return HEALTH_INFO_STRING;
|
||||||
case(7507):
|
case (7507):
|
||||||
return CHILD_CHANGED_HEALTH_STRING;
|
return CHILD_CHANGED_HEALTH_STRING;
|
||||||
case(7508):
|
case (7508):
|
||||||
return CHILD_PROBLEMS_STRING;
|
return CHILD_PROBLEMS_STRING;
|
||||||
case(7509):
|
case (7509):
|
||||||
return OVERWRITING_HEALTH_STRING;
|
return OVERWRITING_HEALTH_STRING;
|
||||||
case(7510):
|
case (7510):
|
||||||
return TRYING_RECOVERY_STRING;
|
return TRYING_RECOVERY_STRING;
|
||||||
case(7511):
|
case (7511):
|
||||||
return RECOVERY_STEP_STRING;
|
return RECOVERY_STEP_STRING;
|
||||||
case(7512):
|
case (7512):
|
||||||
return RECOVERY_DONE_STRING;
|
return RECOVERY_DONE_STRING;
|
||||||
case(7900):
|
case (7900):
|
||||||
return RF_AVAILABLE_STRING;
|
return RF_AVAILABLE_STRING;
|
||||||
case(7901):
|
case (7901):
|
||||||
return RF_LOST_STRING;
|
return RF_LOST_STRING;
|
||||||
case(7902):
|
case (7902):
|
||||||
return BIT_LOCK_STRING;
|
return BIT_LOCK_STRING;
|
||||||
case(7903):
|
case (7903):
|
||||||
return BIT_LOCK_LOST_STRING;
|
return BIT_LOCK_LOST_STRING;
|
||||||
case(7905):
|
case (7905):
|
||||||
return FRAME_PROCESSING_FAILED_STRING;
|
return FRAME_PROCESSING_FAILED_STRING;
|
||||||
case(8900):
|
case (8900):
|
||||||
return CLOCK_SET_STRING;
|
return CLOCK_SET_STRING;
|
||||||
case(8901):
|
case (8901):
|
||||||
return CLOCK_SET_FAILURE_STRING;
|
return CLOCK_SET_FAILURE_STRING;
|
||||||
case(9700):
|
case (9700):
|
||||||
return TEST_STRING;
|
return TEST_STRING;
|
||||||
case(10600):
|
case (10600):
|
||||||
return CHANGE_OF_SETUP_PARAMETER_STRING;
|
return CHANGE_OF_SETUP_PARAMETER_STRING;
|
||||||
case(11101):
|
case (11101):
|
||||||
return MEMORY_READ_RPT_CRC_FAILURE_STRING;
|
return MEMORY_READ_RPT_CRC_FAILURE_STRING;
|
||||||
case(11102):
|
case (11102):
|
||||||
return ACK_FAILURE_STRING;
|
return ACK_FAILURE_STRING;
|
||||||
case(11103):
|
case (11103):
|
||||||
return EXE_FAILURE_STRING;
|
return EXE_FAILURE_STRING;
|
||||||
case(11104):
|
case (11104):
|
||||||
return CRC_FAILURE_EVENT_STRING;
|
return CRC_FAILURE_EVENT_STRING;
|
||||||
default:
|
default:
|
||||||
return "UNKNOWN_EVENT";
|
return "UNKNOWN_EVENT";
|
||||||
|
@ -3,6 +3,6 @@
|
|||||||
|
|
||||||
#include <fsfw/events/Event.h>
|
#include <fsfw/events/Event.h>
|
||||||
|
|
||||||
const char * translateEvents(Event event);
|
const char* translateEvents(Event event);
|
||||||
|
|
||||||
#endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */
|
#endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */
|
||||||
|
@ -1,11 +1,10 @@
|
|||||||
#include "MissionMessageTypes.h"
|
#include "MissionMessageTypes.h"
|
||||||
|
|
||||||
#include <fsfw/ipc/CommandMessage.h>
|
#include <fsfw/ipc/CommandMessage.h>
|
||||||
|
|
||||||
void messagetypes::clearMissionMessage(CommandMessage* message) {
|
void messagetypes::clearMissionMessage(CommandMessage* message) {
|
||||||
switch(message->getMessageType()) {
|
switch (message->getMessageType()) {
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -17,6 +17,6 @@ enum MESSAGE_TYPE {
|
|||||||
};
|
};
|
||||||
|
|
||||||
void clearMissionMessage(CommandMessage* message);
|
void clearMissionMessage(CommandMessage* message);
|
||||||
}
|
} // namespace messagetypes
|
||||||
|
|
||||||
#endif /* CONFIG_IPC_MISSIONMESSAGETYPES_H_ */
|
#endif /* CONFIG_IPC_MISSIONMESSAGETYPES_H_ */
|
||||||
|
@ -1,12 +1,13 @@
|
|||||||
#ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
#ifndef HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
||||||
#define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
#define HOSTED_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_
|
||||||
|
|
||||||
#include <cstdint>
|
|
||||||
#include <commonObjects.h>
|
#include <commonObjects.h>
|
||||||
|
|
||||||
|
#include <cstdint>
|
||||||
|
|
||||||
// The objects will be instantiated in the ID order
|
// The objects will be instantiated in the ID order
|
||||||
namespace objects {
|
namespace objects {
|
||||||
enum sourceObjects: uint32_t {
|
enum sourceObjects : uint32_t {
|
||||||
|
|
||||||
PUS_SERVICE_3 = 0x51000300,
|
PUS_SERVICE_3 = 0x51000300,
|
||||||
PUS_SERVICE_5 = 0x51000400,
|
PUS_SERVICE_5 = 0x51000400,
|
||||||
@ -25,7 +26,7 @@ namespace objects {
|
|||||||
|
|
||||||
/* 0x49 ('I') for Communication Interfaces **/
|
/* 0x49 ('I') for Communication Interfaces **/
|
||||||
ARDUINO_COM_IF = 0x49000001
|
ARDUINO_COM_IF = 0x49000001
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */
|
#endif /* BSP_CONFIG_OBJECTS_SYSTEMOBJECTLIST_H_ */
|
||||||
|
@ -38,8 +38,8 @@ const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END";
|
|||||||
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
||||||
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
||||||
|
|
||||||
const char* translateObject(object_id_t object) {
|
const char *translateObject(object_id_t object) {
|
||||||
switch( (object & 0xFFFFFFFF) ) {
|
switch ((object & 0xFFFFFFFF)) {
|
||||||
case 0x42694269:
|
case 0x42694269:
|
||||||
return TEST_TASK_STRING;
|
return TEST_TASK_STRING;
|
||||||
case 0x4400AFFE:
|
case 0x4400AFFE:
|
||||||
|
@ -1,9 +1,10 @@
|
|||||||
#ifndef CONFIG_RETURNVALUES_CLASSIDS_H_
|
#ifndef CONFIG_RETURNVALUES_CLASSIDS_H_
|
||||||
#define CONFIG_RETURNVALUES_CLASSIDS_H_
|
#define CONFIG_RETURNVALUES_CLASSIDS_H_
|
||||||
|
|
||||||
#include "commonClassIds.h"
|
|
||||||
#include <fsfw/returnvalues/FwClassIds.h>
|
#include <fsfw/returnvalues/FwClassIds.h>
|
||||||
|
|
||||||
|
#include "commonClassIds.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Source IDs starts at 73 for now
|
* Source IDs starts at 73 for now
|
||||||
* Framework IDs for ReturnValues run from 0 to 56
|
* Framework IDs for ReturnValues run from 0 to 56
|
||||||
@ -15,5 +16,4 @@ enum {
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif /* CONFIG_RETURNVALUES_CLASSIDS_H_ */
|
#endif /* CONFIG_RETURNVALUES_CLASSIDS_H_ */
|
||||||
|
@ -12,8 +12,7 @@
|
|||||||
* APID is a 11 bit number
|
* APID is a 11 bit number
|
||||||
*/
|
*/
|
||||||
namespace apid {
|
namespace apid {
|
||||||
static const uint16_t EIVE_OBSW = 0x65;
|
static const uint16_t EIVE_OBSW = 0x65;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#endif /* FSFWCONFIG_TMTC_APID_H_ */
|
#endif /* FSFWCONFIG_TMTC_APID_H_ */
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
#define CONFIG_TMTC_PUSIDS_HPP_
|
#define CONFIG_TMTC_PUSIDS_HPP_
|
||||||
|
|
||||||
namespace pus {
|
namespace pus {
|
||||||
enum Ids{
|
enum Ids {
|
||||||
PUS_SERVICE_1 = 1,
|
PUS_SERVICE_1 = 1,
|
||||||
PUS_SERVICE_2 = 2,
|
PUS_SERVICE_2 = 2,
|
||||||
PUS_SERVICE_3 = 3,
|
PUS_SERVICE_3 = 3,
|
||||||
|
@ -1,10 +1,9 @@
|
|||||||
|
#include <iostream>
|
||||||
|
|
||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "OBSWVersion.h"
|
#include "OBSWVersion.h"
|
||||||
|
|
||||||
#include "fsfw/FSFWVersion.h"
|
#include "fsfw/FSFWVersion.h"
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#ifdef WIN32
|
#ifdef WIN32
|
||||||
static const char* COMPILE_PRINTOUT = "Windows";
|
static const char* COMPILE_PRINTOUT = "Windows";
|
||||||
#elif LINUX
|
#elif LINUX
|
||||||
@ -17,21 +16,18 @@ static const char* COMPILE_PRINTOUT = "unknown OS";
|
|||||||
* Linux and Windows.
|
* Linux and Windows.
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
int main(void)
|
int main(void) {
|
||||||
{
|
|
||||||
std::cout << "-- EIVE OBSW --" << std::endl;
|
std::cout << "-- EIVE OBSW --" << std::endl;
|
||||||
std::cout << "-- Compiled for " << COMPILE_PRINTOUT << " --" << std::endl;
|
std::cout << "-- Compiled for " << COMPILE_PRINTOUT << " --" << std::endl;
|
||||||
std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION <<
|
std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "."
|
||||||
"." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "." <<
|
<< SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "."
|
||||||
FSFW_REVISION << "--" << std::endl;
|
<< FSFW_REVISION << "--" << std::endl;
|
||||||
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
||||||
|
|
||||||
initmission::initMission();
|
initmission::initMission();
|
||||||
|
|
||||||
for(;;) {
|
for (;;) {
|
||||||
// suspend main thread by sleeping it.
|
// suspend main thread by sleeping it.
|
||||||
TaskFactory::delayTask(5000);
|
TaskFactory::delayTask(5000);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,27 +1,27 @@
|
|||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "ObjectFactory.h"
|
|
||||||
|
|
||||||
#include "objects/systemObjectList.h"
|
#include <fsfw/objectmanager/ObjectManager.h>
|
||||||
#include "OBSWConfig.h"
|
|
||||||
#include "pollingsequence/pollingSequenceFactory.h"
|
|
||||||
|
|
||||||
#include <mission/utility/InitMission.h>
|
|
||||||
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
#include <fsfw/objectmanager/ObjectManagerIF.h>
|
||||||
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
|
||||||
#include <fsfw/serviceinterface/ServiceInterface.h>
|
#include <fsfw/serviceinterface/ServiceInterface.h>
|
||||||
#include <fsfw/objectmanager/ObjectManager.h>
|
|
||||||
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
|
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
|
||||||
#include <fsfw/tasks/PeriodicTaskIF.h>
|
#include <fsfw/tasks/PeriodicTaskIF.h>
|
||||||
#include <fsfw/tasks/TaskFactory.h>
|
#include <fsfw/tasks/TaskFactory.h>
|
||||||
|
#include <mission/utility/InitMission.h>
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
|
#include "ObjectFactory.h"
|
||||||
|
#include "objects/systemObjectList.h"
|
||||||
|
#include "pollingsequence/pollingSequenceFactory.h"
|
||||||
|
|
||||||
ServiceInterfaceStream sif::debug("DEBUG");
|
ServiceInterfaceStream sif::debug("DEBUG");
|
||||||
ServiceInterfaceStream sif::info("INFO");
|
ServiceInterfaceStream sif::info("INFO");
|
||||||
ServiceInterfaceStream sif::warning("WARNING");
|
ServiceInterfaceStream sif::warning("WARNING");
|
||||||
ServiceInterfaceStream sif::error("ERROR");
|
ServiceInterfaceStream sif::error("ERROR");
|
||||||
|
|
||||||
ObjectManagerIF *objectManager = nullptr;
|
ObjectManagerIF* objectManager = nullptr;
|
||||||
|
|
||||||
void initmission::initMission() {
|
void initmission::initMission() {
|
||||||
sif::info << "Building global objects.." << std::endl;
|
sif::info << "Building global objects.." << std::endl;
|
||||||
@ -37,30 +37,29 @@ void initmission::initMission() {
|
|||||||
void initmission::initTasks() {
|
void initmission::initTasks() {
|
||||||
TaskFactory* factory = TaskFactory::instance();
|
TaskFactory* factory = TaskFactory::instance();
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
if(factory == nullptr) {
|
if (factory == nullptr) {
|
||||||
/* Should never happen ! */
|
/* Should never happen ! */
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
||||||
void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline;
|
void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline;
|
||||||
#else
|
#else
|
||||||
void (*missedDeadlineFunc) (void) = nullptr;
|
void (*missedDeadlineFunc)(void) = nullptr;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/* TMTC Distribution */
|
/* TMTC Distribution */
|
||||||
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
||||||
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR);
|
result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -68,13 +67,13 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask(
|
PeriodicTaskIF* udpBridgeTask = factory->createPeriodicTask(
|
||||||
"UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"UDP_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
result = udpBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
result = udpBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Add component UDP Unix Bridge failed" << std::endl;
|
sif::error << "Add component UDP Unix Bridge failed" << std::endl;
|
||||||
}
|
}
|
||||||
PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask(
|
PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask(
|
||||||
"UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = udpPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
result = udpPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Add component UDP Polling failed" << std::endl;
|
sif::error << "Add component UDP Polling failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -90,11 +89,10 @@ void initmission::initTasks() {
|
|||||||
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
#endif /* OBSW_ADD_TEST_CODE == 1 */
|
||||||
|
|
||||||
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
||||||
for(const auto& task: taskVector) {
|
for (const auto& task : taskVector) {
|
||||||
if(task != nullptr) {
|
if (task != nullptr) {
|
||||||
task->startTask();
|
task->startTask();
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::error << "Task in vector " << name << " is invalid!" << std::endl;
|
sif::error << "Task in vector " << name << " is invalid!" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -112,7 +110,7 @@ void initmission::initTasks() {
|
|||||||
taskStarter(pstTasks, "PST Tasks");
|
taskStarter(pstTasks, "PST Tasks");
|
||||||
|
|
||||||
#if OBSW_ADD_TEST_PST == 1
|
#if OBSW_ADD_TEST_PST == 1
|
||||||
if(startTestPst) {
|
if (startTestPst) {
|
||||||
pstTestTask->startTask();
|
pstTestTask->startTask();
|
||||||
}
|
}
|
||||||
#endif /* RPI_TEST_ACS_BOARD == 1 */
|
#endif /* RPI_TEST_ACS_BOARD == 1 */
|
||||||
@ -120,12 +118,13 @@ void initmission::initTasks() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void initmission::createPusTasks(TaskFactory& factory,
|
void initmission::createPusTasks(TaskFactory& factory,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc, std::vector<PeriodicTaskIF*>& taskVec) {
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
PeriodicTaskIF* pusVerification = factory.createPeriodicTask(
|
PeriodicTaskIF* pusVerification = factory.createPeriodicTask(
|
||||||
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusVerification);
|
taskVec.push_back(pusVerification);
|
||||||
@ -133,11 +132,11 @@ void initmission::createPusTasks(TaskFactory& factory,
|
|||||||
PeriodicTaskIF* pusEvents = factory.createPeriodicTask(
|
PeriodicTaskIF* pusEvents = factory.createPeriodicTask(
|
||||||
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
}
|
}
|
||||||
result = pusEvents->addComponent(objects::EVENT_MANAGER);
|
result = pusEvents->addComponent(objects::EVENT_MANAGER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER);
|
initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusEvents);
|
taskVec.push_back(pusEvents);
|
||||||
@ -145,11 +144,11 @@ void initmission::createPusTasks(TaskFactory& factory,
|
|||||||
PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask(
|
||||||
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
}
|
}
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusHighPrio);
|
taskVec.push_back(pusHighPrio);
|
||||||
@ -157,19 +156,19 @@ void initmission::createPusTasks(TaskFactory& factory,
|
|||||||
PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask(
|
||||||
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT);
|
initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS);
|
initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING);
|
initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusMedPrio);
|
taskVec.push_back(pusMedPrio);
|
||||||
@ -177,24 +176,23 @@ void initmission::createPusTasks(TaskFactory& factory,
|
|||||||
PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask(
|
||||||
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
||||||
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST);
|
||||||
}
|
}
|
||||||
result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER);
|
result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("INT_ERR_RPRT",
|
initmission::printAddObjectError("INT_ERR_RPRT", objects::INTERNAL_ERROR_REPORTER);
|
||||||
objects::INTERNAL_ERROR_REPORTER);
|
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusLowPrio);
|
taskVec.push_back(pusLowPrio);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initmission::createPstTasks(TaskFactory& factory,
|
void initmission::createPstTasks(TaskFactory& factory,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc, std::vector<PeriodicTaskIF*> &taskVec) {
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
#if OBSW_ADD_SPI_TEST_CODE == 0
|
#if OBSW_ADD_SPI_TEST_CODE == 0
|
||||||
FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask(
|
||||||
"SPI_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0,
|
"SPI_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc);
|
||||||
missedDeadlineFunc);
|
|
||||||
result = pst::pstSpi(spiPst);
|
result = pst::pstSpi(spiPst);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
||||||
@ -205,29 +203,29 @@ void initmission::createPstTasks(TaskFactory& factory,
|
|||||||
|
|
||||||
void initmission::createTestTasks(TaskFactory& factory,
|
void initmission::createTestTasks(TaskFactory& factory,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc,
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
std::vector<PeriodicTaskIF*> &taskVec) {
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
||||||
"TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"TEST_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = testTask->addComponent(objects::TEST_TASK);
|
result = testTask->addComponent(objects::TEST_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
||||||
}
|
}
|
||||||
#if RPI_ADD_SPI_TEST == 1
|
#if RPI_ADD_SPI_TEST == 1
|
||||||
result = testTask->addComponent(objects::SPI_TEST);
|
result = testTask->addComponent(objects::SPI_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST);
|
initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST);
|
||||||
}
|
}
|
||||||
#endif /* RPI_ADD_SPI_TEST == 1 */
|
#endif /* RPI_ADD_SPI_TEST == 1 */
|
||||||
#if RPI_ADD_GPIO_TEST == 1
|
#if RPI_ADD_GPIO_TEST == 1
|
||||||
result = testTask->addComponent(objects::LIBGPIOD_TEST);
|
result = testTask->addComponent(objects::LIBGPIOD_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST);
|
initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST);
|
||||||
}
|
}
|
||||||
#endif /* RPI_ADD_GPIO_TEST == 1 */
|
#endif /* RPI_ADD_GPIO_TEST == 1 */
|
||||||
#if RPI_ADD_UART_TEST == 1
|
#if RPI_ADD_UART_TEST == 1
|
||||||
result = testTask->addComponent(objects::UART_TEST);
|
result = testTask->addComponent(objects::UART_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("UART_TEST", objects::UART_TEST);
|
initmission::printAddObjectError("UART_TEST", objects::UART_TEST);
|
||||||
}
|
}
|
||||||
#endif /* RPI_ADD_GPIO_TEST == 1 */
|
#endif /* RPI_ADD_GPIO_TEST == 1 */
|
||||||
@ -235,13 +233,12 @@ void initmission::createTestTasks(TaskFactory& factory,
|
|||||||
bool startTestPst = true;
|
bool startTestPst = true;
|
||||||
static_cast<void>(startTestPst);
|
static_cast<void>(startTestPst);
|
||||||
#if OBSW_ADD_TEST_PST == 1
|
#if OBSW_ADD_TEST_PST == 1
|
||||||
FixedTimeslotTaskIF* pstTestTask = factory->createFixedTimeslotTask("TEST_PST", 50,
|
FixedTimeslotTaskIF* pstTestTask = factory->createFixedTimeslotTask(
|
||||||
PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc);
|
"TEST_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 2.0, missedDeadlineFunc);
|
||||||
result = pst::pstTest(pstTestTask);
|
result = pst::pstTest(pstTestTask);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "initmission::initTasks: ACS PST empty or invalid" << std::endl;
|
sif::info << "initmission::initTasks: ACS PST empty or invalid" << std::endl;
|
||||||
startTestPst = false;
|
startTestPst = false;
|
||||||
}
|
}
|
||||||
#endif /* RPI_TEST_ACS_BOARD == 1 */
|
#endif /* RPI_TEST_ACS_BOARD == 1 */
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -1,9 +1,10 @@
|
|||||||
#ifndef BSP_LINUX_INITMISSION_H_
|
#ifndef BSP_LINUX_INITMISSION_H_
|
||||||
#define BSP_LINUX_INITMISSION_H_
|
#define BSP_LINUX_INITMISSION_H_
|
||||||
|
|
||||||
#include "fsfw/tasks/Typedef.h"
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
#include "fsfw/tasks/Typedef.h"
|
||||||
|
|
||||||
class PeriodicTaskIF;
|
class PeriodicTaskIF;
|
||||||
class TaskFactory;
|
class TaskFactory;
|
||||||
|
|
||||||
@ -11,14 +12,12 @@ namespace initmission {
|
|||||||
void initMission();
|
void initMission();
|
||||||
void initTasks();
|
void initTasks();
|
||||||
|
|
||||||
void createPstTasks(TaskFactory& factory,
|
void createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc,
|
std::vector<PeriodicTaskIF*>& taskVec);
|
||||||
std::vector<PeriodicTaskIF*> &taskVec);
|
void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
void createTestTasks(TaskFactory& factory,
|
std::vector<PeriodicTaskIF*>& taskVec);
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc,
|
|
||||||
std::vector<PeriodicTaskIF*> &taskVec);
|
|
||||||
void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
std::vector<PeriodicTaskIF*>& taskVec);
|
std::vector<PeriodicTaskIF*>& taskVec);
|
||||||
};
|
}; // namespace initmission
|
||||||
|
|
||||||
#endif /* BSP_LINUX_INITMISSION_H_ */
|
#endif /* BSP_LINUX_INITMISSION_H_ */
|
||||||
|
@ -1,47 +1,47 @@
|
|||||||
#include <devConf.h>
|
|
||||||
#include "ObjectFactory.h"
|
#include "ObjectFactory.h"
|
||||||
|
|
||||||
#include "objects/systemObjectList.h"
|
#include <devConf.h>
|
||||||
|
#include <mission/devices/GPSHyperionHandler.h>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
#include "devices/addresses.h"
|
#include "devices/addresses.h"
|
||||||
#include "devices/gpioIds.h"
|
#include "devices/gpioIds.h"
|
||||||
#include "OBSWConfig.h"
|
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
||||||
#include "tmtc/apid.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
#include "tmtc/pusIds.h"
|
#include "fsfw/tmtcpacket/pus/tm.h"
|
||||||
|
#include "fsfw/tmtcservices/CommandingServiceBase.h"
|
||||||
|
#include "fsfw/tmtcservices/PusServiceBase.h"
|
||||||
#include "linux/boardtest/LibgpiodTest.h"
|
#include "linux/boardtest/LibgpiodTest.h"
|
||||||
#include "linux/boardtest/SpiTestClass.h"
|
#include "linux/boardtest/SpiTestClass.h"
|
||||||
#include "linux/boardtest/UartTestClass.h"
|
#include "linux/boardtest/UartTestClass.h"
|
||||||
|
|
||||||
#include "mission/core/GenericFactory.h"
|
#include "mission/core/GenericFactory.h"
|
||||||
|
#include "mission/devices/GyroADIS1650XHandler.h"
|
||||||
#include "mission/utility/TmFunnel.h"
|
#include "mission/utility/TmFunnel.h"
|
||||||
#include <mission/devices/GPSHyperionHandler.h>
|
#include "objects/systemObjectList.h"
|
||||||
#include "mission/devices/GyroADIS16507Handler.h"
|
#include "tmtc/apid.h"
|
||||||
|
#include "tmtc/pusIds.h"
|
||||||
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
|
|
||||||
#include "fsfw/tmtcservices/CommandingServiceBase.h"
|
|
||||||
#include "fsfw/tmtcservices/PusServiceBase.h"
|
|
||||||
#include "fsfw/tmtcpacket/pus/tm.h"
|
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
|
||||||
|
|
||||||
/* UDP server includes */
|
/* UDP server includes */
|
||||||
#if OBSW_USE_TMTC_TCP_BRIDGE == 1
|
#if OBSW_USE_TMTC_TCP_BRIDGE == 1
|
||||||
#include <fsfw/src/fsfw/osal/common/TcpTmTcBridge.h>
|
#include <fsfw/src/fsfw/osal/common/TcpTmTcBridge.h>
|
||||||
#include <fsfw/src/fsfw/osal/common/TcpTmTcServer.h>
|
#include <fsfw/src/fsfw/osal/common/TcpTmTcServer.h>
|
||||||
#else
|
#else
|
||||||
#include "fsfw/osal/common/UdpTmTcBridge.h"
|
|
||||||
#include "fsfw/osal/common/UdpTcPollingTask.h"
|
#include "fsfw/osal/common/UdpTcPollingTask.h"
|
||||||
|
#include "fsfw/osal/common/UdpTmTcBridge.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h"
|
|
||||||
#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h"
|
|
||||||
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
|
|
||||||
#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h"
|
|
||||||
#include "fsfw_hal/linux/rpi/GpioRPi.h"
|
|
||||||
#include "fsfw_hal/common/gpio/GpioCookie.h"
|
|
||||||
#include "fsfw_hal/linux/spi/SpiCookie.h"
|
|
||||||
#include "fsfw_hal/linux/spi/SpiComIF.h"
|
|
||||||
#include <fsfw_hal/linux/uart/UartComIF.h>
|
#include <fsfw_hal/linux/uart/UartComIF.h>
|
||||||
#include <fsfw_hal/linux/uart/UartCookie.h>
|
#include <fsfw_hal/linux/uart/UartCookie.h>
|
||||||
|
|
||||||
|
#include "fsfw_hal/common/gpio/GpioCookie.h"
|
||||||
|
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
|
||||||
|
#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h"
|
||||||
|
#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h"
|
||||||
|
#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h"
|
||||||
|
#include "fsfw_hal/linux/rpi/GpioRPi.h"
|
||||||
|
#include "fsfw_hal/linux/spi/SpiComIF.h"
|
||||||
|
#include "fsfw_hal/linux/spi/SpiCookie.h"
|
||||||
|
|
||||||
void Factory::setStaticFrameworkObjectIds() {
|
void Factory::setStaticFrameworkObjectIds() {
|
||||||
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR;
|
||||||
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
PusServiceBase::packetDestination = objects::TM_FUNNEL;
|
||||||
@ -57,9 +57,7 @@ void Factory::setStaticFrameworkObjectIds() {
|
|||||||
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
TmPacketBase::timeStamperId = objects::TIME_STAMPER;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ObjectFactory::produce(void* args) {
|
||||||
|
|
||||||
void ObjectFactory::produce(void* args){
|
|
||||||
Factory::setStaticFrameworkObjectIds();
|
Factory::setStaticFrameworkObjectIds();
|
||||||
ObjectFactory::produceGenericObjects();
|
ObjectFactory::produceGenericObjects();
|
||||||
|
|
||||||
@ -84,91 +82,99 @@ void ObjectFactory::produce(void* args){
|
|||||||
static_cast<void>(spiCookie);
|
static_cast<void>(spiCookie);
|
||||||
|
|
||||||
#if OBSW_ADD_ACS_BOARD == 1
|
#if OBSW_ADD_ACS_BOARD == 1
|
||||||
if(gpioCookie == nullptr) {
|
if (gpioCookie == nullptr) {
|
||||||
gpioCookie = new GpioCookie();
|
gpioCookie = new GpioCookie();
|
||||||
}
|
}
|
||||||
// TODO: Missing pin for Gyro 2
|
// TODO: Missing pin for Gyro 2
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_0_LIS3_CS, gpio::MGM_0_BCM_PIN, "MGM_0_LIS3",
|
||||||
"MGM_0_LIS3", gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_1_RM3100_CS, gpio::MGM_1_BCM_PIN,
|
||||||
"MGM_1_RM3100", gpio::Direction::OUT, 1);
|
"MGM_1_RM3100", gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_2_LIS3_CS, gpio::MGM_2_BCM_PIN, "MGM_2_LIS3",
|
||||||
"MGM_2_LIS3", gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::MGM_3_RM3100_CS, gpio::MGM_3_BCM_PIN,
|
||||||
"MGM_3_RM3100", gpio::Direction::OUT, 1);
|
"MGM_3_RM3100", gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN,
|
||||||
"GYRO_0_ADIS", gpio::Direction::OUT, 1);
|
"GYRO_0_ADIS", gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_1_L3G_CS, gpio::GYRO_1_BCM_PIN, "GYRO_1_L3G",
|
||||||
"GYRO_1_L3G", gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_2_ADIS_CS, gpio::GYRO_2_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_2_ADIS_CS, gpio::GYRO_2_BCM_PIN,
|
||||||
"GYRO_2_ADIS", gpio::Direction::OUT, 1);
|
"GYRO_2_ADIS", gpio::Direction::OUT, 1);
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_3_L3G_CS, gpio::GYRO_3_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_3_L3G_CS, gpio::GYRO_3_BCM_PIN, "GYRO_3_L3G",
|
||||||
"GYRO_3_L3G", gpio::Direction::OUT, 1);
|
gpio::Direction::OUT, 1);
|
||||||
gpioIF->addGpios(gpioCookie);
|
gpioIF->addGpios(gpioCookie);
|
||||||
|
|
||||||
spiDev = "/dev/spidev0.1";
|
spiDev = "/dev/spidev0.1";
|
||||||
spiCookie = new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::MGM_0_LIS3, gpioIds::MGM_0_LIS3_CS, spiDev,
|
||||||
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
||||||
auto mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER,
|
auto mgmLis3Handler =
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
new MgmLIS3MDLHandler(objects::MGM_0_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
mgmLis3Handler->setStartUpImmediately();
|
mgmLis3Handler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
mgmLis3Handler->setToGoToNormalMode(true);
|
mgmLis3Handler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::MGM_1_RM3100, gpioIds::MGM_1_RM3100_CS, spiDev,
|
||||||
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
||||||
auto mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER,
|
auto mgmRm3100Handler =
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
new MgmRM3100Handler(objects::MGM_1_RM3100_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
mgmRm3100Handler->setStartUpImmediately();
|
mgmRm3100Handler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
mgmRm3100Handler->setToGoToNormalMode(true);
|
mgmRm3100Handler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::MGM_2_LIS3, gpioIds::MGM_2_LIS3_CS, spiDev,
|
||||||
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
MGMLIS3MDL::MAX_BUFFER_SIZE, spi::DEFAULT_LIS3_MODE, spi::DEFAULT_LIS3_SPEED);
|
||||||
mgmLis3Handler = new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER,
|
mgmLis3Handler =
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
new MgmLIS3MDLHandler(objects::MGM_2_LIS3_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
mgmLis3Handler->setStartUpImmediately();
|
mgmLis3Handler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
mgmLis3Handler->setToGoToNormalMode(true);
|
mgmLis3Handler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::MGM_3_RM3100, gpioIds::MGM_3_RM3100_CS, spiDev,
|
||||||
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
RM3100::MAX_BUFFER_SIZE, spi::DEFAULT_RM3100_MODE, spi::DEFAULT_RM3100_SPEED);
|
||||||
mgmRm3100Handler = new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER,
|
mgmRm3100Handler =
|
||||||
objects::SPI_COM_IF, spiCookie, 0);
|
new MgmRM3100Handler(objects::MGM_3_RM3100_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
mgmRm3100Handler->setStartUpImmediately();
|
mgmRm3100Handler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
mgmRm3100Handler->setToGoToNormalMode(true);
|
mgmRm3100Handler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
||||||
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
auto adisHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF,
|
auto adisHandler =
|
||||||
spiCookie);
|
new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie);
|
||||||
adisHandler->setStartUpImmediately();
|
adisHandler->setStartUpImmediately();
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev,
|
spiCookie =
|
||||||
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
new SpiCookie(addresses::GYRO_1_L3G, gpioIds::GYRO_1_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE,
|
||||||
auto gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF,
|
spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
spiCookie, 0);
|
auto gyroL3gHandler =
|
||||||
|
new GyroHandlerL3GD20H(objects::GYRO_1_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
gyroL3gHandler->setStartUpImmediately();
|
gyroL3gHandler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_L3GD20_GYRO_DEBUG== 1
|
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
||||||
gyroL3gHandler->setToGoToNormalMode(true);
|
gyroL3gHandler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev,
|
spiCookie =
|
||||||
|
new SpiCookie(addresses::GYRO_2_ADIS, gpioIds::GYRO_2_ADIS_CS, spiDev,
|
||||||
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
adisHandler = new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF,
|
adisHandler =
|
||||||
spiCookie);
|
new GyroADIS16507Handler(objects::GYRO_2_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie);
|
||||||
adisHandler->setStartUpImmediately();
|
adisHandler->setStartUpImmediately();
|
||||||
|
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev,
|
spiCookie =
|
||||||
L3GD20H::MAX_BUFFER_SIZE, spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
new SpiCookie(addresses::GYRO_3_L3G, gpioIds::GYRO_3_L3G_CS, spiDev, L3GD20H::MAX_BUFFER_SIZE,
|
||||||
gyroL3gHandler = new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF,
|
spi::DEFAULT_L3G_MODE, spi::DEFAULT_L3G_SPEED);
|
||||||
spiCookie, 0);
|
gyroL3gHandler =
|
||||||
|
new GyroHandlerL3GD20H(objects::GYRO_3_L3G_HANDLER, objects::SPI_COM_IF, spiCookie, 0);
|
||||||
gyroL3gHandler->setStartUpImmediately();
|
gyroL3gHandler->setStartUpImmediately();
|
||||||
#if FSFW_HAL_L3GD20_GYRO_DEBUG== 1
|
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
||||||
gyroL3gHandler->setToGoToNormalMode(true);
|
gyroL3gHandler->setToGoToNormalMode(true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -180,7 +186,6 @@ void ObjectFactory::produce(void* args){
|
|||||||
}
|
}
|
||||||
|
|
||||||
void ObjectFactory::createTestTasks() {
|
void ObjectFactory::createTestTasks() {
|
||||||
|
|
||||||
new TestTask(objects::TEST_TASK);
|
new TestTask(objects::TEST_TASK);
|
||||||
|
|
||||||
#if RPI_ADD_SPI_TEST == 1
|
#if RPI_ADD_SPI_TEST == 1
|
||||||
@ -208,7 +213,7 @@ void ObjectFactory::createTestTasks() {
|
|||||||
#endif /* RPI_LOOPBACK_TEST_GPIO == 1 */
|
#endif /* RPI_LOOPBACK_TEST_GPIO == 1 */
|
||||||
|
|
||||||
#if RPI_TEST_ADIS16507 == 1
|
#if RPI_TEST_ADIS16507 == 1
|
||||||
if(gpioCookie == nullptr) {
|
if (gpioCookie == nullptr) {
|
||||||
gpioCookie = new GpioCookie();
|
gpioCookie = new GpioCookie();
|
||||||
}
|
}
|
||||||
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN,
|
gpio::createRpiGpioConfig(gpioCookie, gpioIds::GYRO_0_ADIS_CS, gpio::GYRO_0_BCM_PIN,
|
||||||
@ -217,20 +222,20 @@ void ObjectFactory::createTestTasks() {
|
|||||||
|
|
||||||
spiDev = "/dev/spidev0.1";
|
spiDev = "/dev/spidev0.1";
|
||||||
spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
spiCookie = new SpiCookie(addresses::GYRO_0_ADIS, gpioIds::GYRO_0_ADIS_CS, spiDev,
|
||||||
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE, spi::DEFAULT_ADIS16507_SPEED,
|
ADIS16507::MAXIMUM_REPLY_SIZE, spi::DEFAULT_ADIS16507_MODE,
|
||||||
nullptr, nullptr);
|
spi::DEFAULT_ADIS16507_SPEED, nullptr, nullptr);
|
||||||
auto adisGyroHandler = new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie);
|
auto adisGyroHandler =
|
||||||
|
new GyroADIS16507Handler(objects::GYRO_0_ADIS_HANDLER, objects::SPI_COM_IF, spiCookie);
|
||||||
adisGyroHandler->setStartUpImmediately();
|
adisGyroHandler->setStartUpImmediately();
|
||||||
#endif /* RPI_TEST_ADIS16507 == 1 */
|
#endif /* RPI_TEST_ADIS16507 == 1 */
|
||||||
|
|
||||||
#if RPI_TEST_GPS_HANDLER == 1
|
#if RPI_TEST_GPS_HANDLER == 1
|
||||||
UartCookie* uartCookie = new UartCookie(objects::GPS0_HANDLER, "/dev/serial0",
|
UartCookie* uartCookie =
|
||||||
UartModes::CANONICAL, 9600, 1024);
|
new UartCookie(objects::GPS0_HANDLER, "/dev/serial0", UartModes::CANONICAL, 9600, 1024);
|
||||||
uartCookie->setToFlushInput(true);
|
uartCookie->setToFlushInput(true);
|
||||||
uartCookie->setReadCycles(6);
|
uartCookie->setReadCycles(6);
|
||||||
GPSHyperionHandler* gpsHandler = new GPSHyperionHandler(objects::GPS0_HANDLER,
|
GPSHyperionHandler* gpsHandler =
|
||||||
objects::UART_COM_IF, uartCookie, false);
|
new GPSHyperionHandler(objects::GPS0_HANDLER, objects::UART_COM_IF, uartCookie, false);
|
||||||
gpsHandler->setStartUpImmediately();
|
gpsHandler->setStartUpImmediately();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -1,12 +1,11 @@
|
|||||||
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
#ifndef BSP_LINUX_OBJECTFACTORY_H_
|
||||||
#define BSP_LINUX_OBJECTFACTORY_H_
|
#define BSP_LINUX_OBJECTFACTORY_H_
|
||||||
|
|
||||||
|
|
||||||
namespace ObjectFactory {
|
namespace ObjectFactory {
|
||||||
void setStatics();
|
void setStatics();
|
||||||
void produce(void* args);
|
void produce(void* args);
|
||||||
|
|
||||||
void createTestTasks();
|
void createTestTasks();
|
||||||
};
|
}; // namespace ObjectFactory
|
||||||
|
|
||||||
#endif /* BSP_LINUX_OBJECTFACTORY_H_ */
|
#endif /* BSP_LINUX_OBJECTFACTORY_H_ */
|
||||||
|
@ -7,7 +7,8 @@ extern "C" void __gcov_flush();
|
|||||||
#else
|
#else
|
||||||
void __gcov_flush() {
|
void __gcov_flush() {
|
||||||
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
||||||
"coverage information is desired.\n" << std::flush;
|
"coverage information is desired.\n"
|
||||||
|
<< std::flush;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2,13 +2,9 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
void printChar(const char* character, bool errStream) {
|
void printChar(const char* character, bool errStream) {
|
||||||
if(errStream) {
|
if (errStream) {
|
||||||
putc(*character, stderr);
|
putc(*character, stderr);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
putc(*character, stdout);
|
putc(*character, stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,12 +1,11 @@
|
|||||||
|
#include <iostream>
|
||||||
|
|
||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
#include "OBSWVersion.h"
|
#include "OBSWVersion.h"
|
||||||
|
|
||||||
#include "fsfw/FSFWVersion.h"
|
#include "fsfw/FSFWVersion.h"
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
|
|
||||||
#ifdef RASPBERRY_PI
|
#ifdef RASPBERRY_PI
|
||||||
static const char* const BOARD_NAME = "Raspberry Pi";
|
static const char* const BOARD_NAME = "Raspberry Pi";
|
||||||
#elif defined(BEAGLEBONEBLACK)
|
#elif defined(BEAGLEBONEBLACK)
|
||||||
@ -19,21 +18,18 @@ static const char* const BOARD_NAME = "Unknown Board";
|
|||||||
* @brief This is the main program and entry point for the Raspberry Pi.
|
* @brief This is the main program and entry point for the Raspberry Pi.
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
int main(void)
|
int main(void) {
|
||||||
{
|
|
||||||
std::cout << "-- EIVE OBSW --" << std::endl;
|
std::cout << "-- EIVE OBSW --" << std::endl;
|
||||||
std::cout << "-- Compiled for Linux board " << BOARD_NAME << " --" << std::endl;
|
std::cout << "-- Compiled for Linux board " << BOARD_NAME << " --" << std::endl;
|
||||||
std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION <<
|
std::cout << "-- OBSW " << SW_NAME << " v" << SW_VERSION << "." << SW_SUBVERSION << "."
|
||||||
"." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION <<
|
<< SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << FSFW_REVISION
|
||||||
FSFW_REVISION << "--" << std::endl;
|
<< "--" << std::endl;
|
||||||
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
||||||
|
|
||||||
initmission::initMission();
|
initmission::initMission();
|
||||||
|
|
||||||
for(;;) {
|
for (;;) {
|
||||||
/* Suspend main thread by sleeping it. */
|
/* Suspend main thread by sleeping it. */
|
||||||
TaskFactory::delayTask(5000);
|
TaskFactory::delayTask(5000);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -8,69 +8,69 @@ static constexpr char SPI_RW_DEV[] = "/dev/spidev3.0";
|
|||||||
|
|
||||||
static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c-1";
|
static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c-1";
|
||||||
|
|
||||||
static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ttyUL3";
|
static constexpr char UART_GNSS_DEV[] = "/dev/ttyUL0";
|
||||||
static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ttyUL4";
|
static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ttyUL2";
|
||||||
static constexpr char UART_SYRLINKS_DEV[] = "/dev/ttyUL5";
|
static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ttyUL3";
|
||||||
static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ttyUL8";
|
static constexpr char UART_SYRLINKS_DEV[] = "/dev/ttyUL4";
|
||||||
|
static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ttyUL7";
|
||||||
static constexpr char UART_GNSS_0_DEV[] = "/dev/ttyUL0";
|
|
||||||
static constexpr char UART_GNSS_1_DEV[] = "/dev/ttyUL2";
|
|
||||||
|
|
||||||
static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0";
|
static constexpr char UIO_PDEC_REGISTERS[] = "/dev/uio0";
|
||||||
static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2";
|
static constexpr char UIO_PDEC_CONFIG_MEMORY[] = "/dev/uio2";
|
||||||
static constexpr char UIO_PDEC_RAM[] = "/dev/uio3";
|
static constexpr char UIO_PDEC_RAM[] = "/dev/uio3";
|
||||||
|
|
||||||
namespace gpioNames {
|
namespace gpioNames {
|
||||||
static constexpr char GYRO_0_ADIS_CS[] = "gyro_0_adis_chip_select";
|
static constexpr char GYRO_0_ADIS_CS[] = "gyro_0_adis_chip_select";
|
||||||
static constexpr char GYRO_1_L3G_CS[] = "gyro_1_l3g_chip_select";
|
static constexpr char GYRO_1_L3G_CS[] = "gyro_1_l3g_chip_select";
|
||||||
static constexpr char GYRO_2_ADIS_CS[] = "gyro_2_adis_chip_select";
|
static constexpr char GYRO_2_ADIS_CS[] = "gyro_2_adis_chip_select";
|
||||||
static constexpr char GYRO_3_L3G_CS[] = "gyro_3_l3g_chip_select";
|
static constexpr char GYRO_3_L3G_CS[] = "gyro_3_l3g_chip_select";
|
||||||
static constexpr char MGM_0_CS[] = "mgm_0_lis3_chip_select";
|
static constexpr char MGM_0_CS[] = "mgm_0_lis3_chip_select";
|
||||||
static constexpr char MGM_1_CS[] = "mgm_1_rm3100_chip_select";
|
static constexpr char MGM_1_CS[] = "mgm_1_rm3100_chip_select";
|
||||||
static constexpr char MGM_2_CS[] = "mgm_2_lis3_chip_select";
|
static constexpr char MGM_2_CS[] = "mgm_2_lis3_chip_select";
|
||||||
static constexpr char MGM_3_CS[] = "mgm_3_rm3100_chip_select";
|
static constexpr char MGM_3_CS[] = "mgm_3_rm3100_chip_select";
|
||||||
static constexpr char RESET_GNSS_0[] = "reset_gnss_0";
|
static constexpr char RESET_GNSS_0[] = "reset_gnss_0";
|
||||||
static constexpr char RESET_GNSS_1[] = "reset_gnss_1";
|
static constexpr char RESET_GNSS_1[] = "reset_gnss_1";
|
||||||
static constexpr char GYRO_0_ENABLE[] = "gyro_0_enable";
|
static constexpr char GNSS_0_ENABLE[] = "enable_gnss_0";
|
||||||
static constexpr char GYRO_2_ENABLE[] = "gyro_2_enable";
|
static constexpr char GNSS_1_ENABLE[] = "enable_gnss_1";
|
||||||
static constexpr char HEATER_0[] = "heater0";
|
static constexpr char GYRO_0_ENABLE[] = "enable_gyro_0";
|
||||||
static constexpr char HEATER_1[] = "heater1";
|
static constexpr char GYRO_2_ENABLE[] = "enable_gyro_2";
|
||||||
static constexpr char HEATER_2[] = "heater2";
|
static constexpr char HEATER_0[] = "heater0";
|
||||||
static constexpr char HEATER_3[] = "heater3";
|
static constexpr char HEATER_1[] = "heater1";
|
||||||
static constexpr char HEATER_4[] = "heater4";
|
static constexpr char HEATER_2[] = "heater2";
|
||||||
static constexpr char HEATER_5[] = "heater5";
|
static constexpr char HEATER_3[] = "heater3";
|
||||||
static constexpr char HEATER_6[] = "heater6";
|
static constexpr char HEATER_4[] = "heater4";
|
||||||
static constexpr char HEATER_7[] = "heater7";
|
static constexpr char HEATER_5[] = "heater5";
|
||||||
static constexpr char SA_DPL_PIN_0[] = "sa_dpl_0";
|
static constexpr char HEATER_6[] = "heater6";
|
||||||
static constexpr char SA_DPL_PIN_1[] = "sa_dpl_1";
|
static constexpr char HEATER_7[] = "heater7";
|
||||||
static constexpr char SPI_MUX_BIT_1_PIN[] = "spi_mux_bit_1";
|
static constexpr char SA_DPL_PIN_0[] = "sa_dpl_0";
|
||||||
static constexpr char SPI_MUX_BIT_2_PIN[] = "spi_mux_bit_2";
|
static constexpr char SA_DPL_PIN_1[] = "sa_dpl_1";
|
||||||
static constexpr char SPI_MUX_BIT_3_PIN[] = "spi_mux_bit_3";
|
static constexpr char SPI_MUX_BIT_1_PIN[] = "spi_mux_bit_1";
|
||||||
static constexpr char SPI_MUX_BIT_4_PIN[] = "spi_mux_bit_4";
|
static constexpr char SPI_MUX_BIT_2_PIN[] = "spi_mux_bit_2";
|
||||||
static constexpr char SPI_MUX_BIT_5_PIN[] = "spi_mux_bit_5";
|
static constexpr char SPI_MUX_BIT_3_PIN[] = "spi_mux_bit_3";
|
||||||
static constexpr char SPI_MUX_BIT_6_PIN[] = "spi_mux_bit_6";
|
static constexpr char SPI_MUX_BIT_4_PIN[] = "spi_mux_bit_4";
|
||||||
static constexpr char EN_RW_CS[] = "en_rw_cs";
|
static constexpr char SPI_MUX_BIT_5_PIN[] = "spi_mux_bit_5";
|
||||||
static constexpr char EN_RW_1[] = "enable_rw_1";
|
static constexpr char SPI_MUX_BIT_6_PIN[] = "spi_mux_bit_6";
|
||||||
static constexpr char EN_RW_2[] = "enable_rw_2";
|
static constexpr char EN_RW_CS[] = "en_rw_cs";
|
||||||
static constexpr char EN_RW_3[] = "enable_rw_3";
|
static constexpr char EN_RW_1[] = "enable_rw_1";
|
||||||
static constexpr char EN_RW_4[] = "enable_rw_4";
|
static constexpr char EN_RW_2[] = "enable_rw_2";
|
||||||
static constexpr char SPI_MUX_SELECT[] = "spi_mux_select";
|
static constexpr char EN_RW_3[] = "enable_rw_3";
|
||||||
static constexpr char RAD_SENSOR_CHIP_SELECT[] = "rad_sensor_chip_select";
|
static constexpr char EN_RW_4[] = "enable_rw_4";
|
||||||
static constexpr char PAPB_BUSY_SIGNAL_VC0[] = "papb_busy_signal_vc0";
|
static constexpr char GNSS_MUX_SELECT[] = "gnss_mux_select";
|
||||||
static constexpr char PAPB_EMPTY_SIGNAL_VC0[] = "papb_empty_signal_vc0";
|
static constexpr char RAD_SENSOR_CHIP_SELECT[] = "rad_sensor_chip_select";
|
||||||
static constexpr char PAPB_BUSY_SIGNAL_VC1[] = "papb_busy_signal_vc1";
|
static constexpr char PAPB_BUSY_SIGNAL_VC0[] = "papb_busy_signal_vc0";
|
||||||
static constexpr char PAPB_EMPTY_SIGNAL_VC1[] = "papb_empty_signal_vc1";
|
static constexpr char PAPB_EMPTY_SIGNAL_VC0[] = "papb_empty_signal_vc0";
|
||||||
static constexpr char PAPB_BUSY_SIGNAL_VC2[] = "papb_busy_signal_vc2";
|
static constexpr char PAPB_BUSY_SIGNAL_VC1[] = "papb_busy_signal_vc1";
|
||||||
static constexpr char PAPB_EMPTY_SIGNAL_VC2[] = "papb_empty_signal_vc2";
|
static constexpr char PAPB_EMPTY_SIGNAL_VC1[] = "papb_empty_signal_vc1";
|
||||||
static constexpr char PAPB_BUSY_SIGNAL_VC3[] = "papb_busy_signal_vc3";
|
static constexpr char PAPB_BUSY_SIGNAL_VC2[] = "papb_busy_signal_vc2";
|
||||||
static constexpr char PAPB_EMPTY_SIGNAL_VC3[] = "papb_empty_signal_vc3";
|
static constexpr char PAPB_EMPTY_SIGNAL_VC2[] = "papb_empty_signal_vc2";
|
||||||
static constexpr char RS485_EN_TX_CLOCK[] = "tx_clock_enable_ltc2872";
|
static constexpr char PAPB_BUSY_SIGNAL_VC3[] = "papb_busy_signal_vc3";
|
||||||
static constexpr char RS485_EN_TX_DATA[] = "tx_data_enable_ltc2872";
|
static constexpr char PAPB_EMPTY_SIGNAL_VC3[] = "papb_empty_signal_vc3";
|
||||||
static constexpr char RS485_EN_RX_CLOCK[] = "rx_clock_enable_ltc2872";
|
static constexpr char RS485_EN_TX_CLOCK[] = "tx_clock_enable_ltc2872";
|
||||||
static constexpr char RS485_EN_RX_DATA[] = "rx_data_enable_ltc2872";
|
static constexpr char RS485_EN_TX_DATA[] = "tx_data_enable_ltc2872";
|
||||||
static constexpr char PDEC_RESET[] = "pdec_reset";
|
static constexpr char RS485_EN_RX_CLOCK[] = "rx_clock_enable_ltc2872";
|
||||||
static constexpr char BIT_RATE_SEL[] = "bit_rate_sel";
|
static constexpr char RS485_EN_RX_DATA[] = "rx_data_enable_ltc2872";
|
||||||
}
|
static constexpr char PDEC_RESET[] = "pdec_reset";
|
||||||
}
|
static constexpr char BIT_RATE_SEL[] = "bit_rate_sel";
|
||||||
|
} // namespace gpioNames
|
||||||
|
} // namespace q7s
|
||||||
|
|
||||||
#endif /* BSP_Q7S_BOARDCONFIG_BUSCONF_H_ */
|
#endif /* BSP_Q7S_BOARDCONFIG_BUSCONF_H_ */
|
||||||
|
@ -7,7 +7,8 @@ extern "C" void __gcov_flush();
|
|||||||
#else
|
#else
|
||||||
void __gcov_flush() {
|
void __gcov_flush() {
|
||||||
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
sif::info << "GCC GCOV: Please supply GCOV=1 in Makefile if "
|
||||||
"coverage information is desired.\n" << std::flush;
|
"coverage information is desired.\n"
|
||||||
|
<< std::flush;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2,13 +2,9 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
void printChar(const char* character, bool errStream) {
|
void printChar(const char* character, bool errStream) {
|
||||||
if(errStream) {
|
if (errStream) {
|
||||||
putc(*character, stderr);
|
putc(*character, stderr);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
putc(*character, stdout);
|
putc(*character, stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,26 +1,23 @@
|
|||||||
#include "FileSystemTest.h"
|
#include "FileSystemTest.h"
|
||||||
|
|
||||||
|
#include <cstdlib>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
#include "fsfw/timemanager/Stopwatch.h"
|
#include "fsfw/timemanager/Stopwatch.h"
|
||||||
|
|
||||||
#include <iostream>
|
enum SdCard { SDC0, SDC1 };
|
||||||
#include <cstdlib>
|
|
||||||
|
|
||||||
enum SdCard {
|
|
||||||
SDC0,
|
|
||||||
SDC1
|
|
||||||
};
|
|
||||||
|
|
||||||
FileSystemTest::FileSystemTest() {
|
FileSystemTest::FileSystemTest() {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
SdCard sdCard = SdCard::SDC0;
|
SdCard sdCard = SdCard::SDC0;
|
||||||
cout << "SD Card Test for SD card " << static_cast<int>(sdCard) << std::endl;
|
cout << "SD Card Test for SD card " << static_cast<int>(sdCard) << std::endl;
|
||||||
//Stopwatch stopwatch;
|
// Stopwatch stopwatch;
|
||||||
std::system("q7hw sd info all > /tmp/sd_status.txt");
|
std::system("q7hw sd info all > /tmp/sd_status.txt");
|
||||||
//stopwatch.stop(true);
|
// stopwatch.stop(true);
|
||||||
std::system("q7hw sd set 0 on > /tmp/sd_set.txt");
|
std::system("q7hw sd set 0 on > /tmp/sd_set.txt");
|
||||||
//stopwatch.stop(true);
|
// stopwatch.stop(true);
|
||||||
std::system("q7hw sd set 0 off > /tmp/sd_set.txt");
|
std::system("q7hw sd set 0 off > /tmp/sd_set.txt");
|
||||||
//stopwatch.stop(true);
|
// stopwatch.stop(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
FileSystemTest::~FileSystemTest() {
|
FileSystemTest::~FileSystemTest() {}
|
||||||
}
|
|
||||||
|
@ -2,12 +2,11 @@
|
|||||||
#define BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_
|
#define BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_
|
||||||
|
|
||||||
class FileSystemTest {
|
class FileSystemTest {
|
||||||
public:
|
public:
|
||||||
FileSystemTest();
|
FileSystemTest();
|
||||||
virtual~ FileSystemTest();
|
virtual ~FileSystemTest();
|
||||||
private:
|
|
||||||
|
private:
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif /* BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_ */
|
#endif /* BSP_Q7S_BOARDTEST_FILESYSTEMTEST_H_ */
|
||||||
|
@ -1,41 +1,57 @@
|
|||||||
|
#include "Q7STestTask.h"
|
||||||
|
|
||||||
#include <bsp_q7s/core/CoreController.h>
|
#include <bsp_q7s/core/CoreController.h>
|
||||||
#include <bsp_q7s/memory/FileSystemHandler.h>
|
#include <bsp_q7s/memory/FileSystemHandler.h>
|
||||||
#include <fsfw/objectmanager/ObjectManager.h>
|
#include <fsfw/objectmanager/ObjectManager.h>
|
||||||
#include "Q7STestTask.h"
|
#include <gps.h>
|
||||||
|
#include <libgpsmm.h>
|
||||||
|
|
||||||
|
#include <cstdio>
|
||||||
|
#include <ctime>
|
||||||
|
#include <fstream>
|
||||||
|
#include <iomanip>
|
||||||
|
#include <iostream>
|
||||||
|
#include <nlohmann/json.hpp>
|
||||||
|
|
||||||
#include "bsp_q7s/memory/SdCardManager.h"
|
#include "bsp_q7s/memory/SdCardManager.h"
|
||||||
#include "bsp_q7s/memory/scratchApi.h"
|
#include "bsp_q7s/memory/scratchApi.h"
|
||||||
|
|
||||||
#include "fsfw/timemanager/Stopwatch.h"
|
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
#include "fsfw/timemanager/Stopwatch.h"
|
||||||
#include "test/DummyParameter.h"
|
#include "test/DummyParameter.h"
|
||||||
|
|
||||||
#include <nlohmann/json.hpp>
|
Q7STestTask::Q7STestTask(object_id_t objectId) : TestTask(objectId) {
|
||||||
|
doTestSdCard = false;
|
||||||
#include <iostream>
|
doTestScratchApi = false;
|
||||||
#include <fstream>
|
doTestGps = false;
|
||||||
#include <cstdio>
|
|
||||||
|
|
||||||
Q7STestTask::Q7STestTask(object_id_t objectId): TestTask(objectId) {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t Q7STestTask::performOneShotAction() {
|
ReturnValue_t Q7STestTask::performOneShotAction() {
|
||||||
//testSdCard();
|
if (doTestSdCard) {
|
||||||
//testScratchApi();
|
testSdCard();
|
||||||
//testJsonLibDirect();
|
}
|
||||||
//testDummyParams();
|
if (doTestScratchApi) {
|
||||||
//testProtHandler();
|
testScratchApi();
|
||||||
|
}
|
||||||
|
// testJsonLibDirect();
|
||||||
|
// testDummyParams();
|
||||||
|
// testProtHandler();
|
||||||
FsOpCodes opCode = FsOpCodes::APPEND_TO_FILE;
|
FsOpCodes opCode = FsOpCodes::APPEND_TO_FILE;
|
||||||
testFileSystemHandlerDirect(opCode);
|
testFileSystemHandlerDirect(opCode);
|
||||||
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;
|
||||||
int result = std::system("q7hw sd info all > /tmp/sd_status.txt");
|
int result = std::system("q7hw sd info all > /tmp/sd_status.txt");
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
sif::debug << "system call failed with " << result << endl;
|
sif::debug << "system call failed with " << result << endl;
|
||||||
}
|
}
|
||||||
ifstream sdStatus("/tmp/sd_status.txt");
|
ifstream sdStatus("/tmp/sd_status.txt");
|
||||||
@ -44,11 +60,10 @@ void Q7STestTask::testSdCard() {
|
|||||||
while (std::getline(sdStatus, line)) {
|
while (std::getline(sdStatus, line)) {
|
||||||
std::istringstream iss(line);
|
std::istringstream iss(line);
|
||||||
string word;
|
string word;
|
||||||
while(iss >> word) {
|
while (iss >> word) {
|
||||||
if(word == "on") {
|
if (word == "on") {
|
||||||
sif::info << "SD card " << static_cast<int>(idx) << " is on" << endl;
|
sif::info << "SD card " << static_cast<int>(idx) << " is on" << endl;
|
||||||
}
|
} else if (word == "off") {
|
||||||
else if(word == "off") {
|
|
||||||
sif::info << "SD card " << static_cast<int>(idx) << " is off" << endl;
|
sif::info << "SD card " << static_cast<int>(idx) << " is off" << endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -69,23 +84,23 @@ void Q7STestTask::fileTests() {
|
|||||||
|
|
||||||
void Q7STestTask::testScratchApi() {
|
void Q7STestTask::testScratchApi() {
|
||||||
ReturnValue_t result = scratch::writeNumber("TEST", 1);
|
ReturnValue_t result = scratch::writeNumber("TEST", 1);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::debug << "Q7STestTask::scratchApiTest: Writing number failed" << std::endl;
|
sif::debug << "Q7STestTask::scratchApiTest: Writing number failed" << std::endl;
|
||||||
}
|
}
|
||||||
int number = 0;
|
int number = 0;
|
||||||
result = scratch::readNumber("TEST", number);
|
result = scratch::readNumber("TEST", number);
|
||||||
sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST\": " << number << std::endl;
|
sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST\": " << number << std::endl;
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl;
|
sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
result = scratch::writeString("TEST2", "halloWelt");
|
result = scratch::writeString("TEST2", "halloWelt");
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::debug << "Q7STestTask::scratchApiTest: Writing string failed" << std::endl;
|
sif::debug << "Q7STestTask::scratchApiTest: Writing string failed" << std::endl;
|
||||||
}
|
}
|
||||||
std::string string;
|
std::string string;
|
||||||
result = scratch::readString("TEST2", string);
|
result = scratch::readString("TEST2", string);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl;
|
sif::debug << "Q7STestTask::scratchApiTest: Reading number failed" << std::endl;
|
||||||
}
|
}
|
||||||
sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST2\": " << string << std::endl;
|
sif::info << "Q7STestTask::testScratchApi: Value for key \"TEST2\": " << string << std::endl;
|
||||||
@ -112,13 +127,12 @@ void Q7STestTask::testDummyParams() {
|
|||||||
DummyParameter param(mntPrefix, "dummy_json.txt");
|
DummyParameter param(mntPrefix, "dummy_json.txt");
|
||||||
param.printKeys();
|
param.printKeys();
|
||||||
param.print();
|
param.print();
|
||||||
if(not param.getJsonFileExists()) {
|
if (not param.getJsonFileExists()) {
|
||||||
param.writeJsonFile();
|
param.writeJsonFile();
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t result = param.readJsonFile();
|
ReturnValue_t result = param.readJsonFile();
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
param.setValue(DummyParameter::DUMMY_KEY_PARAM_1, 3);
|
param.setValue(DummyParameter::DUMMY_KEY_PARAM_1, 3);
|
||||||
@ -127,17 +141,27 @@ void Q7STestTask::testDummyParams() {
|
|||||||
param.writeJsonFile();
|
param.writeJsonFile();
|
||||||
param.print();
|
param.print();
|
||||||
|
|
||||||
int test = param.getValue<int>(DummyParameter::DUMMY_KEY_PARAM_1);
|
int test = 0;
|
||||||
std::string test2 = param.getValue<std::string>(DummyParameter::DUMMY_KEY_PARAM_2);
|
result = param.getValue<int>(DummyParameter::DUMMY_KEY_PARAM_1, &test);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "Q7STestTask::testDummyParams: Key " << DummyParameter::DUMMY_KEY_PARAM_1
|
||||||
|
<< " does not exist" << std::endl;
|
||||||
|
}
|
||||||
|
std::string test2;
|
||||||
|
result = param.getValue<std::string>(DummyParameter::DUMMY_KEY_PARAM_2, &test2);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::warning << "Q7STestTask::testDummyParams: Key " << DummyParameter::DUMMY_KEY_PARAM_1
|
||||||
|
<< " does not exist" << std::endl;
|
||||||
|
}
|
||||||
sif::info << "Test value (3 expected): " << test << std::endl;
|
sif::info << "Test value (3 expected): " << test << std::endl;
|
||||||
sif::info << "Test value 2 (\"blirb\" expected): " << test2 << std::endl;
|
sif::info << "Test value 2 (\"blirb\" expected): " << test2 << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t Q7STestTask::initialize() {
|
ReturnValue_t Q7STestTask::initialize() {
|
||||||
coreController = ObjectManager::instance()->get<CoreController>(objects::CORE_CONTROLLER);
|
coreController = ObjectManager::instance()->get<CoreController>(objects::CORE_CONTROLLER);
|
||||||
if(coreController == nullptr) {
|
if (coreController == nullptr) {
|
||||||
sif::warning << "Q7STestTask::initialize: Could not retrieve CORE_CONTROLLER object" <<
|
sif::warning << "Q7STestTask::initialize: Could not retrieve CORE_CONTROLLER object"
|
||||||
std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
return TestTask::initialize();
|
return TestTask::initialize();
|
||||||
}
|
}
|
||||||
@ -147,77 +171,91 @@ void Q7STestTask::testProtHandler() {
|
|||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
// If any chips are unlocked, lock them here
|
// If any chips are unlocked, lock them here
|
||||||
result = coreController->setBootCopyProtection(
|
result = coreController->setBootCopyProtection(
|
||||||
CoreController::Chip::ALL_CHIP, CoreController::Copy::ALL_COPY, true,
|
CoreController::Chip::ALL_CHIP, CoreController::Copy::ALL_COPY, true, opPerformed, true);
|
||||||
opPerformed, true);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
// unlock own copy
|
// unlock own copy
|
||||||
result = coreController->setBootCopyProtection(
|
result = coreController->setBootCopyProtection(
|
||||||
CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, false,
|
CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, false, opPerformed, true);
|
||||||
opPerformed, true);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
||||||
}
|
}
|
||||||
if(not opPerformed) {
|
if (not opPerformed) {
|
||||||
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
||||||
}
|
}
|
||||||
int retval = std::system("print-chip-prot-status.sh");
|
int retval = std::system("print-chip-prot-status.sh");
|
||||||
if(retval != 0) {
|
if (retval != 0) {
|
||||||
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
||||||
}
|
}
|
||||||
|
|
||||||
// lock own copy
|
// lock own copy
|
||||||
result = coreController->setBootCopyProtection(
|
result = coreController->setBootCopyProtection(
|
||||||
CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, true,
|
CoreController::Chip::SELF_CHIP, CoreController::Copy::SELF_COPY, true, opPerformed, true);
|
||||||
opPerformed, true);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
||||||
}
|
}
|
||||||
if(not opPerformed) {
|
if (not opPerformed) {
|
||||||
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
||||||
}
|
}
|
||||||
retval = std::system("print-chip-prot-status.sh");
|
retval = std::system("print-chip-prot-status.sh");
|
||||||
if(retval != 0) {
|
if (retval != 0) {
|
||||||
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
||||||
}
|
}
|
||||||
|
|
||||||
// unlock specific copy
|
// unlock specific copy
|
||||||
result = coreController->setBootCopyProtection(
|
result = coreController->setBootCopyProtection(
|
||||||
CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, false,
|
CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, false, opPerformed, true);
|
||||||
opPerformed, true);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
||||||
}
|
}
|
||||||
if(not opPerformed) {
|
if (not opPerformed) {
|
||||||
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
||||||
}
|
}
|
||||||
retval = std::system("print-chip-prot-status.sh");
|
retval = std::system("print-chip-prot-status.sh");
|
||||||
if(retval != 0) {
|
if (retval != 0) {
|
||||||
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
||||||
}
|
}
|
||||||
|
|
||||||
// lock specific copy
|
// lock specific copy
|
||||||
result = coreController->setBootCopyProtection(
|
result = coreController->setBootCopyProtection(
|
||||||
CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, true,
|
CoreController::Chip::CHIP_1, CoreController::Copy::COPY_1, true, opPerformed, true);
|
||||||
opPerformed, true);
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: Op failed" << std::endl;
|
||||||
}
|
}
|
||||||
if(not opPerformed) {
|
if (not opPerformed) {
|
||||||
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
sif::warning << "Q7STestTask::testProtHandler: No op performed" << std::endl;
|
||||||
}
|
}
|
||||||
retval = std::system("print-chip-prot-status.sh");
|
retval = std::system("print-chip-prot-status.sh");
|
||||||
if(retval != 0) {
|
if (retval != 0) {
|
||||||
utility::handleSystemError(retval, "Q7STestTask::testProtHandler");
|
utility::handleSystemError(retval, "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);
|
if (fsHandler == nullptr) {
|
||||||
if(fsHandler == nullptr) {
|
|
||||||
sif::warning << "Q7STestTask::testFileSystemHandlerDirect: No FS handler running.."
|
sif::warning << "Q7STestTask::testFileSystemHandlerDirect: No FS handler running.."
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
@ -226,28 +264,27 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) {
|
|||||||
|
|
||||||
// Lambda for common code
|
// Lambda for common code
|
||||||
auto createNonEmptyTmpDir = [&]() {
|
auto createNonEmptyTmpDir = [&]() {
|
||||||
if(not std::filesystem::exists("/tmp/test")) {
|
if (not std::filesystem::exists("/tmp/test")) {
|
||||||
result = fsHandler->createDirectory("/tmp", "test", false, &cfg);
|
result = fsHandler->createDirectory("/tmp", "test", false, &cfg);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Creating sample files
|
// Creating sample files
|
||||||
sif::info << "Creating sample files in directory" << std::endl;
|
sif::info << "Creating sample files in directory" << std::endl;
|
||||||
result = fsHandler->createFile("/tmp/test", "test1.txt", nullptr, 0, &cfg);
|
result = fsHandler->createFile("/tmp/test", "test1.txt", nullptr, 0, &cfg);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
result = fsHandler->createFile("/tmp/test", "test2.txt", nullptr, 0, &cfg);
|
result = fsHandler->createFile("/tmp/test", "test2.txt", nullptr, 0, &cfg);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
switch (opCode) {
|
||||||
switch(opCode) {
|
case (FsOpCodes::CREATE_EMPTY_FILE_IN_TMP): {
|
||||||
case(FsOpCodes::CREATE_EMPTY_FILE_IN_TMP): {
|
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
sif::info << "Creating empty file in /tmp folder" << std::endl;
|
sif::info << "Creating empty file in /tmp folder" << std::endl;
|
||||||
@ -255,89 +292,83 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) {
|
|||||||
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::REMOVE_TMP_FILE): {
|
case (FsOpCodes::REMOVE_TMP_FILE): {
|
||||||
sif::info << "Deleting /tmp/test.txt sample file" << std::endl;
|
sif::info << "Deleting /tmp/test.txt sample file" << std::endl;
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
if(not std::filesystem::exists("/tmp/test.txt")) {
|
if (not std::filesystem::exists("/tmp/test.txt")) {
|
||||||
// Creating sample file
|
// Creating sample file
|
||||||
sif::info << "Creating sample file /tmp/test.txt to delete" << std::endl;
|
sif::info << "Creating sample file /tmp/test.txt to delete" << std::endl;
|
||||||
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
||||||
}
|
}
|
||||||
result = fsHandler->removeFile("/tmp", "test.txt", &cfg);
|
result = fsHandler->removeFile("/tmp", "test.txt", &cfg);
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
if (result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "File removed successfully" << std::endl;
|
sif::info << "File removed successfully" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "File removal failed!" << std::endl;
|
sif::warning << "File removal failed!" << std::endl;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::CREATE_DIR_IN_TMP): {
|
case (FsOpCodes::CREATE_DIR_IN_TMP): {
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
sif::info << "Creating empty file in /tmp folder" << std::endl;
|
sif::info << "Creating empty file in /tmp folder" << std::endl;
|
||||||
// Do not delete file, user can check existence in shell
|
// Do not delete file, user can check existence in shell
|
||||||
ReturnValue_t result = fsHandler->createDirectory("/tmp/", "test", false, &cfg);
|
ReturnValue_t result = fsHandler->createDirectory("/tmp/", "test", false, &cfg);
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
if (result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "Directory created successfully" << std::endl;
|
sif::info << "Directory created successfully" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "Directory creation failed!" << std::endl;
|
sif::warning << "Directory creation failed!" << std::endl;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::REMOVE_EMPTY_DIR_IN_TMP): {
|
case (FsOpCodes::REMOVE_EMPTY_DIR_IN_TMP): {
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
if(not std::filesystem::exists("/tmp/test")) {
|
if (not std::filesystem::exists("/tmp/test")) {
|
||||||
result = fsHandler->createDirectory("/tmp", "test", false, &cfg);
|
result = fsHandler->createDirectory("/tmp", "test", false, &cfg);
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
// Delete any leftover files to regular dir removal works
|
// Delete any leftover files to regular dir removal works
|
||||||
std::remove("/tmp/test/*");
|
std::remove("/tmp/test/*");
|
||||||
}
|
}
|
||||||
result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
if (result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "Directory removed successfully" << std::endl;
|
sif::info << "Directory removed successfully" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "Directory removal failed!" << std::endl;
|
sif::warning << "Directory removal failed!" << std::endl;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::REMOVE_FILLED_DIR_IN_TMP): {
|
case (FsOpCodes::REMOVE_FILLED_DIR_IN_TMP): {
|
||||||
result = createNonEmptyTmpDir();
|
result = createNonEmptyTmpDir();
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
result = fsHandler->removeDirectory("/tmp/", "test", true, &cfg);
|
result = fsHandler->removeDirectory("/tmp/", "test", true, &cfg);
|
||||||
if(result == HasReturnvaluesIF::RETURN_OK) {
|
if (result == HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "Directory removed recursively successfully" << std::endl;
|
sif::info << "Directory removed recursively successfully" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "Recursive directory removal failed!" << std::endl;
|
sif::warning << "Recursive directory removal failed!" << std::endl;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::ATTEMPT_DIR_REMOVAL_NON_EMPTY): {
|
case (FsOpCodes::ATTEMPT_DIR_REMOVAL_NON_EMPTY): {
|
||||||
result = createNonEmptyTmpDir();
|
result = createNonEmptyTmpDir();
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
result = fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::info << "Directory removal attempt failed as expected" << std::endl;
|
sif::info << "Directory removal attempt failed as expected" << std::endl;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "Directory removal worked when it should not have!" << std::endl;
|
sif::warning << "Directory removal worked when it should not have!" << std::endl;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::RENAME_FILE): {
|
case (FsOpCodes::RENAME_FILE): {
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
if(std::filesystem::exists("/tmp/test.txt")) {
|
if (std::filesystem::exists("/tmp/test.txt")) {
|
||||||
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
||||||
}
|
}
|
||||||
sif::info << "Creating empty file /tmp/test.txt and rename to /tmp/test2.txt" << std::endl;
|
sif::info << "Creating empty file /tmp/test.txt and rename to /tmp/test2.txt" << std::endl;
|
||||||
@ -346,21 +377,21 @@ void Q7STestTask::testFileSystemHandlerDirect(FsOpCodes opCode) {
|
|||||||
fsHandler->renameFile("/tmp/", "test.txt", "test2.txt", &cfg);
|
fsHandler->renameFile("/tmp/", "test.txt", "test2.txt", &cfg);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(FsOpCodes::APPEND_TO_FILE): {
|
case (FsOpCodes::APPEND_TO_FILE): {
|
||||||
// No mount prefix, cause file is created in tmp
|
// No mount prefix, cause file is created in tmp
|
||||||
cfg.useMountPrefix = false;
|
cfg.useMountPrefix = false;
|
||||||
if(std::filesystem::exists("/tmp/test.txt")) {
|
if (std::filesystem::exists("/tmp/test.txt")) {
|
||||||
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
||||||
}
|
}
|
||||||
if(std::filesystem::exists("/tmp/test.txt")) {
|
if (std::filesystem::exists("/tmp/test.txt")) {
|
||||||
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
fsHandler->removeDirectory("/tmp/", "test", false, &cfg);
|
||||||
}
|
}
|
||||||
sif::info << "Creating empty file /tmp/test.txt and adding content" << std::endl;
|
sif::info << "Creating empty file /tmp/test.txt and adding content" << std::endl;
|
||||||
std::string content = "Hello World\n";
|
std::string content = "Hello World\n";
|
||||||
// Do not delete file, user can check existence in shell
|
// Do not delete file, user can check existence in shell
|
||||||
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
fsHandler->createFile("/tmp/", "test.txt", nullptr, 0, &cfg);
|
||||||
fsHandler->appendToFile("/tmp/", "test.txt", reinterpret_cast<const uint8_t*>(
|
fsHandler->appendToFile("/tmp/", "test.txt", reinterpret_cast<const uint8_t*>(content.data()),
|
||||||
content.data()), content.size(), 0, &cfg);
|
content.size(), 0, &cfg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -3,14 +3,24 @@
|
|||||||
|
|
||||||
#include "test/testtasks/TestTask.h"
|
#include "test/testtasks/TestTask.h"
|
||||||
|
|
||||||
class Q7STestTask: public TestTask {
|
class CoreController;
|
||||||
public:
|
|
||||||
|
class Q7STestTask : public TestTask {
|
||||||
|
public:
|
||||||
Q7STestTask(object_id_t objectId);
|
Q7STestTask(object_id_t objectId);
|
||||||
|
|
||||||
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();
|
||||||
@ -33,5 +43,4 @@ private:
|
|||||||
void testFileSystemHandlerDirect(FsOpCodes opCode);
|
void testFileSystemHandlerDirect(FsOpCodes opCode);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif /* BSP_Q7S_BOARDTEST_Q7STESTTASK_H_ */
|
#endif /* BSP_Q7S_BOARDTEST_Q7STESTTASK_H_ */
|
||||||
|
@ -1,22 +1,21 @@
|
|||||||
#include "gnssCallback.h"
|
#include "gnssCallback.h"
|
||||||
#include "devices/gpioIds.h"
|
|
||||||
|
|
||||||
|
#include "devices/gpioIds.h"
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
|
||||||
ReturnValue_t gps::triggerGpioResetPin(void *args) {
|
ReturnValue_t gps::triggerGpioResetPin(void* args) {
|
||||||
ResetArgs* resetArgs = reinterpret_cast<ResetArgs*>(args);
|
ResetArgs* resetArgs = reinterpret_cast<ResetArgs*>(args);
|
||||||
if(args == nullptr) {
|
if (args == nullptr) {
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
if (resetArgs->gpioComIF == nullptr) {
|
if (resetArgs->gpioComIF == nullptr) {
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
gpioId_t gpioId;
|
gpioId_t gpioId;
|
||||||
if(resetArgs->gnss1) {
|
if (resetArgs->gnss1) {
|
||||||
gpioId = gpioIds::GNSS_1_NRESET;
|
gpioId = gpioIds::GNSS_1_NRESET;
|
||||||
|
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
gpioId = gpioIds::GNSS_0_NRESET;
|
gpioId = gpioIds::GNSS_0_NRESET;
|
||||||
}
|
}
|
||||||
resetArgs->gpioComIF->pullLow(gpioId);
|
resetArgs->gpioComIF->pullLow(gpioId);
|
||||||
|
@ -1,8 +1,8 @@
|
|||||||
#ifndef BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_
|
#ifndef BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_
|
||||||
#define BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_
|
#define BSP_Q7S_CALLBACKS_GNSSCALLBACK_H_
|
||||||
|
|
||||||
#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h"
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h"
|
||||||
|
|
||||||
struct ResetArgs {
|
struct ResetArgs {
|
||||||
bool gnss1 = false;
|
bool gnss1 = false;
|
||||||
|
@ -1,22 +1,20 @@
|
|||||||
#include "rwSpiCallback.h"
|
#include "rwSpiCallback.h"
|
||||||
#include "devices/gpioIds.h"
|
|
||||||
#include "mission/devices/RwHandler.h"
|
|
||||||
|
|
||||||
#include "fsfw_hal/linux/spi/SpiCookie.h"
|
#include "devices/gpioIds.h"
|
||||||
#include "fsfw_hal/linux/UnixFileGuard.h"
|
|
||||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
|
#include "fsfw_hal/linux/UnixFileGuard.h"
|
||||||
|
#include "fsfw_hal/linux/spi/SpiCookie.h"
|
||||||
|
#include "mission/devices/RwHandler.h"
|
||||||
|
|
||||||
namespace rwSpiCallback {
|
namespace rwSpiCallback {
|
||||||
|
|
||||||
ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sendData,
|
ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sendData,
|
||||||
size_t sendLen, void* args) {
|
size_t sendLen, void* args) {
|
||||||
|
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
|
|
||||||
RwHandler* handler = reinterpret_cast<RwHandler*>(args);
|
RwHandler* handler = reinterpret_cast<RwHandler*>(args);
|
||||||
if(handler == nullptr) {
|
if (handler == nullptr) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Pointer to handler is invalid"
|
sif::error << "rwSpiCallback::spiCallback: Pointer to handler is invalid" << std::endl;
|
||||||
<< std::endl;
|
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -28,7 +26,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
|
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
|
||||||
uint32_t timeoutMs = 0;
|
uint32_t timeoutMs = 0;
|
||||||
MutexIF* mutex = comIf->getMutex(&timeoutType, &timeoutMs);
|
MutexIF* mutex = comIf->getMutex(&timeoutType, &timeoutMs);
|
||||||
if(mutex == nullptr or gpioIF == nullptr) {
|
if (mutex == nullptr or gpioIF == nullptr) {
|
||||||
sif::debug << "rwSpiCallback::spiCallback: Mutex or GPIO interface invalid" << std::endl;
|
sif::debug << "rwSpiCallback::spiCallback: Mutex or GPIO interface invalid" << std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
@ -36,7 +34,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
int fileDescriptor = 0;
|
int fileDescriptor = 0;
|
||||||
std::string device = cookie->getSpiDevice();
|
std::string device = cookie->getSpiDevice();
|
||||||
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "rwSpiCallback::spiCallback");
|
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "rwSpiCallback::spiCallback");
|
||||||
if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
|
if (fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Failed to open device file" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Failed to open device file" << std::endl;
|
||||||
return SpiComIF::OPENING_FILE_FAILED;
|
return SpiComIF::OPENING_FILE_FAILED;
|
||||||
}
|
}
|
||||||
@ -51,18 +49,13 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
/** Disconnect PS SPI peripheral and select AXI SPI core */
|
|
||||||
if(gpioIF->pullHigh(gpioIds::SPI_MUX) != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::error << "rwSpiCallback::spiCallback: Failed to pull spi mux gpio high" << std::endl;
|
|
||||||
}
|
|
||||||
|
|
||||||
/** Sending frame start sign */
|
/** Sending frame start sign */
|
||||||
writeBuffer[0] = 0x7E;
|
writeBuffer[0] = 0x7E;
|
||||||
writeSize = 1;
|
writeSize = 1;
|
||||||
|
|
||||||
// Pull SPI CS low. For now, no support for active high given
|
// Pull SPI CS low. For now, no support for active high given
|
||||||
if(gpioId != gpio::NO_GPIO) {
|
if (gpioId != gpio::NO_GPIO) {
|
||||||
if(gpioIF->pullLow(gpioId) != HasReturnvaluesIF::RETURN_OK) {
|
if (gpioIF->pullLow(gpioId) != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Failed to pull chip select low" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Failed to pull chip select low" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -75,8 +68,8 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
|
|
||||||
/** Encoding and sending command */
|
/** Encoding and sending command */
|
||||||
size_t idx = 0;
|
size_t idx = 0;
|
||||||
while(idx < sendLen) {
|
while (idx < sendLen) {
|
||||||
switch(*(sendData + idx)) {
|
switch (*(sendData + idx)) {
|
||||||
case 0x7E:
|
case 0x7E:
|
||||||
writeBuffer[0] = 0x7D;
|
writeBuffer[0] = 0x7D;
|
||||||
writeBuffer[1] = 0x5E;
|
writeBuffer[1] = 0x5E;
|
||||||
@ -112,7 +105,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
|
|
||||||
uint8_t* rxBuf = nullptr;
|
uint8_t* rxBuf = nullptr;
|
||||||
result = comIf->getReadBuffer(cookie->getSpiAddress(), &rxBuf);
|
result = comIf->getReadBuffer(cookie->getSpiAddress(), &rxBuf);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
closeSpi(gpioId, gpioIF, mutex);
|
closeSpi(gpioId, gpioIF, mutex);
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
@ -128,13 +121,13 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
*/
|
*/
|
||||||
uint8_t byteRead = 0;
|
uint8_t byteRead = 0;
|
||||||
for (int idx = 0; idx < 10; idx++) {
|
for (int idx = 0; idx < 10; idx++) {
|
||||||
if(read(fileDescriptor, &byteRead, 1) != 1) {
|
if (read(fileDescriptor, &byteRead, 1) != 1) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
||||||
closeSpi(gpioId, gpioIF, mutex);
|
closeSpi(gpioId, gpioIF, mutex);
|
||||||
return RwHandler::SPI_READ_FAILURE;
|
return RwHandler::SPI_READ_FAILURE;
|
||||||
}
|
}
|
||||||
if(idx == 0) {
|
if (idx == 0) {
|
||||||
if(byteRead != FLAG_BYTE) {
|
if (byteRead != FLAG_BYTE) {
|
||||||
sif::error << "Invalid data, expected start marker" << std::endl;
|
sif::error << "Invalid data, expected start marker" << std::endl;
|
||||||
closeSpi(gpioId, gpioIF, mutex);
|
closeSpi(gpioId, gpioIF, mutex);
|
||||||
return RwHandler::NO_START_MARKER;
|
return RwHandler::NO_START_MARKER;
|
||||||
@ -157,12 +150,11 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
size_t decodedFrameLen = 0;
|
size_t decodedFrameLen = 0;
|
||||||
while(decodedFrameLen < replyBufferSize) {
|
while (decodedFrameLen < replyBufferSize) {
|
||||||
|
|
||||||
/** First byte already read in */
|
/** First byte already read in */
|
||||||
if (decodedFrameLen != 0) {
|
if (decodedFrameLen != 0) {
|
||||||
byteRead = 0;
|
byteRead = 0;
|
||||||
if(read(fileDescriptor, &byteRead, 1) != 1) {
|
if (read(fileDescriptor, &byteRead, 1) != 1) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
||||||
result = RwHandler::SPI_READ_FAILURE;
|
result = RwHandler::SPI_READ_FAILURE;
|
||||||
break;
|
break;
|
||||||
@ -172,9 +164,8 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
if (byteRead == FLAG_BYTE) {
|
if (byteRead == FLAG_BYTE) {
|
||||||
/** Reached end of frame */
|
/** Reached end of frame */
|
||||||
break;
|
break;
|
||||||
}
|
} else if (byteRead == 0x7D) {
|
||||||
else if (byteRead == 0x7D) {
|
if (read(fileDescriptor, &byteRead, 1) != 1) {
|
||||||
if(read(fileDescriptor, &byteRead, 1) != 1) {
|
|
||||||
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
|
||||||
result = RwHandler::SPI_READ_FAILURE;
|
result = RwHandler::SPI_READ_FAILURE;
|
||||||
break;
|
break;
|
||||||
@ -183,20 +174,17 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
*(rxBuf + decodedFrameLen) = 0x7E;
|
*(rxBuf + decodedFrameLen) = 0x7E;
|
||||||
decodedFrameLen++;
|
decodedFrameLen++;
|
||||||
continue;
|
continue;
|
||||||
}
|
} else if (byteRead == 0x5D) {
|
||||||
else if (byteRead == 0x5D) {
|
|
||||||
*(rxBuf + decodedFrameLen) = 0x7D;
|
*(rxBuf + decodedFrameLen) = 0x7D;
|
||||||
decodedFrameLen++;
|
decodedFrameLen++;
|
||||||
continue;
|
continue;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl;
|
||||||
closeSpi(gpioId, gpioIF, mutex);
|
closeSpi(gpioId, gpioIF, mutex);
|
||||||
result = RwHandler::INVALID_SUBSTITUTE;
|
result = RwHandler::INVALID_SUBSTITUTE;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
*(rxBuf + decodedFrameLen) = byteRead;
|
*(rxBuf + decodedFrameLen) = byteRead;
|
||||||
decodedFrameLen++;
|
decodedFrameLen++;
|
||||||
continue;
|
continue;
|
||||||
@ -208,7 +196,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
* Otherwise there might be something wrong.
|
* Otherwise there might be something wrong.
|
||||||
*/
|
*/
|
||||||
if (decodedFrameLen == replyBufferSize) {
|
if (decodedFrameLen == replyBufferSize) {
|
||||||
if(read(fileDescriptor, &byteRead, 1) != 1) {
|
if (read(fileDescriptor, &byteRead, 1) != 1) {
|
||||||
sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl;
|
sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl;
|
||||||
result = RwHandler::SPI_READ_FAILURE;
|
result = RwHandler::SPI_READ_FAILURE;
|
||||||
break;
|
break;
|
||||||
@ -230,19 +218,15 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void closeSpi (gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) {
|
void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex) {
|
||||||
if(gpioId != gpio::NO_GPIO) {
|
if (gpioId != gpio::NO_GPIO) {
|
||||||
if (gpioIF->pullHigh(gpioId) != HasReturnvaluesIF::RETURN_OK) {
|
if (gpioIF->pullHigh(gpioId) != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "closeSpi: Failed to pull chip select high" << std::endl;
|
sif::error << "closeSpi: Failed to pull chip select high" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(mutex->unlockMutex() != HasReturnvaluesIF::RETURN_OK) {
|
if (mutex->unlockMutex() != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "rwSpiCallback::closeSpi: Failed to unlock mutex" << std::endl;;
|
sif::error << "rwSpiCallback::closeSpi: Failed to unlock mutex" << std::endl;
|
||||||
}
|
;
|
||||||
|
|
||||||
/** Route SPI interface again to PS SPI peripheral */
|
|
||||||
if(gpioIF->pullLow(gpioIds::SPI_MUX) != HasReturnvaluesIF::RETURN_OK) {
|
|
||||||
sif::error << "rwSpiCallback::spiCallback: Failed to pull spi mux gpio low" << std::endl;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
} // namespace rwSpiCallback
|
||||||
|
@ -2,9 +2,8 @@
|
|||||||
#define BSP_Q7S_RW_SPI_CALLBACK_H_
|
#define BSP_Q7S_RW_SPI_CALLBACK_H_
|
||||||
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
#include "fsfw_hal/linux/spi/SpiComIF.h"
|
|
||||||
#include "fsfw_hal/common/gpio/GpioCookie.h"
|
#include "fsfw_hal/common/gpio/GpioCookie.h"
|
||||||
|
#include "fsfw_hal/linux/spi/SpiComIF.h"
|
||||||
|
|
||||||
namespace rwSpiCallback {
|
namespace rwSpiCallback {
|
||||||
|
|
||||||
@ -31,7 +30,7 @@ static constexpr uint8_t FLAG_BYTE = 0x7E;
|
|||||||
* To switch between the to SPI peripherals, an EMIO is used which will also be controlled
|
* To switch between the to SPI peripherals, an EMIO is used which will also be controlled
|
||||||
* by this function.
|
* by this function.
|
||||||
*/
|
*/
|
||||||
ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sendData,
|
ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sendData,
|
||||||
size_t sendLen, void* args);
|
size_t sendLen, void* args);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -43,5 +42,5 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie *cookie, const uint8_t *sen
|
|||||||
*/
|
*/
|
||||||
void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex);
|
void closeSpi(gpioId_t gpioId, GpioIF* gpioIF, MutexIF* mutex);
|
||||||
|
|
||||||
}
|
} // namespace rwSpiCallback
|
||||||
#endif /* BSP_Q7S_RW_SPI_CALLBACK_H_ */
|
#endif /* BSP_Q7S_RW_SPI_CALLBACK_H_ */
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -2,32 +2,19 @@
|
|||||||
#define BSP_Q7S_CORE_CORECONTROLLER_H_
|
#define BSP_Q7S_CORE_CORECONTROLLER_H_
|
||||||
|
|
||||||
#include <fsfw/globalfunctions/PeriodicOperationDivider.h>
|
#include <fsfw/globalfunctions/PeriodicOperationDivider.h>
|
||||||
#include "fsfw/controller/ExtendedControllerBase.h"
|
|
||||||
#include "bsp_q7s/memory/SdCardManager.h"
|
#include "bsp_q7s/memory/SdCardManager.h"
|
||||||
|
|
||||||
#include "events/subsystemIdRanges.h"
|
#include "events/subsystemIdRanges.h"
|
||||||
|
#include "fsfw/controller/ExtendedControllerBase.h"
|
||||||
|
|
||||||
class Timer;
|
class Timer;
|
||||||
class SdCardManager;
|
class SdCardManager;
|
||||||
|
|
||||||
class CoreController: public ExtendedControllerBase {
|
class CoreController : public ExtendedControllerBase {
|
||||||
public:
|
public:
|
||||||
enum Chip: uint8_t {
|
enum Chip : uint8_t { CHIP_0, CHIP_1, NO_CHIP, SELF_CHIP, ALL_CHIP };
|
||||||
CHIP_0,
|
|
||||||
CHIP_1,
|
|
||||||
NO_CHIP,
|
|
||||||
SELF_CHIP,
|
|
||||||
ALL_CHIP
|
|
||||||
};
|
|
||||||
|
|
||||||
enum Copy: uint8_t {
|
enum Copy : uint8_t { COPY_0, COPY_1, NO_COPY, SELF_COPY, ALL_COPY };
|
||||||
COPY_0,
|
|
||||||
COPY_1,
|
|
||||||
NO_COPY,
|
|
||||||
SELF_COPY,
|
|
||||||
ALL_COPY
|
|
||||||
};
|
|
||||||
|
|
||||||
static constexpr char CHIP_PROT_SCRIPT[] = "/home/root/scripts/get-chip-prot-status.sh";
|
static constexpr char CHIP_PROT_SCRIPT[] = "/home/root/scripts/get-chip-prot-status.sh";
|
||||||
static constexpr char CHIP_STATE_FILE[] = "/tmp/chip_prot_status.txt";
|
static constexpr char CHIP_STATE_FILE[] = "/tmp/chip_prot_status.txt";
|
||||||
@ -38,23 +25,21 @@ public:
|
|||||||
static constexpr ActionId_t REBOOT_OBC = 32;
|
static constexpr ActionId_t REBOOT_OBC = 32;
|
||||||
static constexpr ActionId_t MOUNT_OTHER_COPY = 33;
|
static constexpr ActionId_t MOUNT_OTHER_COPY = 33;
|
||||||
|
|
||||||
|
|
||||||
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE;
|
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CORE;
|
||||||
|
|
||||||
static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM);
|
static constexpr Event ALLOC_FAILURE = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM);
|
||||||
|
|
||||||
|
|
||||||
CoreController(object_id_t objectId);
|
CoreController(object_id_t objectId);
|
||||||
virtual~ CoreController();
|
virtual ~CoreController();
|
||||||
|
|
||||||
ReturnValue_t initialize() override;
|
ReturnValue_t initialize() override;
|
||||||
|
|
||||||
ReturnValue_t initializeAfterTaskCreation() override;
|
ReturnValue_t initializeAfterTaskCreation() override;
|
||||||
|
|
||||||
ReturnValue_t executeAction(ActionId_t actionId,
|
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
MessageQueueId_t commandedBy, const uint8_t *data, size_t size) override;
|
const uint8_t* data, size_t size) override;
|
||||||
|
|
||||||
ReturnValue_t handleCommandMessage(CommandMessage *message) override;
|
ReturnValue_t handleCommandMessage(CommandMessage* message) override;
|
||||||
void performControlOperation() override;
|
void performControlOperation() override;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -78,12 +63,12 @@ public:
|
|||||||
* @param updateProtFile Specify whether the protection info file is updated
|
* @param updateProtFile Specify whether the protection info file is updated
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
ReturnValue_t setBootCopyProtection(Chip targetChip, Copy targetCopy,
|
ReturnValue_t setBootCopyProtection(Chip targetChip, Copy targetCopy, bool protect,
|
||||||
bool protect, bool& protOperationPerformed, bool updateProtFile = true);
|
bool& protOperationPerformed, bool updateProtFile = true);
|
||||||
|
|
||||||
bool sdInitFinished() const;
|
bool sdInitFinished() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static Chip CURRENT_CHIP;
|
static Chip CURRENT_CHIP;
|
||||||
static Copy CURRENT_COPY;
|
static Copy CURRENT_COPY;
|
||||||
|
|
||||||
@ -150,8 +135,7 @@ private:
|
|||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
LocalDataPoolManager& poolManager) override;
|
LocalDataPoolManager& poolManager) override;
|
||||||
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
|
||||||
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
|
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t* msToReachTheMode);
|
||||||
uint32_t *msToReachTheMode);
|
|
||||||
|
|
||||||
ReturnValue_t initVersionFile();
|
ReturnValue_t initVersionFile();
|
||||||
ReturnValue_t initBootCopy();
|
ReturnValue_t initBootCopy();
|
||||||
@ -170,15 +154,15 @@ private:
|
|||||||
void checkExternalSdCommandStatus();
|
void checkExternalSdCommandStatus();
|
||||||
|
|
||||||
ReturnValue_t actionListDirectoryIntoFile(ActionId_t actionId, MessageQueueId_t commandedBy,
|
ReturnValue_t actionListDirectoryIntoFile(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
const uint8_t *data, size_t size);
|
const uint8_t* data, size_t size);
|
||||||
ReturnValue_t actionPerformReboot(const uint8_t *data, size_t size);
|
ReturnValue_t actionPerformReboot(const uint8_t* data, size_t size);
|
||||||
|
|
||||||
void performWatchdogControlOperation();
|
void performWatchdogControlOperation();
|
||||||
|
|
||||||
ReturnValue_t handleProtInfoUpdateLine(std::string nextLine);
|
ReturnValue_t handleProtInfoUpdateLine(std::string nextLine);
|
||||||
int handleBootCopyProtAtIndex(Chip targetChip, Copy targetCopy, bool protect,
|
int handleBootCopyProtAtIndex(Chip targetChip, Copy targetCopy, bool protect,
|
||||||
bool &protOperationPerformed, bool selfChip, bool selfCopy, bool allChips,
|
bool& protOperationPerformed, bool selfChip, bool selfCopy,
|
||||||
bool allCopies, uint8_t arrIdx);
|
bool allChips, bool allCopies, uint8_t arrIdx);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* BSP_Q7S_CORE_CORECONTROLLER_H_ */
|
#endif /* BSP_Q7S_CORE_CORECONTROLLER_H_ */
|
||||||
|
@ -1,22 +1,21 @@
|
|||||||
#include "InitMission.h"
|
#include "InitMission.h"
|
||||||
#include "ObjectFactory.h"
|
|
||||||
#include "OBSWConfig.h"
|
|
||||||
#include "pollingsequence/pollingSequenceFactory.h"
|
|
||||||
|
|
||||||
#include "mission/utility/InitMission.h"
|
|
||||||
|
|
||||||
#include "fsfw/platform.h"
|
|
||||||
#include "fsfw/objectmanager/ObjectManagerIF.h"
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
|
||||||
#include "fsfw/serviceinterface/ServiceInterfaceStream.h"
|
|
||||||
#include "fsfw/objectmanager/ObjectManager.h"
|
|
||||||
#include "fsfw/tasks/FixedTimeslotTaskIF.h"
|
|
||||||
#include "fsfw/tasks/PeriodicTaskIF.h"
|
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
|
#include "ObjectFactory.h"
|
||||||
|
#include "fsfw/objectmanager/ObjectManager.h"
|
||||||
|
#include "fsfw/objectmanager/ObjectManagerIF.h"
|
||||||
|
#include "fsfw/platform.h"
|
||||||
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
#include "fsfw/serviceinterface/ServiceInterfaceStream.h"
|
||||||
|
#include "fsfw/tasks/FixedTimeslotTaskIF.h"
|
||||||
|
#include "fsfw/tasks/PeriodicTaskIF.h"
|
||||||
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
#include "mission/utility/InitMission.h"
|
||||||
|
#include "pollingsequence/pollingSequenceFactory.h"
|
||||||
|
|
||||||
/* This is configured for linux without CR */
|
/* This is configured for linux without CR */
|
||||||
#ifdef PLATFORM_UNIX
|
#ifdef PLATFORM_UNIX
|
||||||
ServiceInterfaceStream sif::debug("DEBUG");
|
ServiceInterfaceStream sif::debug("DEBUG");
|
||||||
@ -30,10 +29,9 @@ ServiceInterfaceStream sif::warning("WARNING", true);
|
|||||||
ServiceInterfaceStream sif::error("ERROR", true, false, true);
|
ServiceInterfaceStream sif::error("ERROR", true, false, true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
ObjectManagerIF *objectManager = nullptr;
|
ObjectManagerIF* objectManager = nullptr;
|
||||||
|
|
||||||
void initmission::initMission() {
|
void initmission::initMission() {
|
||||||
|
|
||||||
sif::info << "Building global objects.." << std::endl;
|
sif::info << "Building global objects.." << std::endl;
|
||||||
/* Instantiate global object manager and also create all objects */
|
/* Instantiate global object manager and also create all objects */
|
||||||
ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr);
|
ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr);
|
||||||
@ -47,21 +45,21 @@ void initmission::initMission() {
|
|||||||
void initmission::initTasks() {
|
void initmission::initTasks() {
|
||||||
TaskFactory* factory = TaskFactory::instance();
|
TaskFactory* factory = TaskFactory::instance();
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
if(factory == nullptr) {
|
if (factory == nullptr) {
|
||||||
/* Should never happen ! */
|
/* Should never happen ! */
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
#if OBSW_PRINT_MISSED_DEADLINES == 1
|
||||||
void (*missedDeadlineFunc) (void) = TaskFactory::printMissedDeadline;
|
void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline;
|
||||||
#else
|
#else
|
||||||
void (*missedDeadlineFunc) (void) = nullptr;
|
void (*missedDeadlineFunc)(void) = nullptr;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if BOARD_TE0720 == 0
|
#if BOARD_TE0720 == 0
|
||||||
PeriodicTaskIF* coreController = factory->createPeriodicTask(
|
PeriodicTaskIF* coreController = factory->createPeriodicTask(
|
||||||
"CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
"CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||||
result = coreController->addComponent(objects::CORE_CONTROLLER);
|
result = coreController->addComponent(objects::CORE_CONTROLLER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER);
|
initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -70,15 +68,15 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
||||||
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR);
|
result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR);
|
initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR);
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR);
|
initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR);
|
||||||
}
|
}
|
||||||
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
result = tmTcDistributor->addComponent(objects::TM_FUNNEL);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL);
|
initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -87,13 +85,13 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask(
|
PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask(
|
||||||
"TCPIP_TMTC_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
"TCPIP_TMTC_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("UDP_BRIDGE", objects::TMTC_BRIDGE);
|
initmission::printAddObjectError("UDP_BRIDGE", objects::TMTC_BRIDGE);
|
||||||
}
|
}
|
||||||
PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask(
|
PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask(
|
||||||
"TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK);
|
initmission::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -102,7 +100,7 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* ccsdsHandlerTask = factory->createPeriodicTask(
|
PeriodicTaskIF* ccsdsHandlerTask = factory->createPeriodicTask(
|
||||||
"CCSDS_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"CCSDS_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = ccsdsHandlerTask->addComponent(objects::CCSDS_HANDLER);
|
result = ccsdsHandlerTask->addComponent(objects::CCSDS_HANDLER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER);
|
initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -112,27 +110,44 @@ void initmission::initTasks() {
|
|||||||
PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask(
|
PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask(
|
||||||
"PDEC_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
"PDEC_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||||
result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER);
|
result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER);
|
initmission::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER);
|
||||||
}
|
}
|
||||||
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */
|
||||||
|
|
||||||
# if BOARD_TE0720 == 0
|
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
|
||||||
// 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
|
||||||
PeriodicTaskIF* fsTask = factory->createPeriodicTask(
|
PeriodicTaskIF* fsTask = factory->createPeriodicTask(
|
||||||
"FILE_SYSTEM_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
"FILE_SYSTEM_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||||
result = fsTask->addComponent(objects::FILE_SYSTEM_HANDLER);
|
result = fsTask->addComponent(objects::FILE_SYSTEM_HANDLER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("FILE_SYSTEM_TASK", objects::FILE_SYSTEM_HANDLER);
|
initmission::printAddObjectError("FILE_SYSTEM_TASK", objects::FILE_SYSTEM_HANDLER);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if OBSW_ADD_STAR_TRACKER == 1
|
||||||
|
PeriodicTaskIF* strImgLoaderTask = factory->createPeriodicTask(
|
||||||
|
"FILE_SYSTEM_TASK", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||||
|
result = strImgLoaderTask->addComponent(objects::STR_HELPER);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
initmission::printAddObjectError("FILE_SYSTEM_TASK", objects::STR_HELPER);
|
||||||
|
}
|
||||||
|
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||||
|
|
||||||
#endif /* BOARD_TE0720 */
|
#endif /* BOARD_TE0720 */
|
||||||
|
|
||||||
#if OBSW_TEST_CCSDS_BRIDGE == 1
|
#if OBSW_TEST_CCSDS_BRIDGE == 1
|
||||||
PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask(
|
PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask(
|
||||||
"PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
"PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||||
result = ptmeTestTask->addComponent(objects::CCSDS_IP_CORE_BRIDGE);
|
result = ptmeTestTask->addComponent(objects::CCSDS_IP_CORE_BRIDGE);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE);
|
initmission::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -148,11 +163,10 @@ void initmission::initTasks() {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
auto taskStarter = [](std::vector<PeriodicTaskIF*>& taskVector, std::string name) {
|
||||||
for(const auto& task: taskVector) {
|
for (const auto& task : taskVector) {
|
||||||
if(task != nullptr) {
|
if (task != nullptr) {
|
||||||
task->startTask();
|
task->startTask();
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::error << "Task in vector " << name << " is invalid!" << std::endl;
|
sif::error << "Task in vector " << name << " is invalid!" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -187,47 +201,51 @@ void initmission::initTasks() {
|
|||||||
|
|
||||||
#if BOARD_TE0720 == 0
|
#if BOARD_TE0720 == 0
|
||||||
fsTask->startTask();
|
fsTask->startTask();
|
||||||
|
#if OBSW_ADD_STAR_TRACKER == 1
|
||||||
|
strImgLoaderTask->startTask();
|
||||||
|
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
acsCtrl->startTask();
|
||||||
|
|
||||||
sif::info << "Tasks started.." << std::endl;
|
sif::info << "Tasks started.." << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
void initmission::createPstTasks(TaskFactory& factory,
|
void initmission::createPstTasks(TaskFactory& factory,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc, std::vector<PeriodicTaskIF*> &taskVec) {
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
#if BOARD_TE0720 == 0
|
#if BOARD_TE0720 == 0
|
||||||
/* Polling Sequence Table Default */
|
/* Polling Sequence Table Default */
|
||||||
#if OBSW_ADD_SPI_TEST_CODE == 0
|
#if OBSW_ADD_SPI_TEST_CODE == 0
|
||||||
FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* spiPst = factory.createFixedTimeslotTask(
|
||||||
"PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0,
|
"PST_TASK_DEFAULT", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc);
|
||||||
missedDeadlineFunc);
|
|
||||||
result = pst::pstSpi(spiPst);
|
result = pst::pstSpi(spiPst);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
if(result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
||||||
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
taskVec.push_back(spiPst);
|
taskVec.push_back(spiPst);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
FixedTimeslotTaskIF* uartPst = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* uartPst = factory.createFixedTimeslotTask(
|
||||||
"UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc);
|
"UART_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc);
|
||||||
result = pst::pstUart(uartPst);
|
result = pst::pstUart(uartPst);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
||||||
}
|
}
|
||||||
taskVec.push_back(uartPst);
|
taskVec.push_back(uartPst);
|
||||||
FixedTimeslotTaskIF* gpioPst = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* gpioPst = factory.createFixedTimeslotTask(
|
||||||
"GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc);
|
"GPIO_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc);
|
||||||
result = pst::pstGpio(gpioPst);
|
result = pst::pstGpio(gpioPst);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
||||||
}
|
}
|
||||||
taskVec.push_back(gpioPst);
|
taskVec.push_back(gpioPst);
|
||||||
FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask(
|
||||||
"I2C_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 3.0, missedDeadlineFunc);
|
"I2C_PST", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.2, missedDeadlineFunc);
|
||||||
result = pst::pstI2c(i2cPst);
|
result = pst::pstI2c(i2cPst);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating PST failed!" << std::endl;
|
||||||
@ -236,14 +254,13 @@ void initmission::createPstTasks(TaskFactory& factory,
|
|||||||
FixedTimeslotTaskIF* gomSpacePstTask = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* gomSpacePstTask = factory.createFixedTimeslotTask(
|
||||||
"GS_PST_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc);
|
"GS_PST_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 1.0, missedDeadlineFunc);
|
||||||
result = pst::pstGompaceCan(gomSpacePstTask);
|
result = pst::pstGompaceCan(gomSpacePstTask);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl;
|
sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl;
|
||||||
}
|
}
|
||||||
taskVec.push_back(gomSpacePstTask);
|
taskVec.push_back(gomSpacePstTask);
|
||||||
#else /* BOARD_TE7020 == 0 */
|
#else /* BOARD_TE7020 == 0 */
|
||||||
FixedTimeslotTaskIF * pollingSequenceTaskTE0720 = factory.createFixedTimeslotTask(
|
FixedTimeslotTaskIF* pollingSequenceTaskTE0720 = factory.createFixedTimeslotTask(
|
||||||
"PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0,
|
"PST_TASK_TE0720", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE * 8, 3.0, missedDeadlineFunc);
|
||||||
missedDeadlineFunc);
|
|
||||||
result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720);
|
result = pst::pollingSequenceTE0720(pollingSequenceTaskTE0720);
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "InitMission::initTasks: Creating TE0720 PST failed!" << std::endl;
|
sif::error << "InitMission::initTasks: Creating TE0720 PST failed!" << std::endl;
|
||||||
@ -252,14 +269,15 @@ void initmission::createPstTasks(TaskFactory& factory,
|
|||||||
#endif /* BOARD_TE7020 == 1 */
|
#endif /* BOARD_TE7020 == 1 */
|
||||||
}
|
}
|
||||||
|
|
||||||
void initmission::createPusTasks(TaskFactory &factory,
|
void initmission::createPusTasks(TaskFactory& factory,
|
||||||
TaskDeadlineMissedFunction missedDeadlineFunc, std::vector<PeriodicTaskIF*> &taskVec) {
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
/* PUS Services */
|
/* PUS Services */
|
||||||
PeriodicTaskIF* pusVerification = factory.createPeriodicTask(
|
PeriodicTaskIF* pusVerification = factory.createPeriodicTask(
|
||||||
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION);
|
initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusVerification);
|
taskVec.push_back(pusVerification);
|
||||||
@ -267,11 +285,11 @@ void initmission::createPusTasks(TaskFactory &factory,
|
|||||||
PeriodicTaskIF* pusEvents = factory.createPeriodicTask(
|
PeriodicTaskIF* pusEvents = factory.createPeriodicTask(
|
||||||
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING);
|
||||||
}
|
}
|
||||||
result = pusEvents->addComponent(objects::EVENT_MANAGER);
|
result = pusEvents->addComponent(objects::EVENT_MANAGER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER);
|
initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusEvents);
|
taskVec.push_back(pusEvents);
|
||||||
@ -279,11 +297,11 @@ void initmission::createPusTasks(TaskFactory &factory,
|
|||||||
PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask(
|
||||||
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
"PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc);
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS);
|
||||||
}
|
}
|
||||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT);
|
initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusHighPrio);
|
taskVec.push_back(pusHighPrio);
|
||||||
@ -291,19 +309,19 @@ void initmission::createPusTasks(TaskFactory &factory,
|
|||||||
PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask(
|
||||||
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
initmission::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||||
if(result!=HasReturnvaluesIF::RETURN_OK){
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
sif::error << "Object add component failed" << std::endl;
|
sif::error << "Object add component failed" << std::endl;
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT);
|
initmission::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT);
|
||||||
}
|
}
|
||||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS);
|
initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusMedPrio);
|
taskVec.push_back(pusMedPrio);
|
||||||
@ -311,39 +329,41 @@ void initmission::createPusTasks(TaskFactory &factory,
|
|||||||
PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask(
|
PeriodicTaskIF* pusLowPrio = factory.createPeriodicTask(
|
||||||
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
"PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc);
|
||||||
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST);
|
initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST);
|
||||||
}
|
}
|
||||||
result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER);
|
result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER);
|
initmission::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER);
|
||||||
}
|
}
|
||||||
taskVec.push_back(pusLowPrio);
|
taskVec.push_back(pusLowPrio);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initmission::createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
void initmission::createTestTasks(TaskFactory& factory,
|
||||||
|
TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
std::vector<PeriodicTaskIF*>& taskVec) {
|
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||||
#if OBSW_ADD_TEST_TASK == 1 || OBSW_ADD_SPI_TEST_CODE == 1 || (BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1)
|
#if OBSW_ADD_TEST_TASK == 1 || OBSW_ADD_SPI_TEST_CODE == 1 || \
|
||||||
|
(BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1)
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
#endif
|
#endif
|
||||||
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
PeriodicTaskIF* testTask = factory.createPeriodicTask(
|
||||||
"TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc);
|
"TEST_TASK", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1, missedDeadlineFunc);
|
||||||
#if OBSW_ADD_TEST_TASK == 1
|
#if OBSW_ADD_TEST_TASK == 1
|
||||||
result = testTask->addComponent(objects::TEST_TASK);
|
result = testTask->addComponent(objects::TEST_TASK);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK);
|
||||||
}
|
}
|
||||||
#endif /* OBSW_ADD_TEST_TASK == 1 */
|
#endif /* OBSW_ADD_TEST_TASK == 1 */
|
||||||
|
|
||||||
#if OBSW_ADD_SPI_TEST_CODE == 1
|
#if OBSW_ADD_SPI_TEST_CODE == 1
|
||||||
result = testTask->addComponent(objects::SPI_TEST);
|
result = testTask->addComponent(objects::SPI_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST);
|
initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1
|
#if BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1
|
||||||
result = testTask->addComponent(objects::LIBGPIOD_TEST);
|
result = testTask->addComponent(objects::LIBGPIOD_TEST);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST);
|
initmission::printAddObjectError("GPIOD_TEST", objects::LIBGPIOD_TEST);
|
||||||
}
|
}
|
||||||
#endif /* BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 */
|
#endif /* BOARD_TE0720 == 1 && OBSW_TEST_LIBGPIOD == 1 */
|
||||||
|
@ -1,9 +1,10 @@
|
|||||||
#ifndef BSP_Q7S_INITMISSION_H_
|
#ifndef BSP_Q7S_INITMISSION_H_
|
||||||
#define BSP_Q7S_INITMISSION_H_
|
#define BSP_Q7S_INITMISSION_H_
|
||||||
|
|
||||||
#include "fsfw/tasks/Typedef.h"
|
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
#include "fsfw/tasks/Typedef.h"
|
||||||
|
|
||||||
class PeriodicTaskIF;
|
class PeriodicTaskIF;
|
||||||
class TaskFactory;
|
class TaskFactory;
|
||||||
|
|
||||||
@ -17,6 +18,6 @@ void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadl
|
|||||||
std::vector<PeriodicTaskIF*>& taskVec);
|
std::vector<PeriodicTaskIF*>& taskVec);
|
||||||
void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc,
|
||||||
std::vector<PeriodicTaskIF*>& taskVec);
|
std::vector<PeriodicTaskIF*>& taskVec);
|
||||||
};
|
}; // namespace initmission
|
||||||
|
|
||||||
#endif /* BSP_Q7S_INITMISSION_H_ */
|
#endif /* BSP_Q7S_INITMISSION_H_ */
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -22,9 +22,9 @@ void createSolarArrayDeploymentComponents();
|
|||||||
void createSyrlinksComponents();
|
void createSyrlinksComponents();
|
||||||
void createRtdComponents(LinuxLibgpioIF* gpioComIF);
|
void createRtdComponents(LinuxLibgpioIF* gpioComIF);
|
||||||
void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF);
|
void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF);
|
||||||
void createCcsdsComponents(LinuxLibgpioIF *gpioComIF);
|
void createCcsdsComponents(LinuxLibgpioIF* gpioComIF);
|
||||||
void createTestComponents(LinuxLibgpioIF* gpioComIF);
|
void createTestComponents(LinuxLibgpioIF* gpioComIF);
|
||||||
|
|
||||||
};
|
}; // namespace ObjectFactory
|
||||||
|
|
||||||
#endif /* BSP_Q7S_OBJECTFACTORY_H_ */
|
#endif /* BSP_Q7S_OBJECTFACTORY_H_ */
|
||||||
|
@ -1,8 +1,5 @@
|
|||||||
#include "ParameterHandler.h"
|
#include "ParameterHandler.h"
|
||||||
|
|
||||||
ParameterHandler::ParameterHandler(std::string mountPrefix): mountPrefix(mountPrefix) {
|
ParameterHandler::ParameterHandler(std::string mountPrefix) : mountPrefix(mountPrefix) {}
|
||||||
}
|
|
||||||
|
|
||||||
void ParameterHandler::setMountPrefix(std::string prefix) {
|
void ParameterHandler::setMountPrefix(std::string prefix) { mountPrefix = prefix; }
|
||||||
mountPrefix = prefix;
|
|
||||||
}
|
|
||||||
|
@ -4,19 +4,17 @@
|
|||||||
#include <nlohmann/json.hpp>
|
#include <nlohmann/json.hpp>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
class ParameterHandler {
|
class ParameterHandler {
|
||||||
public:
|
public:
|
||||||
ParameterHandler(std::string mountPrefix);
|
ParameterHandler(std::string mountPrefix);
|
||||||
|
|
||||||
void setMountPrefix(std::string prefix);
|
void setMountPrefix(std::string prefix);
|
||||||
|
|
||||||
void setUpDummyParameter();
|
void setUpDummyParameter();
|
||||||
private:
|
|
||||||
|
private:
|
||||||
std::string mountPrefix;
|
std::string mountPrefix;
|
||||||
DummyParameter dummyParam;
|
DummyParameter dummyParam;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif /* BSP_Q7S_CORE_PARAMETERHANDLER_H_ */
|
#endif /* BSP_Q7S_CORE_PARAMETERHANDLER_H_ */
|
||||||
|
@ -1,14 +1,14 @@
|
|||||||
#include "obsw.h"
|
#include "obsw.h"
|
||||||
#include "OBSWVersion.h"
|
|
||||||
#include "OBSWConfig.h"
|
|
||||||
#include "InitMission.h"
|
|
||||||
#include "watchdogConf.h"
|
|
||||||
|
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
|
||||||
#include "fsfw/FSFWVersion.h"
|
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "InitMission.h"
|
||||||
|
#include "OBSWConfig.h"
|
||||||
|
#include "OBSWVersion.h"
|
||||||
|
#include "fsfw/FSFWVersion.h"
|
||||||
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
#include "watchdogConf.h"
|
||||||
|
|
||||||
static int OBSW_ALREADY_RUNNING = -2;
|
static int OBSW_ALREADY_RUNNING = -2;
|
||||||
|
|
||||||
@ -19,23 +19,24 @@ int obsw::obsw() {
|
|||||||
#else
|
#else
|
||||||
std::cout << "-- Compiled for Linux (TE0720) --" << std::endl;
|
std::cout << "-- Compiled for Linux (TE0720) --" << std::endl;
|
||||||
#endif
|
#endif
|
||||||
std::cout << "-- OBSW v" << SW_VERSION << "." << SW_SUBVERSION <<
|
std::cout << "-- OBSW v" << SW_VERSION << "." << SW_SUBVERSION << "." << SW_REVISION << ", FSFW v"
|
||||||
"." << SW_REVISION << ", FSFW v" << FSFW_VERSION << "." << FSFW_SUBVERSION << "." <<
|
<< FSFW_VERSION << "." << FSFW_SUBVERSION << "." << FSFW_REVISION << "--" << std::endl;
|
||||||
FSFW_REVISION << "--" << std::endl;
|
|
||||||
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
std::cout << "-- " << __DATE__ << " " << __TIME__ << " --" << std::endl;
|
||||||
|
|
||||||
#if Q7S_CHECK_FOR_ALREADY_RUNNING_IMG == 1
|
#if Q7S_CHECK_FOR_ALREADY_RUNNING_IMG == 1
|
||||||
// Check special file here. This file is created or deleted by the eive-watchdog application
|
// Check special file here. This file is created or deleted by the eive-watchdog application
|
||||||
// or systemd service!
|
// or systemd service!
|
||||||
if(std::filesystem::exists(watchdog::RUNNING_FILE_NAME)) {
|
if (std::filesystem::exists(watchdog::RUNNING_FILE_NAME)) {
|
||||||
sif::warning << "File " << watchdog::RUNNING_FILE_NAME << " exists so the software might "
|
sif::warning << "File " << watchdog::RUNNING_FILE_NAME
|
||||||
"already be running. Aborting.." << std::endl;
|
<< " exists so the software might "
|
||||||
|
"already be running. Aborting.."
|
||||||
|
<< std::endl;
|
||||||
return OBSW_ALREADY_RUNNING;
|
return OBSW_ALREADY_RUNNING;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
initmission::initMission();
|
initmission::initMission();
|
||||||
|
|
||||||
for(;;) {
|
for (;;) {
|
||||||
/* Suspend main thread by sleeping it. */
|
/* Suspend main thread by sleeping it. */
|
||||||
TaskFactory::delayTask(5000);
|
TaskFactory::delayTask(5000);
|
||||||
}
|
}
|
||||||
|
@ -3,3 +3,5 @@ target_sources(${TARGET_NAME} PRIVATE
|
|||||||
PlocUpdater.cpp
|
PlocUpdater.cpp
|
||||||
PlocMemoryDumper.cpp
|
PlocMemoryDumper.cpp
|
||||||
)
|
)
|
||||||
|
|
||||||
|
add_subdirectory(startracker)
|
@ -1,21 +1,21 @@
|
|||||||
#include <fsfw/src/fsfw/serialize/SerializeAdapter.h>
|
|
||||||
#include "fsfw/ipc/QueueFactory.h"
|
|
||||||
#include "PlocMemoryDumper.h"
|
#include "PlocMemoryDumper.h"
|
||||||
|
|
||||||
#include <fstream>
|
#include <fsfw/src/fsfw/serialize/SerializeAdapter.h>
|
||||||
|
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
PlocMemoryDumper::PlocMemoryDumper(object_id_t objectId) :
|
#include "fsfw/ipc/QueueFactory.h"
|
||||||
SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) {
|
|
||||||
|
PlocMemoryDumper::PlocMemoryDumper(object_id_t objectId)
|
||||||
|
: SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) {
|
||||||
commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE);
|
commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
PlocMemoryDumper::~PlocMemoryDumper() {
|
PlocMemoryDumper::~PlocMemoryDumper() {}
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocMemoryDumper::initialize() {
|
ReturnValue_t PlocMemoryDumper::initialize() {
|
||||||
|
|
||||||
ReturnValue_t result = SystemObject::initialize();
|
ReturnValue_t result = SystemObject::initialize();
|
||||||
if (result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
@ -38,9 +38,8 @@ ReturnValue_t PlocMemoryDumper::performOperation(uint8_t operationCode) {
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocMemoryDumper::executeAction(ActionId_t actionId,
|
ReturnValue_t PlocMemoryDumper::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
MessageQueueId_t commandedBy, const uint8_t* data, size_t size) {
|
const uint8_t* data, size_t size) {
|
||||||
|
|
||||||
if (state != State::IDLE) {
|
if (state != State::IDLE) {
|
||||||
return IS_BUSY;
|
return IS_BUSY;
|
||||||
}
|
}
|
||||||
@ -71,13 +70,9 @@ ReturnValue_t PlocMemoryDumper::executeAction(ActionId_t actionId,
|
|||||||
return EXECUTION_FINISHED;
|
return EXECUTION_FINISHED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageQueueId_t PlocMemoryDumper::getCommandQueue() const {
|
MessageQueueId_t PlocMemoryDumper::getCommandQueue() const { return commandQueue->getId(); }
|
||||||
return commandQueue->getId();
|
|
||||||
}
|
|
||||||
|
|
||||||
MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() {
|
MessageQueueIF* PlocMemoryDumper::getCommandQueuePtr() { return commandQueue; }
|
||||||
return commandQueue;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMemoryDumper::readCommandQueue() {
|
void PlocMemoryDumper::readCommandQueue() {
|
||||||
CommandMessage message;
|
CommandMessage message;
|
||||||
@ -121,17 +116,12 @@ void PlocMemoryDumper::doStateMachine() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId,
|
void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {}
|
||||||
uint8_t step) {
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMemoryDumper::stepFailedReceived(ActionId_t actionId, uint8_t step,
|
void PlocMemoryDumper::stepFailedReceived(ActionId_t actionId, uint8_t step,
|
||||||
ReturnValue_t returnCode) {
|
ReturnValue_t returnCode) {}
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {
|
void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {}
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocMemoryDumper::completionSuccessfulReceived(ActionId_t actionId) {
|
void PlocMemoryDumper::completionSuccessfulReceived(ActionId_t actionId) {
|
||||||
switch (pendingCommand) {
|
switch (pendingCommand) {
|
||||||
@ -140,8 +130,7 @@ void PlocMemoryDumper::completionSuccessfulReceived(ActionId_t actionId) {
|
|||||||
if (mram.endAddress == mram.startAddress) {
|
if (mram.endAddress == mram.startAddress) {
|
||||||
triggerEvent(MRAM_DUMP_FINISHED);
|
triggerEvent(MRAM_DUMP_FINISHED);
|
||||||
state = State::IDLE;
|
state = State::IDLE;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
state = State::COMMAND_CONSECUTIVE_MRAM_DUMP;
|
state = State::COMMAND_CONSECUTIVE_MRAM_DUMP;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -153,11 +142,10 @@ void PlocMemoryDumper::completionSuccessfulReceived(ActionId_t actionId) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId,
|
void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) {
|
||||||
ReturnValue_t returnCode) {
|
switch (pendingCommand) {
|
||||||
switch(pendingCommand) {
|
case (PLOC_SPV::FIRST_MRAM_DUMP):
|
||||||
case(PLOC_SPV::FIRST_MRAM_DUMP):
|
case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP):
|
||||||
case(PLOC_SPV::CONSECUTIVE_MRAM_DUMP):
|
|
||||||
triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress);
|
triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
@ -179,8 +167,7 @@ void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) {
|
|||||||
tempEndAddress = mram.startAddress + MAX_MRAM_DUMP_SIZE;
|
tempEndAddress = mram.startAddress + MAX_MRAM_DUMP_SIZE;
|
||||||
mram.startAddress += MAX_MRAM_DUMP_SIZE;
|
mram.startAddress += MAX_MRAM_DUMP_SIZE;
|
||||||
mram.lastStartAddress = tempStartAddress;
|
mram.lastStartAddress = tempStartAddress;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
tempStartAddress = mram.startAddress;
|
tempStartAddress = mram.startAddress;
|
||||||
tempEndAddress = mram.endAddress;
|
tempEndAddress = mram.endAddress;
|
||||||
mram.startAddress = mram.endAddress;
|
mram.startAddress = mram.endAddress;
|
||||||
@ -188,8 +175,8 @@ void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) {
|
|||||||
|
|
||||||
MemoryParams params(tempStartAddress, tempEndAddress);
|
MemoryParams params(tempStartAddress, tempEndAddress);
|
||||||
|
|
||||||
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
result =
|
||||||
dumpCommand, ¶ms);
|
commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, dumpCommand, ¶ms);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::warning << "PlocMemoryDumper::commandNextMramDump: Failed to send mram dump command "
|
sif::warning << "PlocMemoryDumper::commandNextMramDump: Failed to send mram dump command "
|
||||||
<< "with start address " << tempStartAddress << " and end address "
|
<< "with start address " << tempStartAddress << " and end address "
|
||||||
@ -203,4 +190,3 @@ void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) {
|
|||||||
pendingCommand = dumpCommand;
|
pendingCommand = dumpCommand;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3,18 +3,18 @@
|
|||||||
|
|
||||||
#include <bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h>
|
#include <bsp_q7s/devices/devicedefinitions/PlocMemDumpDefinitions.h>
|
||||||
#include <bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h>
|
#include <bsp_q7s/devices/devicedefinitions/PlocSupervisorDefinitions.h>
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
#include "fsfw/action/CommandActionHelper.h"
|
#include "bsp_q7s/memory/SdCardManager.h"
|
||||||
#include "fsfw/action/ActionHelper.h"
|
#include "fsfw/action/ActionHelper.h"
|
||||||
#include "fsfw/action/HasActionsIF.h"
|
#include "fsfw/action/CommandActionHelper.h"
|
||||||
#include "fsfw/action/CommandsActionsIF.h"
|
#include "fsfw/action/CommandsActionsIF.h"
|
||||||
|
#include "fsfw/action/HasActionsIF.h"
|
||||||
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
#include "fsfw/tasks/ExecutableObjectIF.h"
|
#include "fsfw/tasks/ExecutableObjectIF.h"
|
||||||
#include "fsfw/objectmanager/SystemObject.h"
|
|
||||||
#include "bsp_q7s/memory/SdCardManager.h"
|
|
||||||
#include "linux/fsfwconfig/objects/systemObjectList.h"
|
|
||||||
#include "fsfw/tmtcpacket/SpacePacket.h"
|
#include "fsfw/tmtcpacket/SpacePacket.h"
|
||||||
|
#include "linux/fsfwconfig/objects/systemObjectList.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Because the buffer of the linux tty driver is limited to 2 x 65535 bytes, this class is
|
* @brief Because the buffer of the linux tty driver is limited to 2 x 65535 bytes, this class is
|
||||||
@ -29,8 +29,7 @@ class PlocMemoryDumper : public SystemObject,
|
|||||||
public ExecutableObjectIF,
|
public ExecutableObjectIF,
|
||||||
public HasReturnvaluesIF,
|
public HasReturnvaluesIF,
|
||||||
public CommandsActionsIF {
|
public CommandsActionsIF {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
static const ActionId_t NONE = 0;
|
static const ActionId_t NONE = 0;
|
||||||
static const ActionId_t DUMP_MRAM = 1;
|
static const ActionId_t DUMP_MRAM = 1;
|
||||||
|
|
||||||
@ -49,13 +48,13 @@ public:
|
|||||||
void completionSuccessfulReceived(ActionId_t actionId) override;
|
void completionSuccessfulReceived(ActionId_t actionId) override;
|
||||||
void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override;
|
void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
static const uint32_t QUEUE_SIZE = 10;
|
static const uint32_t QUEUE_SIZE = 10;
|
||||||
|
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MEMORY_DUMPER;
|
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_MEMORY_DUMPER;
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.
|
//! [EXPORT] : [COMMENT] The capacity of the MRAM amounts to 512 kB. Thus the maximum address must
|
||||||
|
//! not be higher than 0x7d000.
|
||||||
static const ReturnValue_t MRAM_ADDRESS_TOO_HIGH = MAKE_RETURN_CODE(0xA0);
|
static const ReturnValue_t MRAM_ADDRESS_TOO_HIGH = MAKE_RETURN_CODE(0xA0);
|
||||||
//! [EXPORT] : [COMMENT] The specified end address is lower than the start address
|
//! [EXPORT] : [COMMENT] The specified end address is lower than the start address
|
||||||
static const ReturnValue_t MRAM_INVALID_ADDRESS_COMBINATION = MAKE_RETURN_CODE(0xA1);
|
static const ReturnValue_t MRAM_INVALID_ADDRESS_COMBINATION = MAKE_RETURN_CODE(0xA1);
|
||||||
@ -82,7 +81,7 @@ private:
|
|||||||
|
|
||||||
ActionHelper actionHelper;
|
ActionHelper actionHelper;
|
||||||
|
|
||||||
enum class State: uint8_t {
|
enum class State : uint8_t {
|
||||||
IDLE,
|
IDLE,
|
||||||
COMMAND_FIRST_MRAM_DUMP,
|
COMMAND_FIRST_MRAM_DUMP,
|
||||||
COMMAND_CONSECUTIVE_MRAM_DUMP,
|
COMMAND_CONSECUTIVE_MRAM_DUMP,
|
||||||
|
@ -1,26 +1,28 @@
|
|||||||
#include <sstream>
|
|
||||||
#include <string>
|
|
||||||
#include <fstream>
|
|
||||||
#include <filesystem>
|
|
||||||
|
|
||||||
#include "PlocSupervisorHandler.h"
|
#include "PlocSupervisorHandler.h"
|
||||||
#include "OBSWConfig.h"
|
|
||||||
|
|
||||||
#include <fsfw/globalfunctions/CRC.h>
|
|
||||||
#include <fsfw/datapool/PoolReadGuard.h>
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
|
#include <fsfw/globalfunctions/CRC.h>
|
||||||
#include <fsfw/timemanager/Clock.h>
|
#include <fsfw/timemanager/Clock.h>
|
||||||
|
|
||||||
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
|
#include <sstream>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
|
|
||||||
PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid,
|
PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid,
|
||||||
CookieIF * comCookie) :
|
CookieIF* comCookie)
|
||||||
DeviceHandlerBase(objectId, uartComIFid, comCookie), hkset(this), bootStatusReport(this), latchupStatusReport(
|
: DeviceHandlerBase(objectId, uartComIFid, comCookie),
|
||||||
this) {
|
hkset(this),
|
||||||
|
bootStatusReport(this),
|
||||||
|
latchupStatusReport(this) {
|
||||||
if (comCookie == NULL) {
|
if (comCookie == NULL) {
|
||||||
sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl;
|
sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
PlocSupervisorHandler::~PlocSupervisorHandler() {
|
PlocSupervisorHandler::~PlocSupervisorHandler() {}
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::initialize() {
|
ReturnValue_t PlocSupervisorHandler::initialize() {
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
@ -41,8 +43,7 @@ ReturnValue_t PlocSupervisorHandler::initialize() {
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void PlocSupervisorHandler::doStartUp() {
|
||||||
void PlocSupervisorHandler::doStartUp(){
|
|
||||||
#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
|
||||||
@ -50,210 +51,206 @@ void PlocSupervisorHandler::doStartUp(){
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::doShutDown(){
|
void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); }
|
||||||
setMode(_MODE_POWER_DOWN);
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(
|
ReturnValue_t PlocSupervisorHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
|
||||||
DeviceCommandId_t * id) {
|
|
||||||
return NOTHING_TO_SEND;
|
return NOTHING_TO_SEND;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(
|
ReturnValue_t PlocSupervisorHandler::buildTransitionDeviceCommand(DeviceCommandId_t* id) {
|
||||||
DeviceCommandId_t * id){
|
|
||||||
return NOTHING_TO_SEND;
|
return NOTHING_TO_SEND;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(
|
ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t * commandData,
|
const uint8_t* commandData,
|
||||||
size_t commandDataLen) {
|
size_t commandDataLen) {
|
||||||
ReturnValue_t result = RETURN_FAILED;
|
ReturnValue_t result = RETURN_FAILED;
|
||||||
switch(deviceCommand) {
|
switch (deviceCommand) {
|
||||||
case(PLOC_SPV::GET_HK_REPORT): {
|
case (PLOC_SPV::GET_HK_REPORT): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_GET_HK_REPORT);
|
prepareEmptyCmd(PLOC_SPV::APID_GET_HK_REPORT);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::RESTART_MPSOC): {
|
case (PLOC_SPV::RESTART_MPSOC): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_RESTART_MPSOC);
|
prepareEmptyCmd(PLOC_SPV::APID_RESTART_MPSOC);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::START_MPSOC): {
|
case (PLOC_SPV::START_MPSOC): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_START_MPSOC);
|
prepareEmptyCmd(PLOC_SPV::APID_START_MPSOC);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SHUTDOWN_MPSOC): {
|
case (PLOC_SPV::SHUTDOWN_MPSOC): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_SHUTWOWN_MPSOC);
|
prepareEmptyCmd(PLOC_SPV::APID_SHUTWOWN_MPSOC);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SEL_MPSOC_BOOT_IMAGE): {
|
case (PLOC_SPV::SEL_MPSOC_BOOT_IMAGE): {
|
||||||
prepareSelBootImageCmd(commandData);
|
prepareSelBootImageCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::RESET_MPSOC): {
|
case (PLOC_SPV::RESET_MPSOC): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_RESET_MPSOC);
|
prepareEmptyCmd(PLOC_SPV::APID_RESET_MPSOC);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_TIME_REF): {
|
case (PLOC_SPV::SET_TIME_REF): {
|
||||||
result = prepareSetTimeRefCmd();
|
result = prepareSetTimeRefCmd();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_BOOT_TIMEOUT): {
|
case (PLOC_SPV::SET_BOOT_TIMEOUT): {
|
||||||
prepareSetBootTimeoutCmd(commandData);
|
prepareSetBootTimeoutCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_MAX_RESTART_TRIES): {
|
case (PLOC_SPV::SET_MAX_RESTART_TRIES): {
|
||||||
prepareRestartTriesCmd(commandData);
|
prepareRestartTriesCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION): {
|
case (PLOC_SPV::DISABLE_PERIOIC_HK_TRANSMISSION): {
|
||||||
prepareDisableHk();
|
prepareDisableHk();
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::GET_BOOT_STATUS_REPORT): {
|
case (PLOC_SPV::GET_BOOT_STATUS_REPORT): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_GET_BOOT_STATUS_RPT);
|
prepareEmptyCmd(PLOC_SPV::APID_GET_BOOT_STATUS_RPT);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::WATCHDOGS_ENABLE): {
|
case (PLOC_SPV::WATCHDOGS_ENABLE): {
|
||||||
prepareWatchdogsEnableCmd(commandData);
|
prepareWatchdogsEnableCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT): {
|
case (PLOC_SPV::WATCHDOGS_CONFIG_TIMEOUT): {
|
||||||
result = prepareWatchdogsConfigTimeoutCmd(commandData);
|
result = prepareWatchdogsConfigTimeoutCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::ENABLE_LATCHUP_ALERT): {
|
case (PLOC_SPV::ENABLE_LATCHUP_ALERT): {
|
||||||
result = prepareLatchupConfigCmd(commandData, deviceCommand);
|
result = prepareLatchupConfigCmd(commandData, deviceCommand);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::DISABLE_LATCHUP_ALERT): {
|
case (PLOC_SPV::DISABLE_LATCHUP_ALERT): {
|
||||||
result = prepareLatchupConfigCmd(commandData, deviceCommand);
|
result = prepareLatchupConfigCmd(commandData, deviceCommand);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::AUTO_CALIBRATE_ALERT): {
|
case (PLOC_SPV::AUTO_CALIBRATE_ALERT): {
|
||||||
result = prepareAutoCalibrateAlertCmd(commandData);
|
result = prepareAutoCalibrateAlertCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ALERT_LIMIT): {
|
case (PLOC_SPV::SET_ALERT_LIMIT): {
|
||||||
result = prepareSetAlertLimitCmd(commandData);
|
result = prepareSetAlertLimitCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ALERT_IRQ_FILTER): {
|
case (PLOC_SPV::SET_ALERT_IRQ_FILTER): {
|
||||||
result = prepareSetAlertIrqFilterCmd(commandData);
|
result = prepareSetAlertIrqFilterCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ADC_SWEEP_PERIOD): {
|
case (PLOC_SPV::SET_ADC_SWEEP_PERIOD): {
|
||||||
result = prepareSetAdcSweetPeriodCmd(commandData);
|
result = prepareSetAdcSweetPeriodCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ADC_ENABLED_CHANNELS): {
|
case (PLOC_SPV::SET_ADC_ENABLED_CHANNELS): {
|
||||||
prepareSetAdcEnabledChannelsCmd(commandData);
|
prepareSetAdcEnabledChannelsCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE): {
|
case (PLOC_SPV::SET_ADC_WINDOW_AND_STRIDE): {
|
||||||
prepareSetAdcWindowAndStrideCmd(commandData);
|
prepareSetAdcWindowAndStrideCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_ADC_THRESHOLD): {
|
case (PLOC_SPV::SET_ADC_THRESHOLD): {
|
||||||
prepareSetAdcThresholdCmd(commandData);
|
prepareSetAdcThresholdCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::GET_LATCHUP_STATUS_REPORT): {
|
case (PLOC_SPV::GET_LATCHUP_STATUS_REPORT): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_GET_LATCHUP_STATUS_REPORT);
|
prepareEmptyCmd(PLOC_SPV::APID_GET_LATCHUP_STATUS_REPORT);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::COPY_ADC_DATA_TO_MRAM): {
|
case (PLOC_SPV::COPY_ADC_DATA_TO_MRAM): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_COPY_ADC_DATA_TO_MRAM);
|
prepareEmptyCmd(PLOC_SPV::APID_COPY_ADC_DATA_TO_MRAM);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::ENABLE_NVMS): {
|
case (PLOC_SPV::ENABLE_NVMS): {
|
||||||
prepareEnableNvmsCmd(commandData);
|
prepareEnableNvmsCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SELECT_NVM): {
|
case (PLOC_SPV::SELECT_NVM): {
|
||||||
prepareSelectNvmCmd(commandData);
|
prepareSelectNvmCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::RUN_AUTO_EM_TESTS): {
|
case (PLOC_SPV::RUN_AUTO_EM_TESTS): {
|
||||||
result = prepareRunAutoEmTest(commandData);
|
result = prepareRunAutoEmTest(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::WIPE_MRAM): {
|
case (PLOC_SPV::WIPE_MRAM): {
|
||||||
result = prepareWipeMramCmd(commandData);
|
result = prepareWipeMramCmd(commandData);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::FIRST_MRAM_DUMP):
|
case (PLOC_SPV::FIRST_MRAM_DUMP):
|
||||||
case(PLOC_SPV::CONSECUTIVE_MRAM_DUMP):
|
case (PLOC_SPV::CONSECUTIVE_MRAM_DUMP):
|
||||||
result = prepareDumpMramCmd(commandData);
|
result = prepareDumpMramCmd(commandData);
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::PRINT_CPU_STATS): {
|
case (PLOC_SPV::PRINT_CPU_STATS): {
|
||||||
preparePrintCpuStatsCmd(commandData);
|
preparePrintCpuStatsCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_DBG_VERBOSITY): {
|
case (PLOC_SPV::SET_DBG_VERBOSITY): {
|
||||||
prepareSetDbgVerbosityCmd(commandData);
|
prepareSetDbgVerbosityCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::CAN_LOOPBACK_TEST): {
|
case (PLOC_SPV::CAN_LOOPBACK_TEST): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_CAN_LOOPBACK_TEST);
|
prepareEmptyCmd(PLOC_SPV::APID_CAN_LOOPBACK_TEST);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::SET_GPIO): {
|
case (PLOC_SPV::SET_GPIO): {
|
||||||
prepareSetGpioCmd(commandData);
|
prepareSetGpioCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::READ_GPIO): {
|
case (PLOC_SPV::READ_GPIO): {
|
||||||
prepareReadGpioCmd(commandData);
|
prepareReadGpioCmd(commandData);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::RESTART_SUPERVISOR): {
|
case (PLOC_SPV::RESTART_SUPERVISOR): {
|
||||||
prepareEmptyCmd(PLOC_SPV::APID_RESTART_SUPERVISOR);
|
prepareEmptyCmd(PLOC_SPV::APID_RESTART_SUPERVISOR);
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::FACTORY_RESET_CLEAR_ALL): {
|
case (PLOC_SPV::FACTORY_RESET_CLEAR_ALL): {
|
||||||
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CLEAR_ALL);
|
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CLEAR_ALL);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR): {
|
case (PLOC_SPV::FACTORY_RESET_CLEAR_MIRROR): {
|
||||||
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::MIRROR_ENTRIES);
|
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::MIRROR_ENTRIES);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR): {
|
case (PLOC_SPV::FACTORY_RESET_CLEAR_CIRCULAR): {
|
||||||
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CIRCULAR_ENTRIES);
|
PLOC_SPV::FactoryReset packet(PLOC_SPV::FactoryReset::Op::CIRCULAR_ENTRIES);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
result = RETURN_OK;
|
result = RETURN_OK;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::UPDATE_AVAILABLE):
|
case (PLOC_SPV::UPDATE_AVAILABLE):
|
||||||
case(PLOC_SPV::UPDATE_IMAGE_DATA):
|
case (PLOC_SPV::UPDATE_IMAGE_DATA):
|
||||||
case(PLOC_SPV::UPDATE_VERIFY):
|
case (PLOC_SPV::UPDATE_VERIFY):
|
||||||
// Simply forward data from PLOC Updater to supervisor
|
// Simply forward data from PLOC Updater to supervisor
|
||||||
std::memcpy(commandBuffer, commandData, commandDataLen);
|
std::memcpy(commandBuffer, commandData, commandDataLen);
|
||||||
rawPacket = commandBuffer;
|
rawPacket = commandBuffer;
|
||||||
@ -330,14 +327,12 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() {
|
|||||||
PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT);
|
PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT);
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t *start,
|
ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t remainingSize,
|
||||||
size_t remainingSize, DeviceCommandId_t *foundId, size_t *foundLen) {
|
DeviceCommandId_t* foundId, size_t* foundLen) {
|
||||||
|
|
||||||
if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP) {
|
if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP) {
|
||||||
*foundId = PLOC_SPV::FIRST_MRAM_DUMP;
|
*foundId = PLOC_SPV::FIRST_MRAM_DUMP;
|
||||||
return parseMramPackets(start, remainingSize, foundLen);
|
return parseMramPackets(start, remainingSize, foundLen);
|
||||||
}
|
} else if (nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) {
|
||||||
else if (nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) {
|
|
||||||
*foundId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP;
|
*foundId = PLOC_SPV::CONSECUTIVE_MRAM_DUMP;
|
||||||
return parseMramPackets(start, remainingSize, foundLen);
|
return parseMramPackets(start, remainingSize, foundLen);
|
||||||
}
|
}
|
||||||
@ -346,32 +341,32 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t *start,
|
|||||||
|
|
||||||
uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK;
|
uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK;
|
||||||
|
|
||||||
switch(apid) {
|
switch (apid) {
|
||||||
case(PLOC_SPV::APID_ACK_SUCCESS):
|
case (PLOC_SPV::APID_ACK_SUCCESS):
|
||||||
*foundLen = PLOC_SPV::SIZE_ACK_REPORT;
|
*foundLen = PLOC_SPV::SIZE_ACK_REPORT;
|
||||||
*foundId = PLOC_SPV::ACK_REPORT;
|
*foundId = PLOC_SPV::ACK_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_ACK_FAILURE):
|
case (PLOC_SPV::APID_ACK_FAILURE):
|
||||||
*foundLen = PLOC_SPV::SIZE_ACK_REPORT;
|
*foundLen = PLOC_SPV::SIZE_ACK_REPORT;
|
||||||
*foundId = PLOC_SPV::ACK_REPORT;
|
*foundId = PLOC_SPV::ACK_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_HK_REPORT):
|
case (PLOC_SPV::APID_HK_REPORT):
|
||||||
*foundLen = PLOC_SPV::SIZE_HK_REPORT;
|
*foundLen = PLOC_SPV::SIZE_HK_REPORT;
|
||||||
*foundId = PLOC_SPV::HK_REPORT;
|
*foundId = PLOC_SPV::HK_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_BOOT_STATUS_REPORT):
|
case (PLOC_SPV::APID_BOOT_STATUS_REPORT):
|
||||||
*foundLen = PLOC_SPV::SIZE_BOOT_STATUS_REPORT;
|
*foundLen = PLOC_SPV::SIZE_BOOT_STATUS_REPORT;
|
||||||
*foundId = PLOC_SPV::BOOT_STATUS_REPORT;
|
*foundId = PLOC_SPV::BOOT_STATUS_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_LATCHUP_STATUS_REPORT):
|
case (PLOC_SPV::APID_LATCHUP_STATUS_REPORT):
|
||||||
*foundLen = PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT;
|
*foundLen = PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT;
|
||||||
*foundId = PLOC_SPV::LATCHUP_REPORT;
|
*foundId = PLOC_SPV::LATCHUP_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_EXE_SUCCESS):
|
case (PLOC_SPV::APID_EXE_SUCCESS):
|
||||||
*foundLen = PLOC_SPV::SIZE_EXE_REPORT;
|
*foundLen = PLOC_SPV::SIZE_EXE_REPORT;
|
||||||
*foundId = PLOC_SPV::EXE_REPORT;
|
*foundId = PLOC_SPV::EXE_REPORT;
|
||||||
break;
|
break;
|
||||||
case(PLOC_SPV::APID_EXE_FAILURE):
|
case (PLOC_SPV::APID_EXE_FAILURE):
|
||||||
*foundLen = PLOC_SPV::SIZE_EXE_REPORT;
|
*foundLen = PLOC_SPV::SIZE_EXE_REPORT;
|
||||||
*foundId = PLOC_SPV::EXE_REPORT;
|
*foundId = PLOC_SPV::EXE_REPORT;
|
||||||
break;
|
break;
|
||||||
@ -386,8 +381,7 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t *start,
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id,
|
ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||||
const uint8_t *packet) {
|
const uint8_t* packet) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
switch (id) {
|
switch (id) {
|
||||||
@ -416,7 +410,8 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default: {
|
default: {
|
||||||
sif::debug << "PlocSupervisorHandler::interpretDeviceReply: Unknown device reply id" << std::endl;
|
sif::debug << "PlocSupervisorHandler::interpretDeviceReply: Unknown device reply id"
|
||||||
|
<< std::endl;
|
||||||
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
|
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -424,63 +419,58 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid(){
|
void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid() {}
|
||||||
|
|
||||||
}
|
uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 500; }
|
||||||
|
|
||||||
uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo){
|
|
||||||
return 500;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
LocalDataPoolManager& poolManager) {
|
LocalDataPoolManager& poolManager) {
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::NUM_TMS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::TEMP_PS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::TEMP_PL, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::SOC_STATE, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::NVM0_1_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::NVM3_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::MISSION_IO_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::FMC_STATE, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::NUM_TCS, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::UPTIME, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::CPULOAD, new PoolEntry<uint32_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::AVAILABLEHEAP, new PoolEntry<uint32_t>({0}));
|
||||||
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::NUM_TMS, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BOOT_SIGNAL, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::TEMP_PS, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::RESET_COUNTER, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::TEMP_PL, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BOOT_AFTER_MS, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::SOC_STATE, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BOOT_TIMEOUT_MS, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::NVM0_1_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::ACTIVE_NVM, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::NVM3_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BP0_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::MISSION_IO_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BP1_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::FMC_STATE, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::BP2_STATE, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::NUM_TCS, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::UPTIME, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CPULOAD, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::AVAILABLEHEAP, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BOOT_SIGNAL, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_ID, new PoolEntry<uint8_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::RESET_COUNTER, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT0, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BOOT_AFTER_MS, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT1, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BOOT_TIMEOUT_MS, new PoolEntry<uint32_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT2, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::ACTIVE_NVM, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT3, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BP0_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT4, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BP1_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT5, new PoolEntry<uint16_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::BP2_STATE, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::CNT6, new PoolEntry<uint16_t>({0}));
|
||||||
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_SEC, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_ID, new PoolEntry<uint8_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MIN, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT0, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_HOUR, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT1, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_DAY, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT2, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MON, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT3, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_YEAR, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT4, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MSEC, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT5, new PoolEntry<uint16_t>( { 0 }));
|
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_IS_SET, new PoolEntry<uint32_t>({0}));
|
||||||
localDataPoolMap.emplace(PLOC_SPV::CNT6, new PoolEntry<uint16_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_SEC, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MIN, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_HOUR, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_DAY, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MON, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_YEAR, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_MSEC, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
localDataPoolMap.emplace(PLOC_SPV::LATCHUP_RPT_TIME_IS_SET, new PoolEntry<uint32_t>( { 0 }));
|
|
||||||
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command,
|
ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command,
|
||||||
uint8_t expectedReplies, bool useAlternateId,
|
uint8_t expectedReplies,
|
||||||
|
bool useAlternateId,
|
||||||
DeviceCommandId_t alternateReplyID) {
|
DeviceCommandId_t alternateReplyID) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
uint8_t enabledReplies = 0;
|
uint8_t enabledReplies = 0;
|
||||||
@ -585,15 +575,15 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite
|
|||||||
* Every command causes at least one acknowledgment and one execution report. Therefore both
|
* Every command causes at least one acknowledgment and one execution report. Therefore both
|
||||||
* replies will be enabled here.
|
* replies will be enabled here.
|
||||||
*/
|
*/
|
||||||
result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true,
|
result =
|
||||||
PLOC_SPV::ACK_REPORT);
|
DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, PLOC_SPV::ACK_REPORT);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id "
|
sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id "
|
||||||
<< PLOC_SPV::ACK_REPORT << " not in replyMap" << std::endl;
|
<< PLOC_SPV::ACK_REPORT << " not in replyMap" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true,
|
result =
|
||||||
PLOC_SPV::EXE_REPORT);
|
DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, PLOC_SPV::EXE_REPORT);
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id "
|
sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id "
|
||||||
<< PLOC_SPV::EXE_REPORT << " not in replyMap" << std::endl;
|
<< PLOC_SPV::EXE_REPORT << " not in replyMap" << std::endl;
|
||||||
@ -603,7 +593,6 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t foundLen) {
|
ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t foundLen) {
|
||||||
|
|
||||||
uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1);
|
uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1);
|
||||||
|
|
||||||
uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2);
|
uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2);
|
||||||
@ -616,11 +605,10 @@ ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t f
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
result = verifyPacket(data, PLOC_SPV::SIZE_ACK_REPORT);
|
result = verifyPacket(data, PLOC_SPV::SIZE_ACK_REPORT);
|
||||||
if(result == CRC_FAILURE) {
|
if (result == CRC_FAILURE) {
|
||||||
sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl;
|
sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl;
|
||||||
nextReplyId = PLOC_SPV::NONE;
|
nextReplyId = PLOC_SPV::NONE;
|
||||||
replyRawReplyIfnotWiretapped(data, PLOC_SPV::SIZE_ACK_REPORT);
|
replyRawReplyIfnotWiretapped(data, PLOC_SPV::SIZE_ACK_REPORT);
|
||||||
@ -632,10 +620,11 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
|||||||
|
|
||||||
uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK;
|
uint16_t apid = (*(data) << 8 | *(data + 1)) & APID_MASK;
|
||||||
|
|
||||||
switch(apid) {
|
switch (apid) {
|
||||||
case PLOC_SPV::APID_ACK_FAILURE: {
|
case PLOC_SPV::APID_ACK_FAILURE: {
|
||||||
//TODO: Interpretation of status field in acknowledgment report
|
// TODO: Interpretation of status field in acknowledgment report
|
||||||
sif::debug << "PlocSupervisorHandler::handleAckReport: Received Ack failure report" << std::endl;
|
sif::debug << "PlocSupervisorHandler::handleAckReport: Received Ack failure report"
|
||||||
|
<< std::endl;
|
||||||
DeviceCommandId_t commandId = getPendingCommand();
|
DeviceCommandId_t commandId = getPendingCommand();
|
||||||
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
||||||
triggerEvent(SUPV_ACK_FAILURE, commandId);
|
triggerEvent(SUPV_ACK_FAILURE, commandId);
|
||||||
@ -651,7 +640,8 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default: {
|
default: {
|
||||||
sif::debug << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" << std::endl;
|
sif::debug << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report"
|
||||||
|
<< std::endl;
|
||||||
result = RETURN_FAILED;
|
result = RETURN_FAILED;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -661,11 +651,10 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) {
|
ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
result = verifyPacket(data, PLOC_SPV::SIZE_EXE_REPORT);
|
result = verifyPacket(data, PLOC_SPV::SIZE_EXE_REPORT);
|
||||||
if(result == CRC_FAILURE) {
|
if (result == CRC_FAILURE) {
|
||||||
sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl;
|
sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl;
|
||||||
nextReplyId = PLOC_SPV::NONE;
|
nextReplyId = PLOC_SPV::NONE;
|
||||||
return result;
|
return result;
|
||||||
@ -678,15 +667,16 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case (PLOC_SPV::APID_EXE_FAILURE): {
|
case (PLOC_SPV::APID_EXE_FAILURE): {
|
||||||
//TODO: Interpretation of status field in execution report
|
// TODO: Interpretation of status field in execution report
|
||||||
sif::error << "PlocSupervisorHandler::handleExecutionReport: Received execution failure report"
|
sif::error
|
||||||
|
<< "PlocSupervisorHandler::handleExecutionReport: Received execution failure report"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
DeviceCommandId_t commandId = getPendingCommand();
|
DeviceCommandId_t commandId = getPendingCommand();
|
||||||
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
if (commandId != DeviceHandlerIF::NO_COMMAND_ID) {
|
||||||
triggerEvent(SUPV_EXE_FAILURE, commandId);
|
triggerEvent(SUPV_EXE_FAILURE, commandId);
|
||||||
}
|
} else {
|
||||||
else {
|
sif::debug << "PlocSupervisorHandler::handleExecutionReport: Unknown command id"
|
||||||
sif::debug << "PlocSupervisorHandler::handleExecutionReport: Unknown command id" << std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
sendFailureReport(PLOC_SPV::EXE_REPORT, RECEIVED_EXE_FAILURE);
|
sendFailureReport(PLOC_SPV::EXE_REPORT, RECEIVED_EXE_FAILURE);
|
||||||
disableExeReportReply();
|
disableExeReportReply();
|
||||||
@ -706,43 +696,41 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data)
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) {
|
ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
result = verifyPacket(data, PLOC_SPV::SIZE_HK_REPORT);
|
result = verifyPacket(data, PLOC_SPV::SIZE_HK_REPORT);
|
||||||
|
|
||||||
if(result == CRC_FAILURE) {
|
if (result == CRC_FAILURE) {
|
||||||
sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc"
|
sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc" << std::endl;
|
||||||
<< std::endl;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET;
|
uint16_t offset = PLOC_SPV::DATA_FIELD_OFFSET;
|
||||||
hkset.tempPs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.tempPs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.tempPl = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.tempPl = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.tempSup = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.tempSup = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.uptime = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.uptime = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.cpuLoad = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.cpuLoad = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.availableHeap = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.availableHeap = *(data + offset) << 24 | *(data + offset + 1) << 16 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 2) << 8 | *(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.numTcs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.numTcs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.numTms = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.numTms = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.socState = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8
|
hkset.socState = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 |
|
||||||
| *(data + offset + 3);
|
*(data + offset + 3);
|
||||||
offset += 4;
|
offset += 4;
|
||||||
hkset.nvm0_1_state = *(data + offset);
|
hkset.nvm0_1_state = *(data + offset);
|
||||||
offset += 1;
|
offset += 1;
|
||||||
@ -761,7 +749,8 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) {
|
|||||||
sif::info << "PlocSupervisorHandler::handleHkReport: temp_sup: " << hkset.tempSup << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: temp_sup: " << hkset.tempSup << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: uptime: " << hkset.uptime << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: uptime: " << hkset.uptime << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: cpu_load: " << hkset.cpuLoad << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: cpu_load: " << hkset.cpuLoad << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: available_heap: " << hkset.availableHeap << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: available_heap: " << hkset.availableHeap
|
||||||
|
<< std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: num_tcs: " << hkset.numTcs << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: num_tcs: " << hkset.numTcs << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: num_tms: " << hkset.numTms << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: num_tms: " << hkset.numTms << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleHkReport: soc_state: " << hkset.socState << std::endl;
|
sif::info << "PlocSupervisorHandler::handleHkReport: soc_state: " << hkset.socState << std::endl;
|
||||||
@ -780,14 +769,14 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) {
|
ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
result = verifyPacket(data, PLOC_SPV::SIZE_BOOT_STATUS_REPORT);
|
result = verifyPacket(data, PLOC_SPV::SIZE_BOOT_STATUS_REPORT);
|
||||||
|
|
||||||
if(result == CRC_FAILURE) {
|
if (result == CRC_FAILURE) {
|
||||||
sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid"
|
sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid"
|
||||||
" crc" << std::endl;
|
" crc"
|
||||||
|
<< std::endl;
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -835,12 +824,11 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data)
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* data) {
|
ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* data) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
result = verifyPacket(data, PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT);
|
result = verifyPacket(data, PLOC_SPV::SIZE_LATCHUP_STATUS_REPORT);
|
||||||
|
|
||||||
if(result == CRC_FAILURE) {
|
if (result == CRC_FAILURE) {
|
||||||
sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has "
|
sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has "
|
||||||
<< "invalid crc" << std::endl;
|
<< "invalid crc" << std::endl;
|
||||||
return result;
|
return result;
|
||||||
@ -921,15 +909,15 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da
|
|||||||
<< latchupStatusReport.timeYear << std::endl;
|
<< latchupStatusReport.timeYear << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Msec: "
|
sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: Msec: "
|
||||||
<< latchupStatusReport.timeMsec << std::endl;
|
<< latchupStatusReport.timeMsec << std::endl;
|
||||||
sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: 0x"
|
sif::info << "PlocSupervisorHandler::handleLatchupStatusReport: isSet: 0x" << std::hex
|
||||||
<< std::hex << latchupStatusReport.timeMsec << std::dec << std::endl;
|
<< latchupStatusReport.timeMsec << std::dec << std::endl;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::setNextReplyId() {
|
void PlocSupervisorHandler::setNextReplyId() {
|
||||||
switch(getPendingCommand()) {
|
switch (getPendingCommand()) {
|
||||||
case PLOC_SPV::GET_HK_REPORT:
|
case PLOC_SPV::GET_HK_REPORT:
|
||||||
nextReplyId = PLOC_SPV::HK_REPORT;
|
nextReplyId = PLOC_SPV::HK_REPORT;
|
||||||
break;
|
break;
|
||||||
@ -952,16 +940,14 @@ void PlocSupervisorHandler::setNextReplyId() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId){
|
size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId) {
|
||||||
|
|
||||||
size_t replyLen = 0;
|
size_t replyLen = 0;
|
||||||
|
|
||||||
if (nextReplyId == PLOC_SPV::NONE) {
|
if (nextReplyId == PLOC_SPV::NONE) {
|
||||||
return replyLen;
|
return replyLen;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP
|
if (nextReplyId == PLOC_SPV::FIRST_MRAM_DUMP || nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) {
|
||||||
|| nextReplyId == PLOC_SPV::CONSECUTIVE_MRAM_DUMP) {
|
|
||||||
/**
|
/**
|
||||||
* Try to read 20 MRAM packets. If reply is larger, the packets will be read with the
|
* Try to read 20 MRAM packets. If reply is larger, the packets will be read with the
|
||||||
* next doSendRead call. The command will be as long active as the packet with the sequence
|
* next doSendRead call. The command will be as long active as the packet with the sequence
|
||||||
@ -978,8 +964,7 @@ size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId){
|
|||||||
return replyLen;
|
return replyLen;
|
||||||
}
|
}
|
||||||
replyLen = iter->second.replyLen;
|
replyLen = iter->second.replyLen;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::debug << "PlocSupervisorHandler::getNextReplyLength: No entry for reply with reply id "
|
sif::debug << "PlocSupervisorHandler::getNextReplyLength: No entry for reply with reply id "
|
||||||
<< std::hex << nextReplyId << " in deviceReplyMap" << std::endl;
|
<< std::hex << nextReplyId << " in deviceReplyMap" << std::endl;
|
||||||
}
|
}
|
||||||
@ -987,8 +972,8 @@ size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId){
|
|||||||
return replyLen;
|
return replyLen;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId) {
|
void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize,
|
||||||
|
DeviceCommandId_t replyId) {
|
||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
if (wiretappingMode == RAW) {
|
if (wiretappingMode == RAW) {
|
||||||
@ -1018,7 +1003,7 @@ void PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) {
|
|||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t * commandData) {
|
void PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* commandData) {
|
||||||
PLOC_SPV::MPSoCBootSelect packet(*commandData, *(commandData + 1), *(commandData + 2),
|
PLOC_SPV::MPSoCBootSelect packet(*commandData, *(commandData + 1), *(commandData + 2),
|
||||||
*(commandData + 3));
|
*(commandData + 3));
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
@ -1042,20 +1027,20 @@ void PlocSupervisorHandler::prepareDisableHk() {
|
|||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t * commandData) {
|
void PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t* commandData) {
|
||||||
uint32_t timeout = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8
|
uint32_t timeout = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 |
|
||||||
| *(commandData + 3);
|
*(commandData + 3);
|
||||||
PLOC_SPV::SetBootTimeout packet(timeout);
|
PLOC_SPV::SetBootTimeout packet(timeout);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t * commandData) {
|
void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* commandData) {
|
||||||
uint8_t restartTries = *(commandData);
|
uint8_t restartTries = *(commandData);
|
||||||
PLOC_SPV::SetRestartTries packet(restartTries);
|
PLOC_SPV::SetRestartTries packet(restartTries);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::prepareWatchdogsEnableCmd(const uint8_t * commandData) {
|
void PlocSupervisorHandler::prepareWatchdogsEnableCmd(const uint8_t* commandData) {
|
||||||
uint8_t offset = 0;
|
uint8_t offset = 0;
|
||||||
uint8_t watchdogPs = *(commandData + offset);
|
uint8_t watchdogPs = *(commandData + offset);
|
||||||
offset += 1;
|
offset += 1;
|
||||||
@ -1066,15 +1051,15 @@ void PlocSupervisorHandler::prepareWatchdogsEnableCmd(const uint8_t * commandDat
|
|||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::prepareWatchdogsConfigTimeoutCmd(const uint8_t * commandData) {
|
ReturnValue_t PlocSupervisorHandler::prepareWatchdogsConfigTimeoutCmd(const uint8_t* commandData) {
|
||||||
uint8_t offset = 0;
|
uint8_t offset = 0;
|
||||||
uint8_t watchdog = *(commandData + offset);
|
uint8_t watchdog = *(commandData + offset);
|
||||||
offset += 1;
|
offset += 1;
|
||||||
if (watchdog > 2) {
|
if (watchdog > 2) {
|
||||||
return INVALID_WATCHDOG;
|
return INVALID_WATCHDOG;
|
||||||
}
|
}
|
||||||
uint32_t timeout = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16
|
uint32_t timeout = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 |
|
||||||
| *(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
*(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
||||||
if (timeout < 1000 || timeout > 360000) {
|
if (timeout < 1000 || timeout > 360000) {
|
||||||
return INVALID_WATCHDOG_TIMEOUT;
|
return INVALID_WATCHDOG_TIMEOUT;
|
||||||
}
|
}
|
||||||
@ -1115,8 +1100,8 @@ ReturnValue_t PlocSupervisorHandler::prepareAutoCalibrateAlertCmd(const uint8_t*
|
|||||||
uint8_t offset = 0;
|
uint8_t offset = 0;
|
||||||
uint8_t latchupId = *commandData;
|
uint8_t latchupId = *commandData;
|
||||||
offset += 1;
|
offset += 1;
|
||||||
uint32_t mg = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16
|
uint32_t mg = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 |
|
||||||
| *(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
*(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
||||||
if (latchupId > 6) {
|
if (latchupId > 6) {
|
||||||
return INVALID_LATCHUP_ID;
|
return INVALID_LATCHUP_ID;
|
||||||
}
|
}
|
||||||
@ -1141,8 +1126,8 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm
|
|||||||
uint8_t offset = 0;
|
uint8_t offset = 0;
|
||||||
uint8_t latchupId = *commandData;
|
uint8_t latchupId = *commandData;
|
||||||
offset += 1;
|
offset += 1;
|
||||||
uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16
|
uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 |
|
||||||
| *(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
*(commandData + offset + 2) << 8 | *(commandData + offset + 3);
|
||||||
if (latchupId > 6) {
|
if (latchupId > 6) {
|
||||||
return INVALID_LATCHUP_ID;
|
return INVALID_LATCHUP_ID;
|
||||||
}
|
}
|
||||||
@ -1152,8 +1137,8 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::prepareSetAdcSweetPeriodCmd(const uint8_t* commandData) {
|
ReturnValue_t PlocSupervisorHandler::prepareSetAdcSweetPeriodCmd(const uint8_t* commandData) {
|
||||||
uint32_t sweepPeriod = *(commandData) << 24 | *(commandData + 1) << 16
|
uint32_t sweepPeriod = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 |
|
||||||
| *(commandData + 2) << 8 | *(commandData + 3);
|
*(commandData + 3);
|
||||||
if (sweepPeriod < 21) {
|
if (sweepPeriod < 21) {
|
||||||
return SWEEP_PERIOD_TOO_SMALL;
|
return SWEEP_PERIOD_TOO_SMALL;
|
||||||
}
|
}
|
||||||
@ -1178,8 +1163,8 @@ void PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* comma
|
|||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData) {
|
void PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData) {
|
||||||
uint32_t threshold = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8
|
uint32_t threshold = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 |
|
||||||
| *(commandData + 3);
|
*(commandData + 3);
|
||||||
PLOC_SPV::SetAdcThreshold packet(threshold);
|
PLOC_SPV::SetAdcThreshold packet(threshold);
|
||||||
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
packetToOutBuffer(packet.getWholeData(), packet.getFullSize());
|
||||||
}
|
}
|
||||||
@ -1275,12 +1260,11 @@ void PlocSupervisorHandler::packetToOutBuffer(uint8_t* packetData, size_t fullSi
|
|||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::disableAllReplies() {
|
void PlocSupervisorHandler::disableAllReplies() {
|
||||||
|
|
||||||
DeviceReplyMap::iterator iter;
|
DeviceReplyMap::iterator iter;
|
||||||
|
|
||||||
/* Disable ack reply */
|
/* Disable ack reply */
|
||||||
iter = deviceReplyMap.find(PLOC_SPV::ACK_REPORT);
|
iter = deviceReplyMap.find(PLOC_SPV::ACK_REPORT);
|
||||||
DeviceReplyInfo *info = &(iter->second);
|
DeviceReplyInfo* info = &(iter->second);
|
||||||
info->delayCycles = 0;
|
info->delayCycles = 0;
|
||||||
info->command = deviceCommandMap.end();
|
info->command = deviceCommandMap.end();
|
||||||
|
|
||||||
@ -1305,7 +1289,6 @@ void PlocSupervisorHandler::disableAllReplies() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status) {
|
void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnValue_t status) {
|
||||||
|
|
||||||
DeviceReplyIter iter = deviceReplyMap.find(replyId);
|
DeviceReplyIter iter = deviceReplyMap.find(replyId);
|
||||||
|
|
||||||
if (iter == deviceReplyMap.end()) {
|
if (iter == deviceReplyMap.end()) {
|
||||||
@ -1316,7 +1299,8 @@ void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnV
|
|||||||
DeviceCommandInfo* info = &(iter->second.command->second);
|
DeviceCommandInfo* info = &(iter->second.command->second);
|
||||||
|
|
||||||
if (info == nullptr) {
|
if (info == nullptr) {
|
||||||
sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply has no active command" << std::endl;
|
sif::debug << "PlocSupervisorHandler::sendFailureReport: Reply has no active command"
|
||||||
|
<< std::endl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1328,14 +1312,14 @@ void PlocSupervisorHandler::sendFailureReport(DeviceCommandId_t replyId, ReturnV
|
|||||||
|
|
||||||
void PlocSupervisorHandler::disableExeReportReply() {
|
void PlocSupervisorHandler::disableExeReportReply() {
|
||||||
DeviceReplyIter iter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT);
|
DeviceReplyIter iter = deviceReplyMap.find(PLOC_SPV::EXE_REPORT);
|
||||||
DeviceReplyInfo *info = &(iter->second);
|
DeviceReplyInfo* info = &(iter->second);
|
||||||
info->delayCycles = 0;
|
info->delayCycles = 0;
|
||||||
info->command = deviceCommandMap.end();
|
info->command = deviceCommandMap.end();
|
||||||
/* Expected replies is set to one here. The value will set to 0 in replyToReply() */
|
/* Expected replies is set to one here. The value will set to 0 in replyToReply() */
|
||||||
info->command->second.expectedReplies = 1;
|
info->command->second.expectedReplies = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t *packet, size_t remainingSize,
|
ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, size_t remainingSize,
|
||||||
size_t* foundLen) {
|
size_t* foundLen) {
|
||||||
ReturnValue_t result = IGNORE_FULL_PACKET;
|
ReturnValue_t result = IGNORE_FULL_PACKET;
|
||||||
uint16_t packetLen = 0;
|
uint16_t packetLen = 0;
|
||||||
@ -1367,7 +1351,6 @@ ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t *packet, siz
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) {
|
ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) {
|
||||||
|
|
||||||
ReturnValue_t result = RETURN_FAILED;
|
ReturnValue_t result = RETURN_FAILED;
|
||||||
|
|
||||||
// Prepare packet for downlink
|
// Prepare packet for downlink
|
||||||
@ -1380,8 +1363,7 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id)
|
|||||||
}
|
}
|
||||||
handleMramDumpFile(id);
|
handleMramDumpFile(id);
|
||||||
if (downlinkMramDump == true) {
|
if (downlinkMramDump == true) {
|
||||||
handleDeviceTM(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH, packetLen - 1,
|
handleDeviceTM(spacePacketBuffer + PLOC_SPV::SPACE_PACKET_HEADER_LENGTH, packetLen - 1, id);
|
||||||
id);
|
|
||||||
}
|
}
|
||||||
packetInBuffer = false;
|
packetInBuffer = false;
|
||||||
receivedMramDumpPackets++;
|
receivedMramDumpPackets++;
|
||||||
@ -1407,35 +1389,34 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) {
|
|||||||
<< "in reply map" << std::endl;
|
<< "in reply map" << std::endl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
DeviceReplyInfo *mramReplyInfo = &(mramDumpIter->second);
|
DeviceReplyInfo* mramReplyInfo = &(mramDumpIter->second);
|
||||||
if (mramReplyInfo == nullptr) {
|
if (mramReplyInfo == nullptr) {
|
||||||
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: MRAM reply info nullptr"
|
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: MRAM reply info nullptr"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
DeviceReplyInfo *exeReplyInfo = &(exeReportIter->second);
|
DeviceReplyInfo* exeReplyInfo = &(exeReportIter->second);
|
||||||
if (exeReplyInfo == nullptr) {
|
if (exeReplyInfo == nullptr) {
|
||||||
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Execution reply info"
|
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Execution reply info"
|
||||||
<< " nullptr" << std::endl;
|
<< " nullptr" << std::endl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
DeviceCommandInfo* info = &(mramReplyInfo->command->second);
|
DeviceCommandInfo* info = &(mramReplyInfo->command->second);
|
||||||
if (info == nullptr){
|
if (info == nullptr) {
|
||||||
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Command info nullptr"
|
sif::debug << "PlocSupervisorHandler::increaseExpectedReplies: Command info nullptr"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t sequenceFlags = spacePacketBuffer[2] >> 6;
|
uint8_t sequenceFlags = spacePacketBuffer[2] >> 6;
|
||||||
if (sequenceFlags != static_cast<uint8_t>(PLOC_SPV::SequenceFlags::LAST_PKT)
|
if (sequenceFlags != static_cast<uint8_t>(PLOC_SPV::SequenceFlags::LAST_PKT) &&
|
||||||
&& (sequenceFlags != static_cast<uint8_t>(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) {
|
(sequenceFlags != static_cast<uint8_t>(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) {
|
||||||
// Command expects at least one MRAM packet more and the execution report
|
// Command expects at least one MRAM packet more and the execution report
|
||||||
info->expectedReplies = 2;
|
info->expectedReplies = 2;
|
||||||
// Wait maximum of 2 cycles for next MRAM packet
|
// Wait maximum of 2 cycles for next MRAM packet
|
||||||
mramReplyInfo->delayCycles = 2;
|
mramReplyInfo->delayCycles = 2;
|
||||||
// Also adapting delay cycles for execution report
|
// Also adapting delay cycles for execution report
|
||||||
exeReplyInfo->delayCycles = 3;
|
exeReplyInfo->delayCycles = 3;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
// Command expects the execution report
|
// Command expects the execution report
|
||||||
info->expectedReplies = 1;
|
info->expectedReplies = 1;
|
||||||
mramReplyInfo->delayCycles = 0;
|
mramReplyInfo->delayCycles = 0;
|
||||||
@ -1456,8 +1437,8 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) {
|
|||||||
uint16_t packetLen = readSpacePacketLength(spacePacketBuffer);
|
uint16_t packetLen = readSpacePacketLength(spacePacketBuffer);
|
||||||
uint8_t sequenceFlags = readSequenceFlags(spacePacketBuffer);
|
uint8_t sequenceFlags = readSequenceFlags(spacePacketBuffer);
|
||||||
if (id == PLOC_SPV::FIRST_MRAM_DUMP) {
|
if (id == PLOC_SPV::FIRST_MRAM_DUMP) {
|
||||||
if (sequenceFlags == static_cast<uint8_t>(PLOC_SPV::SequenceFlags::FIRST_PKT)
|
if (sequenceFlags == static_cast<uint8_t>(PLOC_SPV::SequenceFlags::FIRST_PKT) ||
|
||||||
|| (sequenceFlags == static_cast<uint8_t>(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) {
|
(sequenceFlags == static_cast<uint8_t>(PLOC_SPV::SequenceFlags::STANDALONE_PKT))) {
|
||||||
result = createMramDumpFile();
|
result = createMramDumpFile();
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
@ -1523,8 +1504,8 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp)
|
|||||||
<< std::endl;
|
<< std::endl;
|
||||||
return GET_TIME_FAILURE;
|
return GET_TIME_FAILURE;
|
||||||
}
|
}
|
||||||
timeStamp = std::to_string(time.year) + "-" + std::to_string(time.month) + "-"
|
timeStamp = std::to_string(time.year) + "-" + std::to_string(time.month) + "-" +
|
||||||
+ std::to_string(time.day) + "--" + std::to_string(time.hour) + "-"
|
std::to_string(time.day) + "--" + std::to_string(time.hour) + "-" +
|
||||||
+ std::to_string(time.minute) + "-" + std::to_string(time.second);
|
std::to_string(time.minute) + "-" + std::to_string(time.second);
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
}
|
}
|
||||||
|
@ -1,12 +1,12 @@
|
|||||||
#ifndef MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_
|
#ifndef MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_
|
||||||
#define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_
|
#define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_
|
||||||
|
|
||||||
#include "devicedefinitions/PlocSupervisorDefinitions.h"
|
|
||||||
#include <bsp_q7s/memory/SdCardManager.h>
|
#include <bsp_q7s/memory/SdCardManager.h>
|
||||||
|
|
||||||
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
|
||||||
#include <fsfw_hal/linux/uart/UartComIF.h>
|
#include <fsfw_hal/linux/uart/UartComIF.h>
|
||||||
|
|
||||||
|
#include "devicedefinitions/PlocSupervisorDefinitions.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This is the device handler for the supervisor of the PLOC which is programmed by
|
* @brief This is the device handler for the supervisor of the PLOC which is programmed by
|
||||||
* Thales.
|
* Thales.
|
||||||
@ -19,26 +19,24 @@
|
|||||||
* Arbeitsdaten/08_Used%20Components/PLOC&fileid=940960
|
* Arbeitsdaten/08_Used%20Components/PLOC&fileid=940960
|
||||||
* @author J. Meier
|
* @author J. Meier
|
||||||
*/
|
*/
|
||||||
class PlocSupervisorHandler: public DeviceHandlerBase {
|
class PlocSupervisorHandler : public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
|
PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie);
|
||||||
PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF * comCookie);
|
|
||||||
virtual ~PlocSupervisorHandler();
|
virtual ~PlocSupervisorHandler();
|
||||||
|
|
||||||
virtual ReturnValue_t initialize() override;
|
virtual ReturnValue_t initialize() override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void doStartUp() override;
|
void doStartUp() override;
|
||||||
void doShutDown() override;
|
void doShutDown() override;
|
||||||
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t * id) override;
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||||
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t * id) override;
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||||
void fillCommandAndReplyMap() override;
|
void fillCommandAndReplyMap() override;
|
||||||
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||||
const uint8_t * commandData,size_t commandDataLen) override;
|
size_t commandDataLen) override;
|
||||||
ReturnValue_t scanForReply(const uint8_t *start, size_t remainingSize,
|
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
size_t* foundLen) override;
|
||||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||||
const uint8_t *packet) override;
|
|
||||||
void setNormalDatapoolEntriesInvalid() override;
|
void setNormalDatapoolEntriesInvalid() override;
|
||||||
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
@ -48,8 +46,7 @@ protected:
|
|||||||
DeviceCommandId_t alternateReplyID = 0) override;
|
DeviceCommandId_t alternateReplyID = 0) override;
|
||||||
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER;
|
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER;
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC
|
//! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC
|
||||||
@ -64,25 +61,32 @@ private:
|
|||||||
static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4);
|
static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4);
|
||||||
//! [EXPORT] : [COMMENT] Invalid communication interface specified
|
//! [EXPORT] : [COMMENT] Invalid communication interface specified
|
||||||
static const ReturnValue_t INVALID_UART_COM_IF = MAKE_RETURN_CODE(0xA5);
|
static const ReturnValue_t INVALID_UART_COM_IF = MAKE_RETURN_CODE(0xA5);
|
||||||
//! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0 for PS, 1 for PL and 2 for INT
|
//! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0
|
||||||
|
//! for PS, 1 for PL and 2 for INT
|
||||||
static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA6);
|
static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA6);
|
||||||
//! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid timeouts must be in the range between 1000 and 360000 ms.
|
//! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid
|
||||||
|
//! timeouts must be in the range between 1000 and 360000 ms.
|
||||||
static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA7);
|
static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA7);
|
||||||
//! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID
|
//! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID
|
||||||
static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA8);
|
static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA8);
|
||||||
//! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be larger than 21.
|
//! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be
|
||||||
|
//! larger than 21.
|
||||||
static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA9);
|
static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA9);
|
||||||
//! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1 and 2.
|
//! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1
|
||||||
|
//! and 2.
|
||||||
static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xAA);
|
static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xAA);
|
||||||
//! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed.
|
//! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed.
|
||||||
static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAB);
|
static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAB);
|
||||||
//! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe commands are invalid (e.g. start address bigger than stop address)
|
//! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe
|
||||||
|
//! commands are invalid (e.g. start address bigger than stop address)
|
||||||
static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAC);
|
static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAC);
|
||||||
//! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with other apid.
|
//! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with
|
||||||
|
//! other apid.
|
||||||
static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAD);
|
static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAD);
|
||||||
//! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist
|
//! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist
|
||||||
static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAE);
|
static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAE);
|
||||||
//! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have been created with the reception of the first dump packet.
|
//! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have
|
||||||
|
//! been created with the reception of the first dump packet.
|
||||||
static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAF);
|
static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAF);
|
||||||
|
|
||||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPERVISOR_HANDLER;
|
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPERVISOR_HANDLER;
|
||||||
@ -209,7 +213,7 @@ private:
|
|||||||
/**
|
/**
|
||||||
* @brief This function initializes the space packet to select the boot image of the MPSoC.
|
* @brief This function initializes the space packet to select the boot image of the MPSoC.
|
||||||
*/
|
*/
|
||||||
void prepareSelBootImageCmd(const uint8_t * commandData);
|
void prepareSelBootImageCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
void prepareDisableHk();
|
void prepareDisableHk();
|
||||||
|
|
||||||
@ -223,21 +227,21 @@ private:
|
|||||||
* @brief This function fills the commandBuffer with the data to change the boot timeout
|
* @brief This function fills the commandBuffer with the data to change the boot timeout
|
||||||
* value in the PLOC supervisor.
|
* value in the PLOC supervisor.
|
||||||
*/
|
*/
|
||||||
void prepareSetBootTimeoutCmd(const uint8_t * commandData);
|
void prepareSetBootTimeoutCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
void prepareRestartTriesCmd(const uint8_t * commandData);
|
void prepareRestartTriesCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function fills the command buffer with the packet to enable or disable the
|
* @brief This function fills the command buffer with the packet to enable or disable the
|
||||||
* watchdogs on the PLOC.
|
* watchdogs on the PLOC.
|
||||||
*/
|
*/
|
||||||
void prepareWatchdogsEnableCmd(const uint8_t * commandData);
|
void prepareWatchdogsEnableCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function fills the command buffer with the packet to set the watchdog timer
|
* @brief This function fills the command buffer with the packet to set the watchdog timer
|
||||||
* of one of the three watchdogs (PS, PL, INT).
|
* of one of the three watchdogs (PS, PL, INT).
|
||||||
*/
|
*/
|
||||||
ReturnValue_t prepareWatchdogsConfigTimeoutCmd(const uint8_t * commandData);
|
ReturnValue_t prepareWatchdogsConfigTimeoutCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData,
|
ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData,
|
||||||
DeviceCommandId_t deviceCommand);
|
DeviceCommandId_t deviceCommand);
|
||||||
@ -258,7 +262,6 @@ private:
|
|||||||
void prepareSetGpioCmd(const uint8_t* commandData);
|
void prepareSetGpioCmd(const uint8_t* commandData);
|
||||||
void prepareReadGpioCmd(const uint8_t* commandData);
|
void prepareReadGpioCmd(const uint8_t* commandData);
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Copies the content of a space packet to the command buffer.
|
* @brief Copies the content of a space packet to the command buffer.
|
||||||
*/
|
*/
|
||||||
@ -290,7 +293,7 @@ private:
|
|||||||
* @brief Function is called in scanForReply and fills the spacePacketBuffer with the read
|
* @brief Function is called in scanForReply and fills the spacePacketBuffer with the read
|
||||||
* data until a full packet has been received.
|
* data until a full packet has been received.
|
||||||
*/
|
*/
|
||||||
ReturnValue_t parseMramPackets(const uint8_t *packet, size_t remainingSize, size_t* foundlen);
|
ReturnValue_t parseMramPackets(const uint8_t* packet, size_t remainingSize, size_t* foundlen);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function generates the Service 8 packets for the MRAM dump data.
|
* @brief This function generates the Service 8 packets for the MRAM dump data.
|
||||||
|
@ -1,17 +1,17 @@
|
|||||||
#include "fsfw/ipc/QueueFactory.h"
|
|
||||||
#include "PlocUpdater.h"
|
#include "PlocUpdater.h"
|
||||||
|
|
||||||
#include <fstream>
|
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
#include <string>
|
#include <string>
|
||||||
|
|
||||||
PlocUpdater::PlocUpdater(object_id_t objectId) :
|
#include "fsfw/ipc/QueueFactory.h"
|
||||||
SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) {
|
|
||||||
|
PlocUpdater::PlocUpdater(object_id_t objectId)
|
||||||
|
: SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) {
|
||||||
commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE);
|
commandQueue = QueueFactory::instance()->createMessageQueue(QUEUE_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
PlocUpdater::~PlocUpdater() {
|
PlocUpdater::~PlocUpdater() {}
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t PlocUpdater::initialize() {
|
ReturnValue_t PlocUpdater::initialize() {
|
||||||
#if BOARD_TE0720 == 0
|
#if BOARD_TE0720 == 0
|
||||||
@ -39,8 +39,8 @@ ReturnValue_t PlocUpdater::performOperation(uint8_t operationCode) {
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t PlocUpdater::executeAction(ActionId_t actionId,
|
ReturnValue_t PlocUpdater::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
MessageQueueId_t commandedBy, const uint8_t* data, size_t size) {
|
const uint8_t* data, size_t size) {
|
||||||
ReturnValue_t result = RETURN_FAILED;
|
ReturnValue_t result = RETURN_FAILED;
|
||||||
|
|
||||||
if (state != State::IDLE) {
|
if (state != State::IDLE) {
|
||||||
@ -99,13 +99,9 @@ ReturnValue_t PlocUpdater::executeAction(ActionId_t actionId,
|
|||||||
return EXECUTION_FINISHED;
|
return EXECUTION_FINISHED;
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageQueueId_t PlocUpdater::getCommandQueue() const {
|
MessageQueueId_t PlocUpdater::getCommandQueue() const { return commandQueue->getId(); }
|
||||||
return commandQueue->getId();
|
|
||||||
}
|
|
||||||
|
|
||||||
MessageQueueIF* PlocUpdater::getCommandQueuePtr() {
|
MessageQueueIF* PlocUpdater::getCommandQueuePtr() { return commandQueue; }
|
||||||
return commandQueue;
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocUpdater::readCommandQueue() {
|
void PlocUpdater::readCommandQueue() {
|
||||||
CommandMessage message;
|
CommandMessage message;
|
||||||
@ -167,74 +163,37 @@ ReturnValue_t PlocUpdater::getImageLocation(const uint8_t* data, size_t size) {
|
|||||||
|
|
||||||
#if BOARD_TE0720 == 0
|
#if BOARD_TE0720 == 0
|
||||||
// Check if file is stored on SD card and if associated SD card is mounted
|
// Check if file is stored on SD card and if associated SD card is mounted
|
||||||
if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) == std::string(SdCardManager::SD_0_MOUNT_POINT)) {
|
if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) ==
|
||||||
if (!isSdCardMounted(sd::SLOT_0)) {
|
std::string(SdCardManager::SD_0_MOUNT_POINT)) {
|
||||||
sif::warning << "PlocUpdater::prepareNvm0AUpdate: SD card 0 not mounted" << std::endl;
|
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
|
||||||
|
sif::warning << "PlocUpdater::getImageLocation: SD card 0 not mounted" << std::endl;
|
||||||
return SD_NOT_MOUNTED;
|
return SD_NOT_MOUNTED;
|
||||||
}
|
}
|
||||||
}
|
} else if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) ==
|
||||||
else if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) == std::string(SdCardManager::SD_1_MOUNT_POINT)) {
|
std::string(SdCardManager::SD_1_MOUNT_POINT)) {
|
||||||
if (!isSdCardMounted(sd::SLOT_0)) {
|
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
|
||||||
sif::warning << "PlocUpdater::prepareNvm0AUpdate: SD card 1 not mounted" << std::endl;
|
sif::warning << "PlocUpdater::getImageLocation: SD card 1 not mounted" << std::endl;
|
||||||
return SD_NOT_MOUNTED;
|
return SD_NOT_MOUNTED;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
// update image not stored on SD card
|
||||||
//update image not stored on SD card
|
|
||||||
}
|
}
|
||||||
#endif /* BOARD_TE0720 == 0 */
|
#endif /* BOARD_TE0720 == 0 */
|
||||||
|
|
||||||
updateFile = std::string(reinterpret_cast<const char*>(data), size);
|
updateFile = std::string(reinterpret_cast<const char*>(data), size);
|
||||||
|
|
||||||
// Check if file exists
|
// Check if file exists
|
||||||
if(not std::filesystem::exists(updateFile)) {
|
if (not std::filesystem::exists(updateFile)) {
|
||||||
return FILE_NOT_EXISTS;
|
return FILE_NOT_EXISTS;
|
||||||
}
|
}
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if BOARD_TE0720 == 0
|
void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {}
|
||||||
bool PlocUpdater::isSdCardMounted(sd::SdCard sdCard) {
|
|
||||||
SdCardManager::SdStatePair active;
|
|
||||||
ReturnValue_t result = sdcMan->getSdCardActiveStatus(active);
|
|
||||||
if (result != RETURN_OK) {
|
|
||||||
sif::debug << "PlocUpdater::isSdCardMounted: Failed to get SD card active state";
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (sdCard == sd::SLOT_0) {
|
|
||||||
if (active.first == sd::MOUNTED) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if (sdCard == sd::SLOT_1) {
|
|
||||||
if (active.second == sd::MOUNTED) {
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
sif::debug << "PlocUpdater::isSdCardMounted: Unknown SD card specified" << std::endl;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
#endif /* #if BOARD_TE0720 == 0 */
|
|
||||||
|
|
||||||
void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId,
|
void PlocUpdater::stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) {}
|
||||||
uint8_t step) {
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocUpdater::stepFailedReceived(ActionId_t actionId, uint8_t step,
|
void PlocUpdater::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {}
|
||||||
ReturnValue_t returnCode) {
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocUpdater::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) {
|
void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) {
|
||||||
switch (pendingCommand) {
|
switch (pendingCommand) {
|
||||||
@ -245,8 +204,7 @@ void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) {
|
|||||||
if (remainingPackets == 0) {
|
if (remainingPackets == 0) {
|
||||||
packetsSent = 0; // Reset packets sent variable for next update sequence
|
packetsSent = 0; // Reset packets sent variable for next update sequence
|
||||||
state = State::UPDATE_VERIFY;
|
state = State::UPDATE_VERIFY;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
state = State::UPDATE_TRANSFER;
|
state = State::UPDATE_TRANSFER;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -263,24 +221,22 @@ void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void PlocUpdater::completionFailedReceived(ActionId_t actionId,
|
void PlocUpdater::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) {
|
||||||
ReturnValue_t returnCode) {
|
switch (pendingCommand) {
|
||||||
switch(pendingCommand) {
|
case (PLOC_SPV::UPDATE_AVAILABLE): {
|
||||||
case(PLOC_SPV::UPDATE_AVAILABLE): {
|
|
||||||
triggerEvent(UPDATE_AVAILABLE_FAILED);
|
triggerEvent(UPDATE_AVAILABLE_FAILED);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::UPDATE_IMAGE_DATA): {
|
case (PLOC_SPV::UPDATE_IMAGE_DATA): {
|
||||||
triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent);
|
triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(PLOC_SPV::UPDATE_VERIFY): {
|
case (PLOC_SPV::UPDATE_VERIFY): {
|
||||||
triggerEvent(UPDATE_VERIFY_FAILED);
|
triggerEvent(UPDATE_VERIFY_FAILED);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
sif::debug << "PlocUpdater::completionFailedReceived: Invalid pending command "
|
sif::debug << "PlocUpdater::completionFailedReceived: Invalid pending command " << std::endl;
|
||||||
<< std::endl;
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
state = State::IDLE;
|
state = State::IDLE;
|
||||||
@ -300,7 +256,7 @@ void PlocUpdater::commandUpdateAvailable() {
|
|||||||
imageSize = static_cast<size_t>(file.tellg());
|
imageSize = static_cast<size_t>(file.tellg());
|
||||||
file.close();
|
file.close();
|
||||||
|
|
||||||
numOfUpdatePackets = imageSize / MAX_SP_DATA ;
|
numOfUpdatePackets = imageSize / MAX_SP_DATA;
|
||||||
if (imageSize % MAX_SP_DATA) {
|
if (imageSize % MAX_SP_DATA) {
|
||||||
numOfUpdatePackets++;
|
numOfUpdatePackets++;
|
||||||
}
|
}
|
||||||
@ -311,10 +267,12 @@ void PlocUpdater::commandUpdateAvailable() {
|
|||||||
calcImageCrc();
|
calcImageCrc();
|
||||||
|
|
||||||
PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_AVAILABLE, static_cast<uint8_t>(image),
|
PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_AVAILABLE, static_cast<uint8_t>(image),
|
||||||
static_cast<uint8_t>(partition), imageSize, imageCrc, numOfUpdatePackets);
|
static_cast<uint8_t>(partition), imageSize, imageCrc,
|
||||||
|
numOfUpdatePackets);
|
||||||
|
|
||||||
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
||||||
PLOC_SPV::UPDATE_AVAILABLE, packet.getWholeData(), packet.getFullSize());
|
PLOC_SPV::UPDATE_AVAILABLE, packet.getWholeData(),
|
||||||
|
packet.getFullSize());
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
|
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
|
||||||
<< " packet to supervisor handler" << std::endl;
|
<< " packet to supervisor handler" << std::endl;
|
||||||
@ -344,8 +302,7 @@ void PlocUpdater::commandUpdatePacket() {
|
|||||||
|
|
||||||
if (remainingPackets == 1) {
|
if (remainingPackets == 1) {
|
||||||
payloadLength = imageSize - static_cast<uint16_t>(file.tellg());
|
payloadLength = imageSize - static_cast<uint16_t>(file.tellg());
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
payloadLength = MAX_SP_DATA;
|
payloadLength = MAX_SP_DATA;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -360,7 +317,8 @@ void PlocUpdater::commandUpdatePacket() {
|
|||||||
packet.makeCrc();
|
packet.makeCrc();
|
||||||
|
|
||||||
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
||||||
PLOC_SPV::UPDATE_IMAGE_DATA, packet.getWholeData(), packet.getFullSize());
|
PLOC_SPV::UPDATE_IMAGE_DATA, packet.getWholeData(),
|
||||||
|
packet.getFullSize());
|
||||||
|
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update"
|
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update"
|
||||||
@ -382,10 +340,12 @@ void PlocUpdater::commandUpdateVerify() {
|
|||||||
ReturnValue_t result = RETURN_OK;
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
|
||||||
PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_VERIFY, static_cast<uint8_t>(image),
|
PLOC_SPV::UpdateInfo packet(PLOC_SPV::APID_UPDATE_VERIFY, static_cast<uint8_t>(image),
|
||||||
static_cast<uint8_t>(partition), imageSize, imageCrc, numOfUpdatePackets);
|
static_cast<uint8_t>(partition), imageSize, imageCrc,
|
||||||
|
numOfUpdatePackets);
|
||||||
|
|
||||||
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER,
|
result =
|
||||||
PLOC_SPV::UPDATE_VERIFY, packet.getWholeData(), packet.getFullSize());
|
commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, PLOC_SPV::UPDATE_VERIFY,
|
||||||
|
packet.getWholeData(), packet.getFullSize());
|
||||||
if (result != RETURN_OK) {
|
if (result != RETURN_OK) {
|
||||||
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
|
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
|
||||||
<< " packet to supervisor handler" << std::endl;
|
<< " packet to supervisor handler" << std::endl;
|
||||||
@ -425,12 +385,9 @@ void PlocUpdater::calcImageCrc() {
|
|||||||
void PlocUpdater::adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet) {
|
void PlocUpdater::adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet) {
|
||||||
if (packetsSent == 0) {
|
if (packetsSent == 0) {
|
||||||
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::FIRST_PKT));
|
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::FIRST_PKT));
|
||||||
}
|
} else if (remainingPackets == 1) {
|
||||||
else if (remainingPackets == 1) {
|
|
||||||
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::LAST_PKT));
|
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::LAST_PKT));
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::CONTINUED_PKT));
|
packet.setSequenceFlags(static_cast<uint8_t>(PLOC_SPV::SequenceFlags::CONTINUED_PKT));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2,27 +2,25 @@
|
|||||||
#define MISSION_DEVICES_PLOCUPDATER_H_
|
#define MISSION_DEVICES_PLOCUPDATER_H_
|
||||||
|
|
||||||
#include "OBSWConfig.h"
|
#include "OBSWConfig.h"
|
||||||
|
#include "bsp_q7s/memory/SdCardManager.h"
|
||||||
#include "devicedefinitions/PlocSupervisorDefinitions.h"
|
#include "devicedefinitions/PlocSupervisorDefinitions.h"
|
||||||
|
|
||||||
#include "fsfw/action/CommandActionHelper.h"
|
|
||||||
#include "fsfw/action/ActionHelper.h"
|
#include "fsfw/action/ActionHelper.h"
|
||||||
#include "fsfw/action/HasActionsIF.h"
|
#include "fsfw/action/CommandActionHelper.h"
|
||||||
#include "fsfw/action/CommandsActionsIF.h"
|
#include "fsfw/action/CommandsActionsIF.h"
|
||||||
|
#include "fsfw/action/HasActionsIF.h"
|
||||||
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
#include "fsfw/tasks/ExecutableObjectIF.h"
|
#include "fsfw/tasks/ExecutableObjectIF.h"
|
||||||
#include "fsfw/objectmanager/SystemObject.h"
|
|
||||||
#include "bsp_q7s/memory/SdCardManager.h"
|
|
||||||
#include "linux/fsfwconfig/objects/systemObjectList.h"
|
|
||||||
#include "fsfw/tmtcpacket/SpacePacket.h"
|
#include "fsfw/tmtcpacket/SpacePacket.h"
|
||||||
|
#include "linux/fsfwconfig/objects/systemObjectList.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief An object of this class can be used to perform the software updates of the PLOC. The
|
* @brief An object of this class can be used to perform the software updates of the PLOC. The
|
||||||
* software update will be read from one of the SD cards, split into multiple space
|
* software update will be read from one of the SD cards, split into multiple space
|
||||||
* packets and sent to the PlocSupervisorHandler.
|
* packets and sent to the PlocSupervisorHandler.
|
||||||
*
|
*
|
||||||
* @details The MPSoC has two boot memories (NVM0 and NVM1) where each stores two images (Partition A
|
* @details The MPSoC has two boot memories (NVM0 and NVM1) where each stores two images (Partition
|
||||||
* and Partition B)
|
* A and Partition B)
|
||||||
*
|
*
|
||||||
* @author J. Meier
|
* @author J. Meier
|
||||||
*/
|
*/
|
||||||
@ -31,8 +29,7 @@ class PlocUpdater : public SystemObject,
|
|||||||
public ExecutableObjectIF,
|
public ExecutableObjectIF,
|
||||||
public HasReturnvaluesIF,
|
public HasReturnvaluesIF,
|
||||||
public CommandsActionsIF {
|
public CommandsActionsIF {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
static const ActionId_t UPDATE_A_UBOOT = 0;
|
static const ActionId_t UPDATE_A_UBOOT = 0;
|
||||||
static const ActionId_t UPDATE_A_BITSTREAM = 1;
|
static const ActionId_t UPDATE_A_BITSTREAM = 1;
|
||||||
static const ActionId_t UPDATE_A_LINUX = 2;
|
static const ActionId_t UPDATE_A_LINUX = 2;
|
||||||
@ -57,15 +54,15 @@ public:
|
|||||||
void completionSuccessfulReceived(ActionId_t actionId) override;
|
void completionSuccessfulReceived(ActionId_t actionId) override;
|
||||||
void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override;
|
void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_UPDATER;
|
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_UPDATER;
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Updater is already performing an update
|
//! [EXPORT] : [COMMENT] Updater is already performing an update
|
||||||
static const ReturnValue_t UPDATER_BUSY = MAKE_RETURN_CODE(0xA0);
|
static const ReturnValue_t UPDATER_BUSY = MAKE_RETURN_CODE(0xA0);
|
||||||
//! [EXPORT] : [COMMENT] Received update command with invalid path string (too long).
|
//! [EXPORT] : [COMMENT] Received update command with invalid path string (too long).
|
||||||
static const ReturnValue_t NAME_TOO_LONG = MAKE_RETURN_CODE(0xA1);
|
static const ReturnValue_t NAME_TOO_LONG = MAKE_RETURN_CODE(0xA1);
|
||||||
//! [EXPORT] : [COMMENT] Received command to initiate update but SD card with update image not mounted.
|
//! [EXPORT] : [COMMENT] Received command to initiate update but SD card with update image not
|
||||||
|
//! mounted.
|
||||||
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA2);
|
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA2);
|
||||||
//! [EXPORT] : [COMMENT] Update file received with update command does not exist.
|
//! [EXPORT] : [COMMENT] Update file received with update command does not exist.
|
||||||
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA3);
|
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA3);
|
||||||
@ -74,13 +71,15 @@ private:
|
|||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Try to read update file but the file does not exist.
|
//! [EXPORT] : [COMMENT] Try to read update file but the file does not exist.
|
||||||
//! P1: Indicates in which state the file read fails
|
//! P1: Indicates in which state the file read fails
|
||||||
//! P2: During the update transfer the second parameter gives information about the number of already sent packets
|
//! P2: During the update transfer the second parameter gives information about the number of
|
||||||
|
//! already sent packets
|
||||||
static const Event UPDATE_FILE_NOT_EXISTS = MAKE_EVENT(0, severity::LOW);
|
static const Event UPDATE_FILE_NOT_EXISTS = MAKE_EVENT(0, severity::LOW);
|
||||||
//! [EXPORT] : [COMMENT] Failed to send command to supervisor handler
|
//! [EXPORT] : [COMMENT] Failed to send command to supervisor handler
|
||||||
//! P1: Return value of CommandActionHelper::commandAction
|
//! P1: Return value of CommandActionHelper::commandAction
|
||||||
//! P2: Action ID of command to send
|
//! P2: Action ID of command to send
|
||||||
static const Event ACTION_COMMANDING_FAILED = MAKE_EVENT(1, severity::LOW);
|
static const Event ACTION_COMMANDING_FAILED = MAKE_EVENT(1, severity::LOW);
|
||||||
//! [EXPORT] : [COMMENT] Supervisor handler replied action message indicating a command execution failure of the update available command
|
//! [EXPORT] : [COMMENT] Supervisor handler replied action message indicating a command execution
|
||||||
|
//! failure of the update available command
|
||||||
static const Event UPDATE_AVAILABLE_FAILED = MAKE_EVENT(2, severity::LOW);
|
static const Event UPDATE_AVAILABLE_FAILED = MAKE_EVENT(2, severity::LOW);
|
||||||
//! [EXPORT] : [COMMENT] Supervisor handler failed to transfer an update space packet.
|
//! [EXPORT] : [COMMENT] Supervisor handler failed to transfer an update space packet.
|
||||||
//! P1: Parameter holds the number of update packets already sent (inclusive the failed packet)
|
//! P1: Parameter holds the number of update packets already sent (inclusive the failed packet)
|
||||||
@ -110,7 +109,7 @@ private:
|
|||||||
|
|
||||||
ActionHelper actionHelper;
|
ActionHelper actionHelper;
|
||||||
|
|
||||||
enum class State: uint8_t {
|
enum class State : uint8_t {
|
||||||
IDLE,
|
IDLE,
|
||||||
UPDATE_AVAILABLE,
|
UPDATE_AVAILABLE,
|
||||||
UPDATE_TRANSFER,
|
UPDATE_TRANSFER,
|
||||||
@ -122,21 +121,11 @@ private:
|
|||||||
|
|
||||||
ActionId_t pendingCommand = PLOC_SPV::NONE;
|
ActionId_t pendingCommand = PLOC_SPV::NONE;
|
||||||
|
|
||||||
enum class Image: uint8_t {
|
enum class Image : uint8_t { NONE, A, B };
|
||||||
NONE,
|
|
||||||
A,
|
|
||||||
B
|
|
||||||
};
|
|
||||||
|
|
||||||
Image image = Image::NONE;
|
Image image = Image::NONE;
|
||||||
|
|
||||||
enum class Partition: uint8_t {
|
enum class Partition : uint8_t { NONE, UBOOT, BITSTREAM, LINUX_OS, APP_SW };
|
||||||
NONE,
|
|
||||||
UBOOT,
|
|
||||||
BITSTREAM,
|
|
||||||
LINUX_OS,
|
|
||||||
APP_SW
|
|
||||||
};
|
|
||||||
|
|
||||||
Partition partition = Partition::NONE;
|
Partition partition = Partition::NONE;
|
||||||
|
|
||||||
@ -174,13 +163,6 @@ private:
|
|||||||
*/
|
*/
|
||||||
void commandUpdateVerify();
|
void commandUpdateVerify();
|
||||||
|
|
||||||
#if BOARD_TE0720 == 0
|
|
||||||
/**
|
|
||||||
* @brief Checks whether the SD card to read from is mounted or not.
|
|
||||||
*/
|
|
||||||
bool isSdCardMounted(sd::SdCard sdCard);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void calcImageCrc();
|
void calcImageCrc();
|
||||||
|
|
||||||
void adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet);
|
void adjustSequenceFlags(PLOC_SPV::UpdatePacket& packet);
|
||||||
|
@ -3,20 +3,19 @@
|
|||||||
|
|
||||||
#include <fsfw/src/fsfw/serialize/SerialLinkedListAdapter.h>
|
#include <fsfw/src/fsfw/serialize/SerialLinkedListAdapter.h>
|
||||||
|
|
||||||
class MemoryParams: public SerialLinkedListAdapter<SerializeIF> {
|
class MemoryParams : public SerialLinkedListAdapter<SerializeIF> {
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Constructor
|
* @brief Constructor
|
||||||
* @param startAddress Start of address range to dump
|
* @param startAddress Start of address range to dump
|
||||||
* @param endAddress End of address range to dump
|
* @param endAddress End of address range to dump
|
||||||
*/
|
*/
|
||||||
MemoryParams(uint32_t startAddress, uint32_t endAddress) :
|
MemoryParams(uint32_t startAddress, uint32_t endAddress)
|
||||||
startAddress(startAddress), endAddress(endAddress) {
|
: startAddress(startAddress), endAddress(endAddress) {
|
||||||
setLinks();
|
setLinks();
|
||||||
}
|
}
|
||||||
private:
|
|
||||||
|
|
||||||
|
private:
|
||||||
void setLinks() {
|
void setLinks() {
|
||||||
setStart(&startAddress);
|
setStart(&startAddress);
|
||||||
startAddress.setNext(&endAddress);
|
startAddress.setNext(&endAddress);
|
||||||
@ -24,10 +23,6 @@ private:
|
|||||||
|
|
||||||
SerializeElement<uint32_t> startAddress;
|
SerializeElement<uint32_t> startAddress;
|
||||||
SerializeElement<uint32_t> endAddress;
|
SerializeElement<uint32_t> endAddress;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_PLOCMEMDUMPDEFINITIONS_H_ */
|
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_PLOCMEMDUMPDEFINITIONS_H_ */
|
||||||
|
File diff suppressed because it is too large
Load Diff
62
bsp_q7s/devices/startracker/ArcsecDatalinkLayer.cpp
Normal file
62
bsp_q7s/devices/startracker/ArcsecDatalinkLayer.cpp
Normal file
@ -0,0 +1,62 @@
|
|||||||
|
#include "ArcsecDatalinkLayer.h"
|
||||||
|
|
||||||
|
ArcsecDatalinkLayer::ArcsecDatalinkLayer() { slipInit(); }
|
||||||
|
|
||||||
|
ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {}
|
||||||
|
|
||||||
|
void ArcsecDatalinkLayer::slipInit() {
|
||||||
|
slipInfo.buffer = rxBuffer;
|
||||||
|
slipInfo.maxlength = StarTracker::MAX_FRAME_SIZE;
|
||||||
|
slipInfo.length = 0;
|
||||||
|
slipInfo.unescape_next = 0;
|
||||||
|
slipInfo.prev_state = SLIP_COMPLETE;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t rawDataSize,
|
||||||
|
size_t* bytesLeft) {
|
||||||
|
size_t bytePos = 0;
|
||||||
|
for (bytePos = 0; bytePos < rawDataSize; bytePos++) {
|
||||||
|
enum arc_dec_result decResult =
|
||||||
|
arc_transport_decode_body(*(rawData + bytePos), &slipInfo, decodedFrame, &decFrameSize);
|
||||||
|
*bytesLeft = rawDataSize - bytePos - 1;
|
||||||
|
switch (decResult) {
|
||||||
|
case ARC_DEC_INPROGRESS: {
|
||||||
|
if (bytePos == rawDataSize - 1) {
|
||||||
|
return DEC_IN_PROGRESS;
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
case ARC_DEC_ERROR_FRAME_SHORT:
|
||||||
|
return REPLY_TOO_SHORT;
|
||||||
|
case ARC_DEC_ERROR_CHECKSUM:
|
||||||
|
return CRC_FAILURE;
|
||||||
|
case ARC_DEC_ASYNC:
|
||||||
|
case ARC_DEC_SYNC: {
|
||||||
|
// Reset length of SLIP struct for next frame
|
||||||
|
slipInfo.length = 0;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
sif::debug << "ArcsecDatalinkLayer::decodeFrame: Unknown result code" << std::endl;
|
||||||
|
break;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t ArcsecDatalinkLayer::getReplyFrameType() { return decodedFrame[0]; }
|
||||||
|
|
||||||
|
const uint8_t* ArcsecDatalinkLayer::getReply() { return &decodedFrame[1]; }
|
||||||
|
|
||||||
|
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, uint32_t length) {
|
||||||
|
arc_transport_encode_body(data, length, encBuffer, &encFrameSize);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t* ArcsecDatalinkLayer::getEncodedFrame() { return encBuffer; }
|
||||||
|
|
||||||
|
uint32_t ArcsecDatalinkLayer::getEncodedLength() { return encFrameSize; }
|
||||||
|
|
||||||
|
uint8_t ArcsecDatalinkLayer::getStatusField() { return *(decodedFrame + STATUS_OFFSET); }
|
||||||
|
|
||||||
|
uint8_t ArcsecDatalinkLayer::getId() { return *(decodedFrame + ID_OFFSET); }
|
98
bsp_q7s/devices/startracker/ArcsecDatalinkLayer.h
Normal file
98
bsp_q7s/devices/startracker/ArcsecDatalinkLayer.h
Normal file
@ -0,0 +1,98 @@
|
|||||||
|
#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||||
|
#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||||
|
|
||||||
|
#include "StarTrackerDefinitions.h"
|
||||||
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "common/misc.h"
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec.
|
||||||
|
*/
|
||||||
|
class ArcsecDatalinkLayer : public HasReturnvaluesIF {
|
||||||
|
public:
|
||||||
|
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER;
|
||||||
|
|
||||||
|
//! [EXPORT] : [COMMENT] More data required to complete frame
|
||||||
|
static const ReturnValue_t DEC_IN_PROGRESS = MAKE_RETURN_CODE(0xA0);
|
||||||
|
//! [EXPORT] : [COMMENT] Data too short to represent a valid frame
|
||||||
|
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xA1);
|
||||||
|
//! [EXPORT] : [COMMENT] Detected CRC failure in received frame
|
||||||
|
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA2);
|
||||||
|
|
||||||
|
static const uint8_t STATUS_OK = 0;
|
||||||
|
|
||||||
|
ArcsecDatalinkLayer();
|
||||||
|
virtual ~ArcsecDatalinkLayer();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Applies decoding to data referenced by rawData pointer
|
||||||
|
*
|
||||||
|
* @param rawData Pointer to raw data received from star tracker
|
||||||
|
* @param rawDataSize Size of raw data stream
|
||||||
|
* @param remainingBytes Number of bytes left
|
||||||
|
*/
|
||||||
|
ReturnValue_t decodeFrame(const uint8_t* rawData, size_t rawDataSize, size_t* bytesLeft);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief SLIP encodes data pointed to by data pointer.
|
||||||
|
*
|
||||||
|
* @param data Pointer to data to encode
|
||||||
|
* @param length Length of buffer to encode
|
||||||
|
*/
|
||||||
|
void encodeFrame(const uint8_t* data, uint32_t length);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns the frame type field of a decoded frame.
|
||||||
|
*/
|
||||||
|
uint8_t getReplyFrameType();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns pointer to reply packet (first entry normally action ID, telemetry ID etc.)
|
||||||
|
*/
|
||||||
|
const uint8_t* getReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns size of encoded frame
|
||||||
|
*/
|
||||||
|
uint32_t getEncodedLength();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns pointer to encoded frame
|
||||||
|
*/
|
||||||
|
uint8_t* getEncodedFrame();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns status of reply
|
||||||
|
*/
|
||||||
|
uint8_t getStatusField();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns ID of reply
|
||||||
|
*/
|
||||||
|
uint8_t getId();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const uint8_t ID_OFFSET = 1;
|
||||||
|
static const uint8_t STATUS_OFFSET = 2;
|
||||||
|
|
||||||
|
// Used by arcsec slip decoding function process received data
|
||||||
|
uint8_t rxBuffer[StarTracker::MAX_FRAME_SIZE];
|
||||||
|
// Decoded frame will be copied to this buffer
|
||||||
|
uint8_t decodedFrame[StarTracker::MAX_FRAME_SIZE];
|
||||||
|
// Buffer where encoded frames will be stored. First byte of encoded frame represents type of
|
||||||
|
// reply
|
||||||
|
uint8_t encBuffer[StarTracker::MAX_FRAME_SIZE * 2 + 2];
|
||||||
|
// Size of decoded frame
|
||||||
|
uint32_t decFrameSize = 0;
|
||||||
|
// Size of encoded frame
|
||||||
|
uint32_t encFrameSize = 0;
|
||||||
|
|
||||||
|
slip_decode_state slipInfo;
|
||||||
|
|
||||||
|
void slipInit();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ */
|
126
bsp_q7s/devices/startracker/ArcsecJsonKeys.h
Normal file
126
bsp_q7s/devices/startracker/ArcsecJsonKeys.h
Normal file
@ -0,0 +1,126 @@
|
|||||||
|
#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
|
||||||
|
#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Keys used in JSON file of ARCSEC.
|
||||||
|
*/
|
||||||
|
namespace arcseckeys {
|
||||||
|
static const char PROPERTIES[] = "properties";
|
||||||
|
static const char NAME[] = "name";
|
||||||
|
static const char VALUE[] = "value";
|
||||||
|
|
||||||
|
static const char LIMITS[] = "limits";
|
||||||
|
static const char ACTION[] = "action";
|
||||||
|
static const char FPGA18CURRENT[] = "FPGA18Current";
|
||||||
|
static const char FPGA25CURRENT[] = "FPGA25Current";
|
||||||
|
static const char FPGA10CURRENT[] = "FPGA10Current";
|
||||||
|
static const char MCUCURRENT[] = "MCUCurrent";
|
||||||
|
static const char CMOS21CURRENT[] = "CMOS21Current";
|
||||||
|
static const char CMOSPIXCURRENT[] = "CMOSPixCurrent";
|
||||||
|
static const char CMOS33CURRENT[] = "CMOS33Current";
|
||||||
|
static const char CMOSVRESCURRENT[] = "CMOSVResCurrent";
|
||||||
|
static const char CMOS_TEMPERATURE[] = "CMOSTemperature";
|
||||||
|
static const char MCU_TEMPERATURE[] = "MCUTemperature";
|
||||||
|
|
||||||
|
static const char MOUNTING[] = "mounting";
|
||||||
|
static const char qw[] = "qw";
|
||||||
|
static const char qx[] = "qx";
|
||||||
|
static const char qy[] = "qy";
|
||||||
|
static const char qz[] = "qz";
|
||||||
|
|
||||||
|
static const char CAMERA[] = "camera";
|
||||||
|
static const char MODE[] = "mode";
|
||||||
|
static const char FOCALLENGTH[] = "focallength";
|
||||||
|
static const char EXPOSURE[] = "exposure";
|
||||||
|
static const char INTERVAL[] = "interval";
|
||||||
|
static const char OFFSET[] = "offset";
|
||||||
|
static const char PGAGAIN[] = "PGAGain";
|
||||||
|
static const char ADCGAIN[] = "ADCGain";
|
||||||
|
static const char REG_1[] = "reg1";
|
||||||
|
static const char VAL_1[] = "val1";
|
||||||
|
static const char REG_2[] = "reg2";
|
||||||
|
static const char VAL_2[] = "val2";
|
||||||
|
static const char REG_3[] = "reg3";
|
||||||
|
static const char VAL_3[] = "val3";
|
||||||
|
static const char REG_4[] = "reg4";
|
||||||
|
static const char VAL_4[] = "val4";
|
||||||
|
static const char REG_5[] = "reg5";
|
||||||
|
static const char VAL_5[] = "val5";
|
||||||
|
static const char REG_6[] = "reg6";
|
||||||
|
static const char VAL_6[] = "val6";
|
||||||
|
static const char REG_7[] = "reg7";
|
||||||
|
static const char VAL_7[] = "val7";
|
||||||
|
static const char REG_8[] = "reg8";
|
||||||
|
static const char VAL_8[] = "val8";
|
||||||
|
static const char FREQ_1[] = "freq1";
|
||||||
|
static const char FREQ_2[] = "freq2";
|
||||||
|
|
||||||
|
static const char BLOB[] = "blob";
|
||||||
|
static const char MIN_VALUE[] = "minValue";
|
||||||
|
static const char MIN_DISTANCE[] = "minDistance";
|
||||||
|
static const char NEIGHBOUR_DISTANCE[] = "neighbourDistance";
|
||||||
|
static const char NEIGHBOUR_BRIGHT_PIXELS[] = "neighbourBrightPixels";
|
||||||
|
static const char MIN_TOTAL_VALUE[] = "minTotalValue";
|
||||||
|
static const char MAX_TOTAL_VALUE[] = "maxTotalValue";
|
||||||
|
static const char MIN_BRIGHT_NEIGHBOURS[] = "minBrightNeighbours";
|
||||||
|
static const char MAX_BRIGHT_NEIGHBOURS[] = "maxBrightNeighbours";
|
||||||
|
static const char MAX_PIXEL_TO_CONSIDER[] = "maxPixelsToConsider";
|
||||||
|
static const char SIGNAL_THRESHOLD[] = "signalThreshold";
|
||||||
|
static const char DARK_THRESHOLD[] = "darkThreshold";
|
||||||
|
static const char ENABLE_HISTOGRAM[] = "enableHistogram";
|
||||||
|
static const char ENABLE_CONTRAST[] = "enableContrast";
|
||||||
|
static const char BIN_MODE[] = "binMode";
|
||||||
|
|
||||||
|
static const char CENTROIDING[] = "centroiding";
|
||||||
|
static const char ENABLE_FILTER[] = "enableFilter";
|
||||||
|
static const char MAX_QUALITY[] = "maxquality";
|
||||||
|
static const char MIN_QUALITY[] = "minquality";
|
||||||
|
static const char MAX_INTENSITY[] = "maxintensity";
|
||||||
|
static const char MIN_INTENSITY[] = "minintensity";
|
||||||
|
static const char MAX_MAGNITUDE[] = "maxmagnitude";
|
||||||
|
static const char GAUSSIAN_CMAX[] = "gaussianCmax";
|
||||||
|
static const char GAUSSIAN_CMIN[] = "gaussianCmin";
|
||||||
|
static const char TRANSMATRIX_00[] = "transmatrix00";
|
||||||
|
static const char TRANSMATRIX_01[] = "transmatrix01";
|
||||||
|
static const char TRANSMATRIX_10[] = "transmatrix10";
|
||||||
|
static const char TRANSMATRIX_11[] = "transmatrix11";
|
||||||
|
|
||||||
|
static const char LISA[] = "lisa";
|
||||||
|
static const char PREFILTER_DIST_THRESHOLD[] = "prefilterDistThreshold";
|
||||||
|
static const char PREFILTER_ANGLE_THRESHOLD[] = "prefilterAngleThreshold";
|
||||||
|
static const char FOV_WIDTH[] = "fov_width";
|
||||||
|
static const char FOV_HEIGHT[] = "fov_height";
|
||||||
|
static const char FLOAT_STAR_LIMIT[] = "float_star_limit";
|
||||||
|
static const char CLOSE_STAR_LIMIT[] = "close_star_limit";
|
||||||
|
static const char RATING_WEIGHT_CLOSE_STAR_COUNT[] = "rating_weight_close_star_count";
|
||||||
|
static const char RATING_WEIGHT_FRACTION_CLOSE[] = "rating_weight_fraction_close";
|
||||||
|
static const char RATING_WEIGHT_MEAN_SUM[] = "rating_weight_mean_sum";
|
||||||
|
static const char RATING_WEIGHT_DB_STAR_COUNT[] = "rating_weight_db_star_count";
|
||||||
|
static const char MAX_COMBINATIONS[] = "max_combinations";
|
||||||
|
static const char NR_STARS_STOP[] = "nr_stars_stop";
|
||||||
|
static const char FRACTION_CLOSE_STOP[] = "fraction_close_stop";
|
||||||
|
|
||||||
|
static const char MATCHING[] = "matching";
|
||||||
|
static const char SQUARED_DISTANCE_LIMIT[] = "squaredDistanceLimit";
|
||||||
|
static const char SQUARED_SHIFT_LIMIT[] = "squaredShiftLimit";
|
||||||
|
|
||||||
|
static const char VALIDATION[] = "validation";
|
||||||
|
static const char STABLE_COUNT[] = "stable_count";
|
||||||
|
static const char MAX_DIFFERENCE[] = "max_difference";
|
||||||
|
static const char MIN_TRACKER_CONFIDENCE[] = "min_trackerConfidence";
|
||||||
|
static const char MIN_MATCHED_STARS[] = "min_matchedStars";
|
||||||
|
|
||||||
|
static const char TRACKING[] = "tracking";
|
||||||
|
static const char THIN_LIMIT[] = "thinLimit";
|
||||||
|
static const char OUTLIER_THRESHOLD[] = "outlierThreshold";
|
||||||
|
static const char OUTLIER_THRESHOLD_QUEST[] = "outlierThresholdQUEST";
|
||||||
|
static const char TRACKER_CHOICE[] = "trackerChoice";
|
||||||
|
|
||||||
|
static const char ALGO[] = "algo";
|
||||||
|
static const char L2T_MIN_CONFIDENCE[] = "l2t_minConfidence";
|
||||||
|
static const char L2T_MIN_MATCHED[] = "l2t_minConfidence";
|
||||||
|
static const char T2L_MIN_CONFIDENCE[] = "t2l_minConfidence";
|
||||||
|
static const char T2L_MIN_MATCHED[] = "t2l_minMatched";
|
||||||
|
} // namespace arcseckeys
|
||||||
|
|
||||||
|
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_ARCSECJSONKEYS_H_ */
|
95
bsp_q7s/devices/startracker/ArcsecJsonParamBase.cpp
Normal file
95
bsp_q7s/devices/startracker/ArcsecJsonParamBase.cpp
Normal file
@ -0,0 +1,95 @@
|
|||||||
|
#include "ArcsecJsonParamBase.h"
|
||||||
|
|
||||||
|
#include "ArcsecJsonKeys.h"
|
||||||
|
|
||||||
|
ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {}
|
||||||
|
|
||||||
|
ReturnValue_t ArcsecJsonParamBase::create(std::string fullname, uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
result = init(fullname);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = createCommand(buffer);
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ArcsecJsonParamBase::getParam(const std::string name, std::string& value) {
|
||||||
|
for (json::iterator it = set.begin(); it != set.end(); ++it) {
|
||||||
|
if ((*it)[arcseckeys::NAME] == name) {
|
||||||
|
value = (*it)[arcseckeys::VALUE];
|
||||||
|
convertEmpty(value);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return PARAM_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::convertEmpty(std::string& value) {
|
||||||
|
if (value == "") {
|
||||||
|
value = "0";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::addfloat(const std::string value, uint8_t* buffer) {
|
||||||
|
float param = std::stof(value);
|
||||||
|
std::memcpy(buffer, ¶m, sizeof(param));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::adduint8(const std::string value, uint8_t* buffer) {
|
||||||
|
uint8_t param = std::stoi(value);
|
||||||
|
std::memcpy(buffer, ¶m, sizeof(param));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::addint16(const std::string value, uint8_t* buffer) {
|
||||||
|
int16_t param = std::stoi(value);
|
||||||
|
std::memcpy(buffer, ¶m, sizeof(param));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::adduint16(const std::string value, uint8_t* buffer) {
|
||||||
|
uint16_t param = std::stoi(value);
|
||||||
|
std::memcpy(buffer, ¶m, sizeof(param));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::adduint32(const std::string value, uint8_t* buffer) {
|
||||||
|
uint32_t param = std::stoi(value);
|
||||||
|
std::memcpy(buffer, ¶m, sizeof(param));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::addSetParamHeader(uint8_t* buffer, uint8_t setId) {
|
||||||
|
*buffer = static_cast<uint8_t>(TMTC_SETPARAMREQ);
|
||||||
|
*(buffer + 1) = setId;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ArcsecJsonParamBase::init(const std::string filename) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
if (not std::filesystem::exists(filename)) {
|
||||||
|
sif::warning << "ArcsecJsonParamBase::init: JSON file " << filename << " does not exist"
|
||||||
|
<< std::endl;
|
||||||
|
return JSON_FILE_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
createJsonObject(filename);
|
||||||
|
result = initSet();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ArcsecJsonParamBase::createJsonObject(const std::string fullname) {
|
||||||
|
json j;
|
||||||
|
std::ifstream file(fullname);
|
||||||
|
file >> j;
|
||||||
|
file.close();
|
||||||
|
properties = j[arcseckeys::PROPERTIES];
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t ArcsecJsonParamBase::initSet() {
|
||||||
|
for (json::iterator it = properties.begin(); it != properties.end(); ++it) {
|
||||||
|
if ((*it)["name"] == setName) {
|
||||||
|
set = (*it)["fields"];
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return SET_NOT_EXISTS;
|
||||||
|
}
|
146
bsp_q7s/devices/startracker/ArcsecJsonParamBase.h
Normal file
146
bsp_q7s/devices/startracker/ArcsecJsonParamBase.h
Normal file
@ -0,0 +1,146 @@
|
|||||||
|
#ifndef BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
|
||||||
|
#define BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_
|
||||||
|
|
||||||
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
|
#include <nlohmann/json.hpp>
|
||||||
|
|
||||||
|
#include "StarTrackerDefinitions.h"
|
||||||
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
|
||||||
|
#include "thirdparty/arcsec_star_tracker/common/genericstructs.h"
|
||||||
|
}
|
||||||
|
|
||||||
|
using json = nlohmann::json;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Base class for creation of parameter configuration commands. Reads parameter set
|
||||||
|
* from a json file located on the filesystem and generates the appropriate command
|
||||||
|
* to apply the parameters to the star tracker software.
|
||||||
|
*
|
||||||
|
* @author J. Meier
|
||||||
|
*/
|
||||||
|
class ArcsecJsonParamBase : public HasReturnvaluesIF {
|
||||||
|
public:
|
||||||
|
static const uint8_t INTERFACE_ID = CLASS_ID::ARCSEC_JSON_BASE;
|
||||||
|
//! [EXPORT] : [COMMENT] Specified json file does not exist
|
||||||
|
static const ReturnValue_t JSON_FILE_NOT_EXISTS = MAKE_RETURN_CODE(1);
|
||||||
|
//! [EXPORT] : [COMMENT] Requested set does not exist in json file
|
||||||
|
static const ReturnValue_t SET_NOT_EXISTS = MAKE_RETURN_CODE(2);
|
||||||
|
//! [EXPORT] : [COMMENT] Requested parameter does not exist in json file
|
||||||
|
static const ReturnValue_t PARAM_NOT_EXISTS = MAKE_RETURN_CODE(3);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Constructor
|
||||||
|
*
|
||||||
|
* @param fullname Name with absolute path of json file containing the parameters to set.
|
||||||
|
*/
|
||||||
|
ArcsecJsonParamBase(std::string setName);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills a buffer with a parameter set
|
||||||
|
*
|
||||||
|
* @param fullname The name including the absolute path of the json file containing the
|
||||||
|
* parameter set.
|
||||||
|
* @param buffer Pointer to the buffer the command will be written to
|
||||||
|
*/
|
||||||
|
ReturnValue_t create(std::string fullname, uint8_t* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns the size of the parameter command.
|
||||||
|
*/
|
||||||
|
virtual size_t getSize() = 0;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
/**
|
||||||
|
* @brief Reads the value of a parameter from a json set
|
||||||
|
*
|
||||||
|
* @param name The name of the parameter
|
||||||
|
* @param value The string representation of the read value
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if successful, otherwise PARAM_NOT_EXISTS
|
||||||
|
*/
|
||||||
|
ReturnValue_t getParam(const std::string name, std::string& value);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Converts empty string which is equal to define a value as zero.
|
||||||
|
*/
|
||||||
|
void convertEmpty(std::string& value);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function adds a float represented as string to a buffer
|
||||||
|
*
|
||||||
|
* @param value The float in string representation to add
|
||||||
|
* @param buffer Pointer to the buffer the float will be written to
|
||||||
|
*/
|
||||||
|
void addfloat(const std::string value, uint8_t* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function adds a uint8_t represented as string to a buffer
|
||||||
|
*
|
||||||
|
* @param value The uint8_t in string representation to add
|
||||||
|
* @param buffer Pointer to the buffer the uint8_t will be written to
|
||||||
|
*/
|
||||||
|
void adduint8(const std::string value, uint8_t* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function adds a int16_t represented as string to a buffer
|
||||||
|
*
|
||||||
|
* @param value The int16_t in string representation to add
|
||||||
|
* @param buffer Pointer to the buffer the int16_t will be written to
|
||||||
|
*/
|
||||||
|
void addint16(const std::string value, uint8_t* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function adds a uint16_t represented as string to a buffer
|
||||||
|
*
|
||||||
|
* @param value The uint16_t in string representation to add
|
||||||
|
* @param buffer Pointer to the buffer the uint16_t will be written to
|
||||||
|
*/
|
||||||
|
void adduint16(const std::string value, uint8_t* buffer);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function adds a uint32_t represented as string to a buffer
|
||||||
|
*
|
||||||
|
* @param value The uint32_t in string representation to add
|
||||||
|
* @param buffer Pointer to the buffer the uint32_t will be written to
|
||||||
|
*/
|
||||||
|
void adduint32(const std::string value, uint8_t* buffer);
|
||||||
|
|
||||||
|
void addSetParamHeader(uint8_t* buffer, uint8_t setId);
|
||||||
|
|
||||||
|
private:
|
||||||
|
json properties;
|
||||||
|
json set;
|
||||||
|
std::string setName;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function must be implemented by the derived class to define creation of a
|
||||||
|
* parameter command.
|
||||||
|
*/
|
||||||
|
virtual ReturnValue_t createCommand(uint8_t* buffer) = 0;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Initializes the properties json object and the set json object
|
||||||
|
*
|
||||||
|
* @param fullname Name including absolute path to json file
|
||||||
|
* @param setName The name of the set to work on
|
||||||
|
*
|
||||||
|
* @param return JSON_FILE_NOT_EXISTS if specified file does not exist, otherwise
|
||||||
|
* RETURN_OK
|
||||||
|
*/
|
||||||
|
ReturnValue_t init(const std::string filename);
|
||||||
|
|
||||||
|
void createJsonObject(const std::string fullname);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Extracts the json set object form the json file
|
||||||
|
*
|
||||||
|
* @param setName The name of the set to create the json object from
|
||||||
|
*/
|
||||||
|
ReturnValue_t initSet();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* BSP_Q7S_DEVICES_STARTRACKER_ARCSECJSONPARAMBASE_H_ */
|
7
bsp_q7s/devices/startracker/CMakeLists.txt
Normal file
7
bsp_q7s/devices/startracker/CMakeLists.txt
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
target_sources(${TARGET_NAME} PRIVATE
|
||||||
|
StarTrackerHandler.cpp
|
||||||
|
StarTrackerJsonCommands.cpp
|
||||||
|
ArcsecDatalinkLayer.cpp
|
||||||
|
ArcsecJsonParamBase.cpp
|
||||||
|
StrHelper.cpp
|
||||||
|
)
|
1048
bsp_q7s/devices/startracker/StarTrackerDefinitions.h
Normal file
1048
bsp_q7s/devices/startracker/StarTrackerDefinitions.h
Normal file
File diff suppressed because it is too large
Load Diff
1947
bsp_q7s/devices/startracker/StarTrackerHandler.cpp
Normal file
1947
bsp_q7s/devices/startracker/StarTrackerHandler.cpp
Normal file
File diff suppressed because it is too large
Load Diff
543
bsp_q7s/devices/startracker/StarTrackerHandler.h
Normal file
543
bsp_q7s/devices/startracker/StarTrackerHandler.h
Normal file
@ -0,0 +1,543 @@
|
|||||||
|
#ifndef MISSION_DEVICES_STARTRACKERHANDLER_H_
|
||||||
|
#define MISSION_DEVICES_STARTRACKERHANDLER_H_
|
||||||
|
|
||||||
|
#include <fsfw/datapool/PoolReadGuard.h>
|
||||||
|
|
||||||
|
#include "ArcsecDatalinkLayer.h"
|
||||||
|
#include "ArcsecJsonParamBase.h"
|
||||||
|
#include "StarTrackerDefinitions.h"
|
||||||
|
#include "StrHelper.h"
|
||||||
|
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||||
|
#include "fsfw/src/fsfw/serialize/SerializeAdapter.h"
|
||||||
|
#include "fsfw/timemanager/Countdown.h"
|
||||||
|
#include "thirdparty/arcsec_star_tracker/common/SLIP.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This is the device handler for the star tracker from arcsec.
|
||||||
|
*
|
||||||
|
* @details Datasheet: https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_IRS/
|
||||||
|
* Arbeitsdaten/08_Used%20Components/ArcSec_KULeuven_Startracker/
|
||||||
|
* Sagitta%201.0%20Datapack&fileid=659181
|
||||||
|
* @author J. Meier
|
||||||
|
*/
|
||||||
|
class StarTrackerHandler : public DeviceHandlerBase {
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
* @brief Constructor
|
||||||
|
*
|
||||||
|
* @param objectId
|
||||||
|
* @param comIF
|
||||||
|
* @param comCookie
|
||||||
|
* @param gpioComIF Pointer to gpio communication interface
|
||||||
|
* @param enablePin GPIO connected to the enable pin of the reaction wheels. Must be pulled
|
||||||
|
* to high to enable the device.
|
||||||
|
*/
|
||||||
|
StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
|
||||||
|
StrHelper* strHelper);
|
||||||
|
virtual ~StarTrackerHandler();
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Overwrite this function from DHB to handle commands executed by the str image
|
||||||
|
* loader task.
|
||||||
|
*/
|
||||||
|
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
|
||||||
|
const uint8_t* data, size_t size) override;
|
||||||
|
|
||||||
|
void performOperationHook() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void doStartUp() override;
|
||||||
|
void doShutDown() override;
|
||||||
|
void doOffActivity() override;
|
||||||
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
|
||||||
|
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
|
||||||
|
void fillCommandAndReplyMap() override;
|
||||||
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData,
|
||||||
|
size_t commandDataLen) override;
|
||||||
|
ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId,
|
||||||
|
size_t* foundLen) override;
|
||||||
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override;
|
||||||
|
void setNormalDatapoolEntriesInvalid() override;
|
||||||
|
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
|
||||||
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
|
||||||
|
LocalDataPoolManager& poolManager) override;
|
||||||
|
/**
|
||||||
|
* @brief Overwritten here to always read all available data from the UartComIF.
|
||||||
|
*/
|
||||||
|
virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
|
||||||
|
virtual ReturnValue_t doSendReadHook() override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HANDLER;
|
||||||
|
|
||||||
|
//! [EXPORT] : [COMMENT] Received reply is too short
|
||||||
|
static const ReturnValue_t REPLY_TOO_SHORT = MAKE_RETURN_CODE(0xB0);
|
||||||
|
//! [EXPORT] : [COMMENT] Received reply with invalid CRC
|
||||||
|
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xB1);
|
||||||
|
//! [EXPORT] : [COMMENT] Image loader executing
|
||||||
|
static const ReturnValue_t IMAGE_LOADER_EXECUTING = MAKE_RETURN_CODE(0xB2);
|
||||||
|
|
||||||
|
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER;
|
||||||
|
|
||||||
|
//! [EXPORT] : [COMMENT] Status in temperature reply signals error
|
||||||
|
static const ReturnValue_t TEMPERATURE_REQ_FAILED = MAKE_RETURN_CODE(0xA0);
|
||||||
|
//! [EXPORT] : [COMMENT] Ping command failed
|
||||||
|
static const ReturnValue_t PING_FAILED = MAKE_RETURN_CODE(0xA1);
|
||||||
|
//! [EXPORT] : [COMMENT] Status in version reply signals error
|
||||||
|
static const ReturnValue_t VERSION_REQ_FAILED = MAKE_RETURN_CODE(0xA3);
|
||||||
|
//! [EXPORT] : [COMMENT] Status in interface reply signals error
|
||||||
|
static const ReturnValue_t INTERFACE_REQ_FAILED = MAKE_RETURN_CODE(0xA4);
|
||||||
|
//! [EXPORT] : [COMMENT] Status in power reply signals error
|
||||||
|
static const ReturnValue_t POWER_REQ_FAILED = MAKE_RETURN_CODE(0xA5);
|
||||||
|
//! [EXPORT] : [COMMENT] Status of reply to parameter set command signals error
|
||||||
|
static const ReturnValue_t SET_PARAM_FAILED = MAKE_RETURN_CODE(0xA6);
|
||||||
|
//! [EXPORT] : [COMMENT] Status of reply to action command signals error
|
||||||
|
static const ReturnValue_t ACTION_FAILED = MAKE_RETURN_CODE(0xA7);
|
||||||
|
//! [EXPORT] : [COMMENT] Received upload image command with invalid length
|
||||||
|
static const ReturnValue_t UPLOAD_TOO_SHORT = MAKE_RETURN_CODE(0xA8);
|
||||||
|
//! [EXPORT] : [COMMENT] Received upload image command with invalid position field
|
||||||
|
static const ReturnValue_t UPLOAD_INVALID_POSITION = MAKE_RETURN_CODE(0xA8);
|
||||||
|
//! [EXPORT] : [COMMENT] Position value in upload image reply not matching sent position
|
||||||
|
static const ReturnValue_t UPLOAD_IMAGE_FAILED = MAKE_RETURN_CODE(0xA9);
|
||||||
|
//! [EXPORT] : [COMMENT] Received upload image command with invalid length
|
||||||
|
static const ReturnValue_t INVALID_UPLOAD_COMMAND = MAKE_RETURN_CODE(0xAA);
|
||||||
|
//! [EXPORT] : [COMMENT] Received invalid path string. Exceeds allowed length
|
||||||
|
static const ReturnValue_t FILE_PATH_TOO_LONG = MAKE_RETURN_CODE(0xAB);
|
||||||
|
//! [EXPORT] : [COMMENT] Name of file received with command is too long
|
||||||
|
static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xAC);
|
||||||
|
//! [EXPORT] : [COMMENT] Received version reply with invalid program ID
|
||||||
|
static const ReturnValue_t INVALID_PROGRAM = MAKE_RETURN_CODE(0xAD);
|
||||||
|
//! [EXPORT] : [COMMENT] Status field reply signals error
|
||||||
|
static const ReturnValue_t REPLY_ERROR = MAKE_RETURN_CODE(0xAE);
|
||||||
|
//! [EXPORT] : [COMMENT] Status field of contrast reply signals error
|
||||||
|
static const ReturnValue_t CONTRAST_REQ_FAILED = MAKE_RETURN_CODE(0xAE);
|
||||||
|
//! [EXPORT] : [COMMENT] Received command which is too short (some data is missing for proper
|
||||||
|
//! execution)
|
||||||
|
static const ReturnValue_t COMMAND_TOO_SHORT = MAKE_RETURN_CODE(0xAF);
|
||||||
|
//! [EXPORT] : [COMMENT] Received command with invalid length (too few or too many parameters)
|
||||||
|
static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xB0);
|
||||||
|
//! [EXPORT] : [COMMENT] Region mismatch between send and received data
|
||||||
|
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xB1);
|
||||||
|
//! [EXPORT] : [COMMENT] Address mismatch between send and received data
|
||||||
|
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xB2);
|
||||||
|
//! [EXPORT] : [COMMENT] Length field mismatch between send and received data
|
||||||
|
static const ReturnValue_t lENGTH_MISMATCH = MAKE_RETURN_CODE(0xB3);
|
||||||
|
//! [EXPORT] : [COMMENT] Specified file does not exist
|
||||||
|
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xB4);
|
||||||
|
//! [EXPORT] : [COMMENT] Reply to upload centroid does not match commanded centroid id
|
||||||
|
static const ReturnValue_t UPLOAD_CENTROID_ID_MISMATCH = MAKE_RETURN_CODE(0xB5);
|
||||||
|
//! [EXPORT] : [COMMENT] Download blob pixel command has invalid type field
|
||||||
|
static const ReturnValue_t INVALID_TYPE = MAKE_RETURN_CODE(0xB6);
|
||||||
|
//! [EXPORT] : [COMMENT] Received FPGA action command with invalid ID
|
||||||
|
static const ReturnValue_t INVALID_ID = MAKE_RETURN_CODE(0xB7);
|
||||||
|
|
||||||
|
static const size_t MAX_PATH_SIZE = 50;
|
||||||
|
static const size_t MAX_FILE_NAME = 30;
|
||||||
|
|
||||||
|
// position (uint32) + 1024 image data
|
||||||
|
static const size_t UPLOAD_COMMAND_LEN = 1028;
|
||||||
|
// Max valid position value in upload image command
|
||||||
|
static const uint16_t MAX_POSITION = 4095;
|
||||||
|
static const uint8_t STATUS_OFFSET = 1;
|
||||||
|
static const uint8_t TICKS_OFFSET = 2;
|
||||||
|
static const uint8_t TIME_OFFSET = 6;
|
||||||
|
static const uint8_t TM_DATA_FIELD_OFFSET = 14;
|
||||||
|
static const uint8_t PARAMETER_ID_OFFSET = 0;
|
||||||
|
static const uint8_t ACTION_ID_OFFSET = 0;
|
||||||
|
static const uint8_t ACTION_DATA_OFFSET = 2;
|
||||||
|
// Ping request will reply ping with this ID (data field)
|
||||||
|
static const uint32_t PING_ID = 0x55;
|
||||||
|
static const uint32_t BOOT_REGION_ID = 1;
|
||||||
|
static const MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING;
|
||||||
|
static const uint32_t MUTEX_TIMEOUT = 20;
|
||||||
|
static const uint32_t BOOT_TIMEOUT = 1000;
|
||||||
|
|
||||||
|
class WriteCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t ADDRESS_OFFSET = 1;
|
||||||
|
static const uint8_t FILE_OFFSET = 5;
|
||||||
|
// Minimum length of a write command (region, address and filename)
|
||||||
|
static const size_t MIN_LENGTH = 7;
|
||||||
|
};
|
||||||
|
|
||||||
|
class ReadCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t ADDRESS_OFFSET = 1;
|
||||||
|
static const uint8_t LENGTH_OFFSET = 5;
|
||||||
|
static const uint8_t FILE_OFFSET = 9;
|
||||||
|
// Minimum length of a read command (region, address, length and filename)
|
||||||
|
static const size_t MIN_LENGTH = 11;
|
||||||
|
};
|
||||||
|
|
||||||
|
class EraseCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 1;
|
||||||
|
uint8_t rememberRegion = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
EraseCmd eraseCmd;
|
||||||
|
|
||||||
|
class UnlockCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t CODE_OFFSET = 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
class ChecksumCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t ADDRESS_OFFSET = 1;
|
||||||
|
static const uint8_t LENGTH_OFFSET = 5;
|
||||||
|
// Length of checksum command
|
||||||
|
static const size_t LENGTH = 9;
|
||||||
|
uint8_t rememberRegion = 0;
|
||||||
|
uint32_t rememberAddress = 0;
|
||||||
|
uint32_t rememberLength = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
ChecksumCmd checksumCmd;
|
||||||
|
|
||||||
|
class SetTimeCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 8;
|
||||||
|
};
|
||||||
|
|
||||||
|
class DownloadCentroidCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
class UploadCentroid {
|
||||||
|
public:
|
||||||
|
uint8_t rememberId = 0;
|
||||||
|
};
|
||||||
|
|
||||||
|
UploadCentroid uploadCentroid;
|
||||||
|
|
||||||
|
class DownloadMatchedStarCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
class DownloadDbImageCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
class DownloadBlobPixCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 2;
|
||||||
|
static const uint8_t NORMAL = 0;
|
||||||
|
static const uint8_t FAST = 1;
|
||||||
|
};
|
||||||
|
|
||||||
|
class FpgaDownloadCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t MIN_LENGTH = 10;
|
||||||
|
};
|
||||||
|
|
||||||
|
class FpgaActionCmd {
|
||||||
|
public:
|
||||||
|
static const uint8_t LENGTH = 1;
|
||||||
|
static const uint8_t ID = 3;
|
||||||
|
};
|
||||||
|
|
||||||
|
MessageQueueIF* eventQueue = nullptr;
|
||||||
|
|
||||||
|
ArcsecDatalinkLayer dataLinkLayer;
|
||||||
|
|
||||||
|
StarTracker::TemperatureSet temperatureSet;
|
||||||
|
StarTracker::VersionSet versionSet;
|
||||||
|
StarTracker::PowerSet powerSet;
|
||||||
|
StarTracker::InterfaceSet interfaceSet;
|
||||||
|
StarTracker::TimeSet timeSet;
|
||||||
|
StarTracker::SolutionSet solutionSet;
|
||||||
|
StarTracker::HistogramSet histogramSet;
|
||||||
|
StarTracker::ContrastSet contrastSet;
|
||||||
|
StarTracker::ChecksumSet checksumSet;
|
||||||
|
StarTracker::DownloadCentroidSet downloadCentroidSet;
|
||||||
|
StarTracker::DownloadMatchedStar downloadMatchedStar;
|
||||||
|
StarTracker::DownloadDBImage downloadDbImage;
|
||||||
|
StarTracker::DownloadBlobPixel downloadBlobPixel;
|
||||||
|
|
||||||
|
// Pointer to object responsible for uploading and downloading images to/from the star tracker
|
||||||
|
StrHelper* strHelper = nullptr;
|
||||||
|
|
||||||
|
uint8_t commandBuffer[StarTracker::MAX_FRAME_SIZE];
|
||||||
|
|
||||||
|
// Countdown to insert delay for star tracker to switch from bootloader to firmware program
|
||||||
|
Countdown bootCountdown;
|
||||||
|
|
||||||
|
std::string paramJsonFile = "/mnt/sd0/startracker/full.json";
|
||||||
|
|
||||||
|
enum class InternalState { TEMPERATURE_REQUEST };
|
||||||
|
|
||||||
|
InternalState internalState = InternalState::TEMPERATURE_REQUEST;
|
||||||
|
|
||||||
|
enum class StartupState {
|
||||||
|
IDLE,
|
||||||
|
CHECK_BOOT_STATE,
|
||||||
|
BOOT,
|
||||||
|
BOOT_DELAY,
|
||||||
|
LIMITS,
|
||||||
|
TRACKING,
|
||||||
|
MOUNTING,
|
||||||
|
CAMERA,
|
||||||
|
BLOB,
|
||||||
|
CENTROIDING,
|
||||||
|
LISA,
|
||||||
|
MATCHING,
|
||||||
|
VALIDATION,
|
||||||
|
ALGO,
|
||||||
|
WAIT_FOR_EXECUTION,
|
||||||
|
DONE
|
||||||
|
};
|
||||||
|
|
||||||
|
StartupState startupState = StartupState::IDLE;
|
||||||
|
|
||||||
|
bool strHelperExecuting = false;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles internal state
|
||||||
|
*/
|
||||||
|
void handleInternalState();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks mode for commands requiring MODE_ON of MODE_NORMAL for execution.
|
||||||
|
*
|
||||||
|
* @param actionId Action id of command to execute
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkMode(ActionId_t actionId);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This function initializes the serial link ip protocol struct slipInfo.
|
||||||
|
*/
|
||||||
|
void slipInit();
|
||||||
|
|
||||||
|
ReturnValue_t scanForActionReply(DeviceCommandId_t* foundId);
|
||||||
|
ReturnValue_t scanForParameterReply(DeviceCommandId_t* foundId);
|
||||||
|
ReturnValue_t scanForTmReply(DeviceCommandId_t* foundId);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to ping the star tracker
|
||||||
|
*/
|
||||||
|
void preparePingRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request the time telemetry.
|
||||||
|
*/
|
||||||
|
void prepareTimeRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles all received event messages
|
||||||
|
*/
|
||||||
|
void handleEvent(EventMessage* eventMessage);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Executes the write command
|
||||||
|
*
|
||||||
|
* @param commandData Pointer to received command data
|
||||||
|
* @param commandDataLen Size of received command data
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if start of execution was successful, otherwise error return value
|
||||||
|
*/
|
||||||
|
ReturnValue_t executeWriteCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts the execution of the fpga download command
|
||||||
|
*
|
||||||
|
* @param commandData Pointer to buffer with command data
|
||||||
|
* @param commandDataLen Size of received command
|
||||||
|
*/
|
||||||
|
ReturnValue_t executeFpgaDownloadCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Extracts information for flash-read-command from TC data and starts execution of
|
||||||
|
* flash-read-procedure
|
||||||
|
*
|
||||||
|
* @param commandData Pointer to received command data
|
||||||
|
* @param commandDataLen Size of received command data
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if start of execution was successful, otherwise error return value
|
||||||
|
*/
|
||||||
|
ReturnValue_t executeReadCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to boot image (works only when star tracker is
|
||||||
|
* in bootloader mode).
|
||||||
|
*/
|
||||||
|
void prepareBootCommand();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to erase a flash region
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareEraseCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to unlock flash region
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareUnlockCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to get the checksum of a flash part
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareChecksumCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to set the unix time
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareSetTimeCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to request a centroid
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareDownloadCentroidCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to upload a centroid for testing purpose
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareUploadCentroidCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills the command buffer with the command to take an image.
|
||||||
|
*/
|
||||||
|
void prepareTakeImageCommand(const uint8_t* commandData);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request the version telemetry packet
|
||||||
|
*/
|
||||||
|
void prepareVersionRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills the command buffer with data to request the interface telemetry packet.
|
||||||
|
*/
|
||||||
|
void prepareInterfaceRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills the command buffer with data to request the power telemetry packet.
|
||||||
|
*/
|
||||||
|
void preparePowerRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to reboot star tracker.
|
||||||
|
*/
|
||||||
|
void prepareRebootCommand();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to subscribe to a telemetry packet.
|
||||||
|
*
|
||||||
|
* @param tmId The ID of the telemetry packet to subscribe to
|
||||||
|
*/
|
||||||
|
void prepareSubscriptionCommand(const uint8_t* tmId);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request solution telemtry packet (contains
|
||||||
|
* attitude information)
|
||||||
|
*/
|
||||||
|
void prepareSolutionRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request temperature from star tracker
|
||||||
|
*/
|
||||||
|
void prepareTemperatureRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request histogram
|
||||||
|
*/
|
||||||
|
void prepareHistogramRequest();
|
||||||
|
|
||||||
|
void prepareContrastRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with command to reset the error signal of the star tracker
|
||||||
|
*/
|
||||||
|
void prepareErrorResetRequest();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Reads parameters from json file specified by string in commandData and
|
||||||
|
* prepares the command to apply the parameter set to the star tracker
|
||||||
|
*
|
||||||
|
* @param commandData Contains string with file name
|
||||||
|
* @param commandDataLen Length of command
|
||||||
|
* @param paramSet The object defining the command generation
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if successful, otherwise error return Value
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareParamCommand(const uint8_t* commandData, size_t commandDataLen,
|
||||||
|
ArcsecJsonParamBase& paramSet);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request matched star.
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareDownloadMatchedStarCommand(const uint8_t* commandData,
|
||||||
|
size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request matched star coordinates.
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareDownloadDbImageCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Fills command buffer with data to request output of the blob filter algorithm.
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareDownloadBlobPixelCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief With this command the FPGA update will be applied to the star tracker
|
||||||
|
*/
|
||||||
|
ReturnValue_t prepareFpgaActionCommand(const uint8_t* commandData, size_t commandDataLen);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles action replies with datasets.
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Default function to handle action replies
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleActionReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles reply to upload centroid command
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleUploadCentroidReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles reply to erase command
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleEraseReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles reply to checksum command
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleChecksumReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles all set parameter replies
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleSetParamReply();
|
||||||
|
|
||||||
|
ReturnValue_t handlePingReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks the loaded program by means of the version set
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkProgram();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles the startup state machine
|
||||||
|
*/
|
||||||
|
void handleStartup(const uint8_t* parameterId);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles telemtry replies and fills the appropriate dataset
|
||||||
|
*
|
||||||
|
* @param dataset Dataset where reply data will be written to
|
||||||
|
* @param size Size of the dataset
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if successful, otherwise error return value
|
||||||
|
*/
|
||||||
|
ReturnValue_t handleTm(LocalPoolDataSetBase& dataset, size_t size);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* MISSION_DEVICES_STARTRACKERHANDLER_H_ */
|
689
bsp_q7s/devices/startracker/StarTrackerJsonCommands.cpp
Normal file
689
bsp_q7s/devices/startracker/StarTrackerJsonCommands.cpp
Normal file
@ -0,0 +1,689 @@
|
|||||||
|
#include "StarTrackerJsonCommands.h"
|
||||||
|
|
||||||
|
#include "ArcsecJsonKeys.h"
|
||||||
|
|
||||||
|
Limits::Limits() : ArcsecJsonParamBase(arcseckeys::LIMITS) {}
|
||||||
|
|
||||||
|
size_t Limits::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Limits::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::LIMITS);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::ACTION, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::FPGA18CURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FPGA25CURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FPGA10CURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MCUCURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CMOS21CURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CMOSPIXCURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CMOS33CURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CMOSVRESCURRENT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CMOS_TEMPERATURE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MCU_TEMPERATURE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Tracking::Tracking() : ArcsecJsonParamBase(arcseckeys::TRACKING) {}
|
||||||
|
|
||||||
|
size_t Tracking::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Tracking::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::TRACKING);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::THIN_LIMIT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::OUTLIER_THRESHOLD, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::OUTLIER_THRESHOLD_QUEST, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::TRACKER_CHOICE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Mounting::Mounting() : ArcsecJsonParamBase(arcseckeys::MOUNTING) {}
|
||||||
|
|
||||||
|
size_t Mounting::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Mounting::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::MOUNTING);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::qw, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::qx, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::qy, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::qz, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Camera::Camera() : ArcsecJsonParamBase(arcseckeys::CAMERA) {}
|
||||||
|
|
||||||
|
size_t Camera::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Camera::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::CAMERA);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::MODE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::FOCALLENGTH, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::EXPOSURE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::INTERVAL, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::OFFSET, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addint16(param, buffer + offset);
|
||||||
|
offset += sizeof(int16_t);
|
||||||
|
result = getParam(arcseckeys::PGAGAIN, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::ADCGAIN, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_1, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_1, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_2, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_2, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_3, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_3, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_4, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_4, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_5, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_5, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_6, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_6, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_7, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_7, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::REG_8, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::VAL_8, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::FREQ_1, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FREQ_2, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Blob::Blob() : ArcsecJsonParamBase(arcseckeys::BLOB) {}
|
||||||
|
|
||||||
|
size_t Blob::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Blob::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::BLOB);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::MODE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::MIN_VALUE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::MIN_DISTANCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::NEIGHBOUR_DISTANCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::NEIGHBOUR_BRIGHT_PIXELS, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::MIN_TOTAL_VALUE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint16(param, buffer + offset);
|
||||||
|
offset += sizeof(uint16_t);
|
||||||
|
result = getParam(arcseckeys::MAX_TOTAL_VALUE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint16(param, buffer + offset);
|
||||||
|
offset += sizeof(uint16_t);
|
||||||
|
result = getParam(arcseckeys::MIN_BRIGHT_NEIGHBOURS, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint16(param, buffer + offset);
|
||||||
|
offset += sizeof(uint16_t);
|
||||||
|
result = getParam(arcseckeys::MAX_BRIGHT_NEIGHBOURS, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint16(param, buffer + offset);
|
||||||
|
offset += sizeof(uint16_t);
|
||||||
|
result = getParam(arcseckeys::MAX_PIXEL_TO_CONSIDER, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint32(param, buffer + offset);
|
||||||
|
offset += sizeof(uint32_t);
|
||||||
|
result = getParam(arcseckeys::SIGNAL_THRESHOLD, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::DARK_THRESHOLD, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::ENABLE_HISTOGRAM, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::ENABLE_CONTRAST, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::BIN_MODE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Centroiding::Centroiding() : ArcsecJsonParamBase(arcseckeys::CENTROIDING) {}
|
||||||
|
|
||||||
|
size_t Centroiding::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Centroiding::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::CENTROIDING);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::ENABLE_FILTER, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::MAX_QUALITY, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MIN_QUALITY, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MAX_INTENSITY, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MIN_INTENSITY, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MAX_MAGNITUDE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::GAUSSIAN_CMAX, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::GAUSSIAN_CMIN, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::TRANSMATRIX_00, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::TRANSMATRIX_01, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::TRANSMATRIX_10, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::TRANSMATRIX_11, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Lisa::Lisa() : ArcsecJsonParamBase(arcseckeys::LISA) {}
|
||||||
|
|
||||||
|
size_t Lisa::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Lisa::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::LISA);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::PREFILTER_DIST_THRESHOLD, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::PREFILTER_ANGLE_THRESHOLD, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FOV_WIDTH, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FOV_HEIGHT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::FLOAT_STAR_LIMIT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::CLOSE_STAR_LIMIT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::RATING_WEIGHT_CLOSE_STAR_COUNT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::RATING_WEIGHT_FRACTION_CLOSE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::RATING_WEIGHT_DB_STAR_COUNT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MAX_COMBINATIONS, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::NR_STARS_STOP, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::FRACTION_CLOSE_STOP, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Matching::Matching() : ArcsecJsonParamBase(arcseckeys::MATCHING) {}
|
||||||
|
|
||||||
|
size_t Matching::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Matching::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::MATCHING);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::SQUARED_DISTANCE_LIMIT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::SQUARED_SHIFT_LIMIT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Validation::Validation() : ArcsecJsonParamBase(arcseckeys::VALIDATION) {}
|
||||||
|
|
||||||
|
size_t Validation::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Validation::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::VALIDATION);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::STABLE_COUNT, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::MAX_DIFFERENCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MIN_TRACKER_CONFIDENCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::MIN_MATCHED_STARS, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
Algo::Algo() : ArcsecJsonParamBase(arcseckeys::ALGO) {}
|
||||||
|
|
||||||
|
size_t Algo::getSize() { return COMMAND_SIZE; }
|
||||||
|
|
||||||
|
ReturnValue_t Algo::createCommand(uint8_t* buffer) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint8_t offset = 0;
|
||||||
|
std::string param;
|
||||||
|
addSetParamHeader(buffer, StarTracker::ID::ALGO);
|
||||||
|
offset = 2;
|
||||||
|
result = getParam(arcseckeys::MODE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::L2T_MIN_CONFIDENCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::L2T_MIN_MATCHED, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
offset += sizeof(uint8_t);
|
||||||
|
result = getParam(arcseckeys::T2L_MIN_CONFIDENCE, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
addfloat(param, buffer + offset);
|
||||||
|
offset += sizeof(float);
|
||||||
|
result = getParam(arcseckeys::T2L_MIN_MATCHED, param);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
adduint8(param, buffer + offset);
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
176
bsp_q7s/devices/startracker/StarTrackerJsonCommands.h
Normal file
176
bsp_q7s/devices/startracker/StarTrackerJsonCommands.h
Normal file
@ -0,0 +1,176 @@
|
|||||||
|
#ifndef BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_
|
||||||
|
#define BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief This file defines a few helper classes to generate commands by means of the parameters
|
||||||
|
* defined in the arcsec json files.
|
||||||
|
* @author J. Meier
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "ArcsecJsonParamBase.h"
|
||||||
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates command to set the limit parameters
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Limits : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Limits();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 43;
|
||||||
|
|
||||||
|
virtual ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the tracking algorithm.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Tracking : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Tracking();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 15;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to set the mounting quaternion
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Mounting : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Mounting();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 18;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to set the mounting quaternion
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Camera : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Camera();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 43;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the blob algorithm
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Blob : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Blob();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 24;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the centroiding algorithm
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Centroiding : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Centroiding();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 47;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the LISA (lost in space algorithm)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Lisa : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Lisa();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 48;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the matching algorithm
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Matching : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Matching();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 10;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates the command to configure the validation parameters
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Validation : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Validation();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 12;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Generates command to configure the mechanism of automatically switching between the
|
||||||
|
* LISA and other algorithms.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
class Algo : public ArcsecJsonParamBase {
|
||||||
|
public:
|
||||||
|
Algo();
|
||||||
|
|
||||||
|
size_t getSize();
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const size_t COMMAND_SIZE = 13;
|
||||||
|
|
||||||
|
ReturnValue_t createCommand(uint8_t* buffer) override;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* BSP_Q7S_DEVICES_DEVICEDEFINITIONS_STARTRACKERJSONCOMMANDS_H_ */
|
672
bsp_q7s/devices/startracker/StrHelper.cpp
Normal file
672
bsp_q7s/devices/startracker/StrHelper.cpp
Normal file
@ -0,0 +1,672 @@
|
|||||||
|
#include "StrHelper.h"
|
||||||
|
|
||||||
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
|
|
||||||
|
#include "mission/utility/Timestamp.h"
|
||||||
|
|
||||||
|
StrHelper::StrHelper(object_id_t objectId) : SystemObject(objectId) {}
|
||||||
|
|
||||||
|
StrHelper::~StrHelper() {}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::initialize() {
|
||||||
|
sdcMan = SdCardManager::instance();
|
||||||
|
if (sdcMan == nullptr) {
|
||||||
|
sif::warning << "StrHelper::initialize: Invalid SD Card Manager" << std::endl;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
semaphore.acquire();
|
||||||
|
while (true) {
|
||||||
|
switch (internalState) {
|
||||||
|
case InternalState::IDLE: {
|
||||||
|
semaphore.acquire();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::UPLOAD_IMAGE: {
|
||||||
|
result = performImageUpload();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(IMAGE_UPLOAD_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(IMAGE_UPLOAD_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::DOWNLOAD_IMAGE: {
|
||||||
|
result = performImageDownload();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(IMAGE_DOWNLOAD_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(IMAGE_DOWNLOAD_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::FLASH_WRITE: {
|
||||||
|
result = performFlashWrite();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(FLASH_WRITE_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(FLASH_WRITE_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::FLASH_READ: {
|
||||||
|
result = performFlashRead();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(FLASH_READ_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(FLASH_READ_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::DOWNLOAD_FPGA_IMAGE: {
|
||||||
|
result = performFpgaDownload();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(FPGA_DOWNLOAD_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(FPGA_DOWNLOAD_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case InternalState::UPLOAD_FPGA_IMAGE: {
|
||||||
|
result = performFpgaUpload();
|
||||||
|
if (result == RETURN_OK) {
|
||||||
|
triggerEvent(FPGA_UPLOAD_SUCCESSFUL);
|
||||||
|
} else {
|
||||||
|
triggerEvent(FPGA_UPLOAD_FAILED);
|
||||||
|
}
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
sif::debug << "StrHelper::performOperation: Invalid state" << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
|
||||||
|
uartComIF = dynamic_cast<UartComIF*>(communicationInterface_);
|
||||||
|
if (uartComIF == nullptr) {
|
||||||
|
sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StrHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
|
||||||
|
ReturnValue_t result = checkPath(fullname);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uploadImage.uploadFile = fullname;
|
||||||
|
if (not std::filesystem::exists(fullname)) {
|
||||||
|
return FILE_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
internalState = InternalState::UPLOAD_FPGA_IMAGE;
|
||||||
|
semaphore.release();
|
||||||
|
terminate = false;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startImageDownload(std::string path) {
|
||||||
|
ReturnValue_t result = checkPath(path);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
if (not std::filesystem::exists(path)) {
|
||||||
|
return PATH_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
downloadImage.path = path;
|
||||||
|
internalState = InternalState::DOWNLOAD_IMAGE;
|
||||||
|
terminate = false;
|
||||||
|
semaphore.release();
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StrHelper::stopProcess() { terminate = true; }
|
||||||
|
|
||||||
|
void StrHelper::setDownloadImageName(std::string filename) { downloadImage.filename = filename; }
|
||||||
|
|
||||||
|
void StrHelper::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
|
||||||
|
|
||||||
|
void StrHelper::setDownloadFpgaImage(std::string filename) { fpgaDownload.fileName = filename; }
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startFlashWrite(std::string fullname, uint8_t region, uint32_t address) {
|
||||||
|
ReturnValue_t result = checkPath(fullname);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
flashWrite.fullname = fullname;
|
||||||
|
if (not std::filesystem::exists(flashWrite.fullname)) {
|
||||||
|
return FILE_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
flashWrite.address = address;
|
||||||
|
flashWrite.region = region;
|
||||||
|
internalState = InternalState::FLASH_WRITE;
|
||||||
|
semaphore.release();
|
||||||
|
terminate = false;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t region, uint32_t address,
|
||||||
|
uint32_t length) {
|
||||||
|
ReturnValue_t result = checkPath(path);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
flashRead.path = path;
|
||||||
|
if (not std::filesystem::exists(flashRead.path)) {
|
||||||
|
return FILE_NOT_EXISTS;
|
||||||
|
}
|
||||||
|
flashRead.address = address;
|
||||||
|
flashRead.region = region;
|
||||||
|
flashRead.size = length;
|
||||||
|
internalState = InternalState::FLASH_READ;
|
||||||
|
semaphore.release();
|
||||||
|
terminate = false;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startFpgaDownload(std::string path, uint32_t startPosition,
|
||||||
|
uint32_t length) {
|
||||||
|
fpgaDownload.path = path;
|
||||||
|
fpgaDownload.startPosition = startPosition;
|
||||||
|
fpgaDownload.length = length;
|
||||||
|
internalState = InternalState::DOWNLOAD_FPGA_IMAGE;
|
||||||
|
semaphore.release();
|
||||||
|
terminate = false;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::startFpgaUpload(std::string uploadFile) {
|
||||||
|
fpgaUpload.uploadFile = uploadFile;
|
||||||
|
internalState = InternalState::UPLOAD_FPGA_IMAGE;
|
||||||
|
semaphore.release();
|
||||||
|
terminate = false;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performImageDownload() {
|
||||||
|
ReturnValue_t result;
|
||||||
|
struct DownloadActionRequest downloadReq;
|
||||||
|
uint32_t size = 0;
|
||||||
|
uint32_t retries = 0;
|
||||||
|
Timestamp timestamp;
|
||||||
|
std::string image = downloadImage.path + "/" + timestamp.str() + downloadImage.filename;
|
||||||
|
std::ofstream file(image, std::ios_base::app | std::ios_base::out);
|
||||||
|
if (not std::filesystem::exists(image)) {
|
||||||
|
return FILE_CREATION_FAILED;
|
||||||
|
}
|
||||||
|
downloadReq.position = 0;
|
||||||
|
while (downloadReq.position < ImageDownload::LAST_POSITION) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
arc_pack_download_action_req(&downloadReq, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, downloadReq.position);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkReplyPosition(downloadReq.position);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + IMAGE_DATA_OFFSET),
|
||||||
|
IMAGE_DATA_SIZE);
|
||||||
|
downloadReq.position++;
|
||||||
|
retries = 0;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performImageUpload() {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint32_t size = 0;
|
||||||
|
uint32_t imageSize = 0;
|
||||||
|
struct UploadActionRequest uploadReq;
|
||||||
|
uploadReq.position = 0;
|
||||||
|
std::memset(&uploadReq.data, 0, sizeof(uploadReq.data));
|
||||||
|
if (not std::filesystem::exists(uploadImage.uploadFile)) {
|
||||||
|
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
std::ifstream file(uploadImage.uploadFile, std::ifstream::binary);
|
||||||
|
// Set position of next character to end of file input stream
|
||||||
|
file.seekg(0, file.end);
|
||||||
|
// tellg returns position of character in input stream
|
||||||
|
imageSize = file.tellg();
|
||||||
|
while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(uploadReq.data), SIZE_IMAGE_PART);
|
||||||
|
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, uploadReq.position);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uploadReq.position++;
|
||||||
|
}
|
||||||
|
std::memset(uploadReq.data, 0, sizeof(uploadReq.data));
|
||||||
|
uint32_t remainder = imageSize - uploadReq.position * SIZE_IMAGE_PART;
|
||||||
|
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(uploadReq.data), remainder);
|
||||||
|
file.close();
|
||||||
|
uploadReq.position++;
|
||||||
|
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, uploadReq.position);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performFlashWrite() {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint32_t size = 0;
|
||||||
|
uint32_t remainingBytes = 0;
|
||||||
|
uint32_t fileSize = 0;
|
||||||
|
struct WriteActionRequest req;
|
||||||
|
if (not std::filesystem::exists(flashWrite.fullname)) {
|
||||||
|
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
std::ifstream file(flashWrite.fullname, std::ifstream::binary);
|
||||||
|
file.seekg(0, file.end);
|
||||||
|
fileSize = file.tellg();
|
||||||
|
remainingBytes = fileSize;
|
||||||
|
req.region = flashWrite.region;
|
||||||
|
req.address = flashWrite.address;
|
||||||
|
req.length = MAX_FLASH_DATA;
|
||||||
|
while (remainingBytes >= MAX_FLASH_DATA) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
file.seekg(fileSize - remainingBytes, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(req.data), MAX_FLASH_DATA);
|
||||||
|
arc_pack_write_action_req(&req, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, req.address);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = checkFlashActionReply(req.region, req.address, req.length);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
remainingBytes = remainingBytes - MAX_FLASH_DATA;
|
||||||
|
}
|
||||||
|
file.seekg(fileSize - remainingBytes, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(req.data), remainingBytes);
|
||||||
|
file.close();
|
||||||
|
arc_pack_write_action_req(&req, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, req.address);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = checkFlashActionReply(req.region, req.address, req.length);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performFlashRead() {
|
||||||
|
ReturnValue_t result;
|
||||||
|
struct ReadActionRequest req;
|
||||||
|
uint32_t bytesRead = 0;
|
||||||
|
uint32_t size = 0;
|
||||||
|
uint32_t retries = 0;
|
||||||
|
Timestamp timestamp;
|
||||||
|
std::string fullname = flashRead.path + "/" + timestamp.str() + flashRead.filename;
|
||||||
|
std::ofstream file(fullname, std::ios_base::app | std::ios_base::out);
|
||||||
|
if (not std::filesystem::exists(fullname)) {
|
||||||
|
return FILE_CREATION_FAILED;
|
||||||
|
}
|
||||||
|
req.region = flashRead.region;
|
||||||
|
while (bytesRead < flashRead.size) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
if ((flashRead.size - bytesRead) < MAX_FLASH_DATA) {
|
||||||
|
req.length = flashRead.size - bytesRead;
|
||||||
|
} else {
|
||||||
|
req.length = MAX_FLASH_DATA;
|
||||||
|
}
|
||||||
|
req.address = flashRead.address + bytesRead;
|
||||||
|
arc_pack_read_action_req(&req, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, req.address);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkFlashActionReply(req.region, req.address, req.length);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + FLASH_READ_DATA_OFFSET),
|
||||||
|
req.length);
|
||||||
|
bytesRead += req.length;
|
||||||
|
retries = 0;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performFpgaDownload() {
|
||||||
|
ReturnValue_t result;
|
||||||
|
struct DownloadFPGAImageActionRequest req;
|
||||||
|
uint32_t size = 0;
|
||||||
|
uint32_t retries = 0;
|
||||||
|
Timestamp timestamp;
|
||||||
|
std::string image = fpgaDownload.path + "/" + timestamp.str() + fpgaDownload.fileName;
|
||||||
|
std::ofstream file(image, std::ios_base::app | std::ios_base::out);
|
||||||
|
if (not std::filesystem::exists(image)) {
|
||||||
|
return FILE_CREATION_FAILED;
|
||||||
|
}
|
||||||
|
req.pos = fpgaDownload.startPosition;
|
||||||
|
while (req.pos < fpgaDownload.length) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
if (fpgaDownload.length - req.pos >= FpgaDownload::MAX_DATA) {
|
||||||
|
req.length = FpgaDownload::MAX_DATA;
|
||||||
|
} else {
|
||||||
|
req.length = fpgaDownload.length - req.pos;
|
||||||
|
}
|
||||||
|
arc_pack_downloadfpgaimage_action_req(&req, commandBuffer, &size);
|
||||||
|
result = sendAndRead(size, req.pos);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
result = checkFpgaActionReply(req.pos, req.length);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||||
|
uartComIF->flushUartRxBuffer(comCookie);
|
||||||
|
retries++;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + FpgaDownload::DATA_OFFSET),
|
||||||
|
req.length);
|
||||||
|
req.pos += req.length;
|
||||||
|
retries = 0;
|
||||||
|
}
|
||||||
|
file.close();
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::performFpgaUpload() {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
uint32_t commandSize = 0;
|
||||||
|
uint32_t bytesUploaded = 0;
|
||||||
|
uint32_t fileSize = 0;
|
||||||
|
struct UploadFPGAImageActionRequest req;
|
||||||
|
if (not std::filesystem::exists(fpgaUpload.uploadFile)) {
|
||||||
|
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
|
||||||
|
internalState = InternalState::IDLE;
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
std::ifstream file(flashWrite.fullname, std::ifstream::binary);
|
||||||
|
file.seekg(0, file.end);
|
||||||
|
fileSize = file.tellg();
|
||||||
|
req.pos = 0;
|
||||||
|
while (bytesUploaded <= fileSize) {
|
||||||
|
if (terminate) {
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
if (fileSize - bytesUploaded > FpgaUpload::MAX_DATA) {
|
||||||
|
req.length = FpgaUpload::MAX_DATA;
|
||||||
|
} else {
|
||||||
|
req.length = fileSize - bytesUploaded;
|
||||||
|
}
|
||||||
|
file.seekg(bytesUploaded, file.beg);
|
||||||
|
file.read(reinterpret_cast<char*>(req.data), req.length);
|
||||||
|
arc_pack_uploadfpgaimage_action_req(&req, commandBuffer, &commandSize);
|
||||||
|
result = sendAndRead(commandSize, req.pos);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = checkFpgaActionReply(req.pos, req.length);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
bytesUploaded += req.length;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
ReturnValue_t decResult = RETURN_OK;
|
||||||
|
size_t receivedDataLen = 0;
|
||||||
|
uint8_t* receivedData = nullptr;
|
||||||
|
size_t bytesLeft = 0;
|
||||||
|
uint32_t missedReplies = 0;
|
||||||
|
datalinkLayer.encodeFrame(commandBuffer, size);
|
||||||
|
result = uartComIF->sendMessage(comCookie, datalinkLayer.getEncodedFrame(),
|
||||||
|
datalinkLayer.getEncodedLength());
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::sendAndRead: Failed to send packet" << std::endl;
|
||||||
|
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
decResult = ArcsecDatalinkLayer::DEC_IN_PROGRESS;
|
||||||
|
while (decResult == ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
|
||||||
|
result = uartComIF->requestReceiveMessage(comCookie, StarTracker::MAX_FRAME_SIZE * 2 + 2);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::sendAndRead: Failed to request reply" << std::endl;
|
||||||
|
triggerEvent(STR_HELPER_REQUESTING_MSG_FAILED, result, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
result = uartComIF->readReceivedMessage(comCookie, &receivedData, &receivedDataLen);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::sendAndRead: Failed to read received message" << std::endl;
|
||||||
|
triggerEvent(STR_HELPER_READING_REPLY_FAILED, result, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
if (receivedDataLen == 0 && missedReplies < MAX_POLLS) {
|
||||||
|
missedReplies++;
|
||||||
|
continue;
|
||||||
|
} else if ((receivedDataLen == 0) && (missedReplies >= MAX_POLLS)) {
|
||||||
|
triggerEvent(STR_HELPER_NO_REPLY, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
} else {
|
||||||
|
missedReplies = 0;
|
||||||
|
}
|
||||||
|
decResult = datalinkLayer.decodeFrame(receivedData, receivedDataLen, &bytesLeft);
|
||||||
|
if (bytesLeft != 0) {
|
||||||
|
// This should never happen
|
||||||
|
sif::warning << "StrHelper::sendAndRead: Bytes left after decoding" << std::endl;
|
||||||
|
triggerEvent(STR_HELPER_COM_ERROR, result, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (decResult != RETURN_OK) {
|
||||||
|
triggerEvent(STR_HELPER_DEC_ERROR, decResult, parameter);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::checkActionReply() {
|
||||||
|
uint8_t type = datalinkLayer.getReplyFrameType();
|
||||||
|
if (type != TMTC_ACTIONREPLY) {
|
||||||
|
sif::warning << "StrHelper::checkActionReply: Received reply with invalid type ID" << std::endl;
|
||||||
|
return INVALID_TYPE_ID;
|
||||||
|
}
|
||||||
|
uint8_t status = datalinkLayer.getStatusField();
|
||||||
|
if (status != ArcsecDatalinkLayer::STATUS_OK) {
|
||||||
|
sif::warning << "StrHelper::checkActionReply: Status failure: "
|
||||||
|
<< static_cast<unsigned int>(status) << std::endl;
|
||||||
|
return STATUS_ERROR;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
|
||||||
|
uint32_t receivedPosition = 0;
|
||||||
|
std::memcpy(&receivedPosition, datalinkLayer.getReply() + POS_OFFSET, sizeof(receivedPosition));
|
||||||
|
if (receivedPosition != expectedPosition) {
|
||||||
|
triggerEvent(POSITION_MISMATCH, receivedPosition);
|
||||||
|
return RETURN_FAILED;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::checkFlashActionReply(uint8_t region_, uint32_t address_,
|
||||||
|
uint16_t length_) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
const uint8_t* data = datalinkLayer.getReply();
|
||||||
|
uint8_t region = *(data + REGION_OFFSET);
|
||||||
|
uint32_t address;
|
||||||
|
const uint8_t* addressData = data + ADDRESS_OFFSET;
|
||||||
|
size_t size = sizeof(address);
|
||||||
|
result =
|
||||||
|
SerializeAdapter::deSerialize(&address, &addressData, &size, SerializeIF::Endianness::LITTLE);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::checkFlashActionReply: Deserialization of address failed"
|
||||||
|
<< std::endl;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint16_t length = 0;
|
||||||
|
size = sizeof(length);
|
||||||
|
const uint8_t* lengthData = data + LENGTH_OFFSET;
|
||||||
|
result =
|
||||||
|
SerializeAdapter::deSerialize(&length, lengthData, &size, SerializeIF::Endianness::LITTLE);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::checkFlashActionReply: Deserialization of length failed"
|
||||||
|
<< std::endl;
|
||||||
|
}
|
||||||
|
if (region != region_) {
|
||||||
|
return REGION_MISMATCH;
|
||||||
|
}
|
||||||
|
if (address != address_) {
|
||||||
|
return ADDRESS_MISMATCH;
|
||||||
|
}
|
||||||
|
if (length != length_) {
|
||||||
|
return LENGTH_MISMATCH;
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::checkFpgaActionReply(uint32_t expectedPosition, uint32_t expectedLength) {
|
||||||
|
ReturnValue_t result = RETURN_OK;
|
||||||
|
result = checkActionReply();
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
const uint8_t* data = datalinkLayer.getReply() + ACTION_DATA_OFFSET;
|
||||||
|
uint32_t position;
|
||||||
|
size_t size = sizeof(position);
|
||||||
|
result = SerializeAdapter::deSerialize(&position, &data, &size, SerializeIF::Endianness::LITTLE);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::checkFpgaActionReply: Deserialization of position failed"
|
||||||
|
<< std::endl;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
uint32_t length;
|
||||||
|
size = sizeof(length);
|
||||||
|
result = SerializeAdapter::deSerialize(&length, &data, &size, SerializeIF::Endianness::LITTLE);
|
||||||
|
if (result != RETURN_OK) {
|
||||||
|
sif::warning << "StrHelper::checkFpgaActionReply: Deserialization of length failed"
|
||||||
|
<< std::endl;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
ReturnValue_t StrHelper::checkPath(std::string name) {
|
||||||
|
if (name.substr(0, sizeof(SdCardManager::SD_0_MOUNT_POINT)) ==
|
||||||
|
std::string(SdCardManager::SD_0_MOUNT_POINT)) {
|
||||||
|
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
|
||||||
|
sif::warning << "StrHelper::checkPath: SD card 0 not mounted" << std::endl;
|
||||||
|
return SD_NOT_MOUNTED;
|
||||||
|
}
|
||||||
|
} else if (name.substr(0, sizeof(SdCardManager::SD_1_MOUNT_POINT)) ==
|
||||||
|
std::string(SdCardManager::SD_1_MOUNT_POINT)) {
|
||||||
|
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
|
||||||
|
sif::warning << "StrHelper::checkPath: SD card 1 not mounted" << std::endl;
|
||||||
|
return SD_NOT_MOUNTED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
397
bsp_q7s/devices/startracker/StrHelper.h
Normal file
397
bsp_q7s/devices/startracker/StrHelper.h
Normal file
@ -0,0 +1,397 @@
|
|||||||
|
#ifndef BSP_Q7S_DEVICES_STRHELPER_H_
|
||||||
|
#define BSP_Q7S_DEVICES_STRHELPER_H_
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "ArcsecDatalinkLayer.h"
|
||||||
|
#include "bsp_q7s/memory/SdCardManager.h"
|
||||||
|
#include "fsfw/devicehandlers/CookieIF.h"
|
||||||
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
|
#include "fsfw/osal/linux/BinarySemaphore.h"
|
||||||
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
#include "fsfw/tasks/ExecutableObjectIF.h"
|
||||||
|
#include "fsfw_hal/linux/uart/UartComIF.h"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h"
|
||||||
|
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Helper class for the star tracker handler to accelerate large data transfers.
|
||||||
|
*/
|
||||||
|
class StrHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF {
|
||||||
|
public:
|
||||||
|
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HELPER;
|
||||||
|
|
||||||
|
//! [EXPORT] : [COMMENT] Image upload failed
|
||||||
|
static const Event IMAGE_UPLOAD_FAILED = MAKE_EVENT(0, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Image download failed
|
||||||
|
static const Event IMAGE_DOWNLOAD_FAILED = MAKE_EVENT(1, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Uploading image to star tracker was successfulop
|
||||||
|
static const Event IMAGE_UPLOAD_SUCCESSFUL = MAKE_EVENT(2, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Image download was successful
|
||||||
|
static const Event IMAGE_DOWNLOAD_SUCCESSFUL = MAKE_EVENT(3, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Finished flash write procedure successfully
|
||||||
|
static const Event FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(4, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Finished flash read procedure successfully
|
||||||
|
static const Event FLASH_READ_SUCCESSFUL = MAKE_EVENT(5, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Flash write procedure failed
|
||||||
|
static const Event FLASH_WRITE_FAILED = MAKE_EVENT(6, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Flash read procedure failed
|
||||||
|
static const Event FLASH_READ_FAILED = MAKE_EVENT(7, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Download of FPGA image successful
|
||||||
|
static const Event FPGA_DOWNLOAD_SUCCESSFUL = MAKE_EVENT(8, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Download of FPGA image failed
|
||||||
|
static const Event FPGA_DOWNLOAD_FAILED = MAKE_EVENT(9, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Upload of FPGA image successful
|
||||||
|
static const Event FPGA_UPLOAD_SUCCESSFUL = MAKE_EVENT(10, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Upload of FPGA image failed
|
||||||
|
static const Event FPGA_UPLOAD_FAILED = MAKE_EVENT(11, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Failed to read communication interface reply data
|
||||||
|
//! P1: Return code of failed communication interface read call
|
||||||
|
//! P1: Upload/download position for which the read call failed
|
||||||
|
static const Event STR_HELPER_READING_REPLY_FAILED = MAKE_EVENT(12, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Unexpected stop of decoding sequence
|
||||||
|
//! P1: Return code of failed communication interface read call
|
||||||
|
//! P1: Upload/download position for which the read call failed
|
||||||
|
static const Event STR_HELPER_COM_ERROR = MAKE_EVENT(13, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Star tracker did not send replies (maybe device is powered off)
|
||||||
|
//! P1: Position of upload or download packet for which no reply was sent
|
||||||
|
static const Event STR_HELPER_NO_REPLY = MAKE_EVENT(14, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Error during decoding of received reply occurred
|
||||||
|
// P1: Return value of decoding function
|
||||||
|
// P2: Position of upload/download packet, or address of flash write/read request
|
||||||
|
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(15, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Position mismatch
|
||||||
|
//! P1: The expected position and thus the position for which the image upload/download failed
|
||||||
|
static const Event POSITION_MISMATCH = MAKE_EVENT(16, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Specified file does not exist
|
||||||
|
//! P1: Internal state of str helper
|
||||||
|
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(17, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Sending packet to star tracker failed
|
||||||
|
//! P1: Return code of communication interface sendMessage function
|
||||||
|
//! P2: Position of upload/download packet, or address of flash write/read request for which
|
||||||
|
//! sending failed
|
||||||
|
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(18, severity::LOW);
|
||||||
|
//! [EXPORT] : [COMMENT] Communication interface requesting reply failed
|
||||||
|
//! P1: Return code of failed request
|
||||||
|
//! P1: Upload/download position, or address of flash write/read request for which transmission
|
||||||
|
//! failed
|
||||||
|
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(19, severity::LOW);
|
||||||
|
|
||||||
|
StrHelper(object_id_t objectId);
|
||||||
|
virtual ~StrHelper();
|
||||||
|
|
||||||
|
ReturnValue_t initialize() override;
|
||||||
|
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
|
||||||
|
|
||||||
|
ReturnValue_t setComIF(DeviceCommunicationIF* communicationInterface_);
|
||||||
|
void setComCookie(CookieIF* comCookie_);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts sequence to upload image to star tracker
|
||||||
|
*
|
||||||
|
* @param uploadImage_ Name including absolute path of the image to upload. Must be previously
|
||||||
|
* transferred to the OBC with the CFDP protocol.
|
||||||
|
*/
|
||||||
|
ReturnValue_t startImageUpload(std::string uploadImage_);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Calling this function initiates the download of an image from the star tracker.
|
||||||
|
*
|
||||||
|
* @param path Path where downloaded image will be stored
|
||||||
|
*/
|
||||||
|
ReturnValue_t startImageDownload(std::string path);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts the flash write procedure
|
||||||
|
*
|
||||||
|
* @param fullname Full name including absolute path of file to write to flash
|
||||||
|
* @param region Region ID of flash region to write to
|
||||||
|
* @param address Start address of flash write procedure
|
||||||
|
*/
|
||||||
|
ReturnValue_t startFlashWrite(std::string fullname, uint8_t region, uint32_t address);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts the flash read procedure
|
||||||
|
*
|
||||||
|
* @param path Path where file with read flash data will be created
|
||||||
|
* @param region Region ID of flash region to read from
|
||||||
|
* @param address Start address of flash section to read
|
||||||
|
* @param length Number of bytes to read from flash
|
||||||
|
*/
|
||||||
|
ReturnValue_t startFlashRead(std::string path, uint8_t region, uint32_t address, uint32_t length);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts the download of the FPGA image
|
||||||
|
*
|
||||||
|
* @param path The path where the file with the downloaded data will be created
|
||||||
|
* @param startPosition Offset in fpga image to read from
|
||||||
|
* @param length Number of bytes to dwonload from the FPGA image
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
ReturnValue_t startFpgaDownload(std::string path, uint32_t startPosition, uint32_t length);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Starts upload of new image to FPGA
|
||||||
|
*
|
||||||
|
* @param uploadFile Full name of file containing FPGA image data
|
||||||
|
*/
|
||||||
|
ReturnValue_t startFpgaUpload(std::string uploadFile);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Can be used to interrupt a running data transfer.
|
||||||
|
*/
|
||||||
|
void stopProcess();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Changes the dafault name of downloaded images
|
||||||
|
*/
|
||||||
|
void setDownloadImageName(std::string filename);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Sets the name of the file which will be created to store the data read from flash
|
||||||
|
*/
|
||||||
|
void setFlashReadFilename(std::string filename);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Set download FPGA image name
|
||||||
|
*/
|
||||||
|
void setDownloadFpgaImage(std::string filename);
|
||||||
|
|
||||||
|
private:
|
||||||
|
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
|
||||||
|
|
||||||
|
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
|
||||||
|
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA0);
|
||||||
|
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
|
||||||
|
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1);
|
||||||
|
//! [EXPORT] : [COMMENT] Specified path does not exist
|
||||||
|
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2);
|
||||||
|
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
|
||||||
|
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(0xA3);
|
||||||
|
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
|
||||||
|
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xA4);
|
||||||
|
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
|
||||||
|
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xA5);
|
||||||
|
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
|
||||||
|
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(0xA6);
|
||||||
|
//! [EXPORT] : [COMMENT] Status field in reply signals error
|
||||||
|
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(0xA7);
|
||||||
|
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
|
||||||
|
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(0xA8);
|
||||||
|
|
||||||
|
// Size of one image part which can be sent per action request
|
||||||
|
static const size_t SIZE_IMAGE_PART = 1024;
|
||||||
|
|
||||||
|
class ImageDownload {
|
||||||
|
public:
|
||||||
|
static const uint32_t LAST_POSITION = 4095;
|
||||||
|
};
|
||||||
|
|
||||||
|
class FpgaDownload {
|
||||||
|
public:
|
||||||
|
static const uint16_t MAX_DATA = 1024;
|
||||||
|
static const uint8_t DATA_OFFSET = 10;
|
||||||
|
// Start position of fpga image part to download
|
||||||
|
uint32_t startPosition = 0;
|
||||||
|
// Length of image part to download
|
||||||
|
uint32_t length = 0;
|
||||||
|
// Path where downloaded FPGA image will be stored
|
||||||
|
std::string path;
|
||||||
|
// Name of file containing downloaded FPGA image
|
||||||
|
std::string fileName = "fpgaimage.bin";
|
||||||
|
};
|
||||||
|
FpgaDownload fpgaDownload;
|
||||||
|
|
||||||
|
class FpgaUpload {
|
||||||
|
public:
|
||||||
|
static const uint32_t MAX_DATA = 1024;
|
||||||
|
// Full name of file to upload
|
||||||
|
std::string uploadFile;
|
||||||
|
};
|
||||||
|
FpgaUpload fpgaUpload;
|
||||||
|
|
||||||
|
static const uint32_t MAX_POLLS = 10000;
|
||||||
|
|
||||||
|
static const uint8_t ACTION_DATA_OFFSET = 2;
|
||||||
|
static const uint8_t POS_OFFSET = 2;
|
||||||
|
static const uint8_t IMAGE_DATA_OFFSET = 5;
|
||||||
|
static const uint8_t FLASH_READ_DATA_OFFSET = 8;
|
||||||
|
static const uint8_t REGION_OFFSET = 2;
|
||||||
|
static const uint8_t ADDRESS_OFFSET = 3;
|
||||||
|
static const uint8_t LENGTH_OFFSET = 7;
|
||||||
|
static const size_t IMAGE_DATA_SIZE = 1024;
|
||||||
|
static const size_t MAX_FLASH_DATA = 1024;
|
||||||
|
static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3;
|
||||||
|
|
||||||
|
enum class InternalState {
|
||||||
|
IDLE,
|
||||||
|
UPLOAD_IMAGE,
|
||||||
|
DOWNLOAD_IMAGE,
|
||||||
|
FLASH_WRITE,
|
||||||
|
FLASH_READ,
|
||||||
|
DOWNLOAD_FPGA_IMAGE,
|
||||||
|
UPLOAD_FPGA_IMAGE
|
||||||
|
};
|
||||||
|
|
||||||
|
InternalState internalState = InternalState::IDLE;
|
||||||
|
|
||||||
|
ArcsecDatalinkLayer datalinkLayer;
|
||||||
|
|
||||||
|
BinarySemaphore semaphore;
|
||||||
|
|
||||||
|
class UploadImage {
|
||||||
|
public:
|
||||||
|
// Name including absolute path of image to upload
|
||||||
|
std::string uploadFile;
|
||||||
|
};
|
||||||
|
UploadImage uploadImage;
|
||||||
|
|
||||||
|
class DownloadImage {
|
||||||
|
public:
|
||||||
|
// Path where the downloaded image will be stored
|
||||||
|
std::string path;
|
||||||
|
// Default name of downloaded image, can be changed via command
|
||||||
|
std::string filename = "image.bin";
|
||||||
|
};
|
||||||
|
DownloadImage downloadImage;
|
||||||
|
|
||||||
|
class FlashWrite {
|
||||||
|
public:
|
||||||
|
// File which contains data to write when executing the flash write command
|
||||||
|
std::string fullname;
|
||||||
|
// Will be set with the flash write command
|
||||||
|
uint8_t region = 0;
|
||||||
|
// Will be set with the flash write command and specifies the start address where to write the
|
||||||
|
// flash data to
|
||||||
|
uint32_t address = 0;
|
||||||
|
};
|
||||||
|
FlashWrite flashWrite;
|
||||||
|
|
||||||
|
class FlashRead {
|
||||||
|
public:
|
||||||
|
// Path where the file containing the read data will be stored
|
||||||
|
std::string path = "";
|
||||||
|
// Default name of file containing the data read from flash, can be changed via command
|
||||||
|
std::string filename = "flashread.bin";
|
||||||
|
// Will be set with the flash read command
|
||||||
|
uint8_t region = 0;
|
||||||
|
// Will be set with the flash read command and specifies the start address of the flash section
|
||||||
|
// to read
|
||||||
|
uint32_t address = 0;
|
||||||
|
// Number of bytes to read from flash
|
||||||
|
uint32_t size = 0;
|
||||||
|
};
|
||||||
|
FlashRead flashRead;
|
||||||
|
|
||||||
|
SdCardManager* sdcMan = nullptr;
|
||||||
|
|
||||||
|
uint8_t commandBuffer[StarTracker::MAX_FRAME_SIZE];
|
||||||
|
|
||||||
|
bool terminate = false;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* UART communication object responsible for low level access of star tracker
|
||||||
|
* Must be set by star tracker handler
|
||||||
|
*/
|
||||||
|
UartComIF* uartComIF = nullptr;
|
||||||
|
// Communication cookie. Must be set by the star tracker handler
|
||||||
|
CookieIF* comCookie = nullptr;
|
||||||
|
|
||||||
|
// Queue id of raw data receiver
|
||||||
|
MessageQueueId_t rawDataReceiver = MessageQueueIF::NO_QUEUE;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Performs image uploading
|
||||||
|
*/
|
||||||
|
ReturnValue_t performImageUpload();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Performs download of last taken image from the star tracker.
|
||||||
|
*
|
||||||
|
* @details Download is split over multiple packets transporting each a maximum of 1024 bytes.
|
||||||
|
* In case the download of one position fails, the same packet will be again
|
||||||
|
* requested. If the download of the packet fails CONFIG_MAX_DOWNLOAD_RETRIES times,
|
||||||
|
* the download will be stopped.
|
||||||
|
*/
|
||||||
|
ReturnValue_t performImageDownload();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Handles flash write procedure
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if successful, otherwise RETURN_FAILED
|
||||||
|
*/
|
||||||
|
ReturnValue_t performFlashWrite();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Sends a sequence of commands to the star tracker to read larger parts from the
|
||||||
|
* flash memory.
|
||||||
|
*/
|
||||||
|
ReturnValue_t performFlashRead();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Performs the download of the FPGA image which requires to be slip over multiple
|
||||||
|
* action requests.
|
||||||
|
*/
|
||||||
|
ReturnValue_t performFpgaDownload();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Performs upload of new FPGA image. Upload sequence split over multiple commands
|
||||||
|
* because one command can only transport 1024 bytes of image data.
|
||||||
|
*/
|
||||||
|
ReturnValue_t performFpgaUpload();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Sends packet to the star tracker and reads reply by using the communication
|
||||||
|
* interface
|
||||||
|
*
|
||||||
|
* @param size Size of data beforehand written to the commandBuffer
|
||||||
|
* @param parameter Parameter 2 of trigger event function
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if successful, otherwise RETURN_FAILED
|
||||||
|
*/
|
||||||
|
ReturnValue_t sendAndRead(size_t size, uint32_t parameter);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks the header (type id and status fields) of the action reply
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if reply confirms success of packet transfer, otherwise REUTRN_FAILED
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkActionReply();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks the position field in a star tracker upload/download reply.
|
||||||
|
*
|
||||||
|
* @param expectedPosition Value of expected position
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if received position matches expected position, otherwise RETURN_FAILED
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkReplyPosition(uint32_t expectedPosition);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks the region, address and length value of a flash write or read reply.
|
||||||
|
*
|
||||||
|
* @return RETURN_OK if values match expected values, otherwise appropriate error return
|
||||||
|
* value.
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkFlashActionReply(uint8_t region_, uint32_t address_, uint16_t length_);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks the reply to the fpga download and upload request
|
||||||
|
*
|
||||||
|
* @param expectedPosition The expected position value in the reply
|
||||||
|
* @param expectedLength The expected length field in the reply
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkFpgaActionReply(uint32_t expectedPosition, uint32_t expectedLength);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Checks if a path points to an sd card and whether the SD card is monuted.
|
||||||
|
*
|
||||||
|
* @return SD_NOT_MOUNTED id SD card is not mounted, otherwise RETURN_OK
|
||||||
|
*/
|
||||||
|
ReturnValue_t checkPath(std::string name);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */
|
@ -1,18 +1,17 @@
|
|||||||
#include "gpioCallbacks.h"
|
#include "gpioCallbacks.h"
|
||||||
#include "busConf.h"
|
|
||||||
#include <devices/gpioIds.h>
|
#include <devices/gpioIds.h>
|
||||||
|
|
||||||
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
|
||||||
#include <fsfw_hal/common/gpio/GpioCookie.h>
|
|
||||||
#include <fsfw/serviceinterface/ServiceInterface.h>
|
#include <fsfw/serviceinterface/ServiceInterface.h>
|
||||||
|
#include <fsfw_hal/common/gpio/GpioCookie.h>
|
||||||
|
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
|
||||||
|
|
||||||
|
#include "busConf.h"
|
||||||
|
|
||||||
namespace gpioCallbacks {
|
namespace gpioCallbacks {
|
||||||
|
|
||||||
GpioIF* gpioComInterface;
|
GpioIF* gpioComInterface;
|
||||||
|
|
||||||
void initSpiCsDecoder(GpioIF* gpioComIF) {
|
void initSpiCsDecoder(GpioIF* gpioComIF) {
|
||||||
|
|
||||||
ReturnValue_t result;
|
ReturnValue_t result;
|
||||||
|
|
||||||
if (gpioComIF == nullptr) {
|
if (gpioComIF == nullptr) {
|
||||||
@ -38,15 +37,15 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
|
|||||||
gpio::DIR_OUT, gpio::LOW);
|
gpio::DIR_OUT, gpio::LOW);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit);
|
||||||
|
|
||||||
// spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_1_PIN, "SPI Mux Bit 1",
|
// spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_1_PIN, "SPI Mux Bit 1",
|
||||||
// gpio::OUT, gpio::LOW);
|
// gpio::OUT, gpio::LOW);
|
||||||
// spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit);
|
// spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_1, spiMuxBit);
|
||||||
// /** Setting mux bit 2 to low disables IC1 on the TCS board */
|
// /** Setting mux bit 2 to low disables IC1 on the TCS board */
|
||||||
// spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_2_PIN, "SPI Mux Bit 2", gpio::OUT, gpio::HIGH);
|
// spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_2_PIN, "SPI Mux Bit 2",
|
||||||
// spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit);
|
// gpio::OUT, gpio::HIGH); spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_2, spiMuxBit);
|
||||||
// /** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board */
|
// /** Setting mux bit 3 to low disables IC2 on the TCS board and IC22 on the interface board
|
||||||
// spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_3_PIN, "SPI Mux Bit 3", gpio::OUT, gpio::LOW);
|
// */ spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_3_PIN, "SPI Mux Bit
|
||||||
// spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit);
|
// 3", gpio::OUT, gpio::LOW); spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_3, spiMuxBit);
|
||||||
|
|
||||||
/** The following gpios can take arbitrary initial values */
|
/** The following gpios can take arbitrary initial values */
|
||||||
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_4_PIN, "SPI Mux Bit 4",
|
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_4_PIN, "SPI Mux Bit 4",
|
||||||
@ -58,8 +57,8 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
|
|||||||
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_6_PIN, "SPI Mux Bit 6",
|
spiMuxBit = new GpiodRegularByLineName(q7s::gpioNames::SPI_MUX_BIT_6_PIN, "SPI Mux Bit 6",
|
||||||
gpio::DIR_OUT, gpio::LOW);
|
gpio::DIR_OUT, gpio::LOW);
|
||||||
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit);
|
spiMuxGpios->addGpio(gpioIds::SPI_MUX_BIT_6, spiMuxBit);
|
||||||
GpiodRegularByLineName* enRwDecoder = new GpiodRegularByLineName(q7s::gpioNames::EN_RW_CS,
|
GpiodRegularByLineName* enRwDecoder =
|
||||||
"EN_RW_CS", gpio::DIR_OUT, gpio::HIGH);
|
new GpiodRegularByLineName(q7s::gpioNames::EN_RW_CS, "EN_RW_CS", gpio::DIR_OUT, gpio::HIGH);
|
||||||
spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder);
|
spiMuxGpios->addGpio(gpioIds::EN_RW_CS, enRwDecoder);
|
||||||
|
|
||||||
result = gpioComInterface->addGpios(spiMuxGpios);
|
result = gpioComInterface->addGpios(spiMuxGpios);
|
||||||
@ -71,7 +70,6 @@ void initSpiCsDecoder(GpioIF* gpioComIF) {
|
|||||||
|
|
||||||
void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value,
|
void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value,
|
||||||
void* args) {
|
void* args) {
|
||||||
|
|
||||||
if (gpioComInterface == nullptr) {
|
if (gpioComInterface == nullptr) {
|
||||||
sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder "
|
sif::debug << "spiCsDecoderCallback: No gpioComIF specified. Call initSpiCsDecoder "
|
||||||
<< "to specify gpioComIF" << std::endl;
|
<< "to specify gpioComIF" << std::endl;
|
||||||
@ -85,305 +83,304 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Lev
|
|||||||
|
|
||||||
if (value == gpio::HIGH) {
|
if (value == gpio::HIGH) {
|
||||||
switch (gpioId) {
|
switch (gpioId) {
|
||||||
case(gpioIds::RTD_IC_3): {
|
case (gpioIds::RTD_IC_3): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_4): {
|
case (gpioIds::RTD_IC_4): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_5): {
|
case (gpioIds::RTD_IC_5): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_6): {
|
case (gpioIds::RTD_IC_6): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_7): {
|
case (gpioIds::RTD_IC_7): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_8): {
|
case (gpioIds::RTD_IC_8): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_9): {
|
case (gpioIds::RTD_IC_9): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_10): {
|
case (gpioIds::RTD_IC_10): {
|
||||||
disableDecoderTcsIc1();
|
disableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_11): {
|
case (gpioIds::RTD_IC_11): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_12): {
|
case (gpioIds::RTD_IC_12): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_13): {
|
case (gpioIds::RTD_IC_13): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_14): {
|
case (gpioIds::RTD_IC_14): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_15): {
|
case (gpioIds::RTD_IC_15): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_16): {
|
case (gpioIds::RTD_IC_16): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_17): {
|
case (gpioIds::RTD_IC_17): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_18): {
|
case (gpioIds::RTD_IC_18): {
|
||||||
disableDecoderTcsIc2();
|
disableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_1): {
|
case (gpioIds::CS_SUS_1): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_2): {
|
case (gpioIds::CS_SUS_2): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_3): {
|
case (gpioIds::CS_SUS_3): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_4): {
|
case (gpioIds::CS_SUS_4): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_5): {
|
case (gpioIds::CS_SUS_5): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_6): {
|
case (gpioIds::CS_SUS_6): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_7): {
|
case (gpioIds::CS_SUS_7): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_8): {
|
case (gpioIds::CS_SUS_8): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_9): {
|
case (gpioIds::CS_SUS_9): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_10): {
|
case (gpioIds::CS_SUS_10): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_11): {
|
case (gpioIds::CS_SUS_11): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_12): {
|
case (gpioIds::CS_SUS_12): {
|
||||||
disableDecoderInterfaceBoardIc2();
|
disableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_13): {
|
case (gpioIds::CS_SUS_13): {
|
||||||
disableDecoderInterfaceBoardIc1();
|
disableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW1): {
|
case (gpioIds::CS_RW1): {
|
||||||
disableRwDecoder();
|
disableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW2): {
|
case (gpioIds::CS_RW2): {
|
||||||
disableRwDecoder();
|
disableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW3): {
|
case (gpioIds::CS_RW3): {
|
||||||
disableRwDecoder();
|
disableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW4): {
|
case (gpioIds::CS_RW4): {
|
||||||
disableRwDecoder();
|
disableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
|
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
|
||||||
}
|
}
|
||||||
}
|
} else if (value == gpio::LOW) {
|
||||||
else if (value == gpio::LOW) {
|
|
||||||
switch (gpioId) {
|
switch (gpioId) {
|
||||||
case(gpioIds::RTD_IC_3): {
|
case (gpioIds::RTD_IC_3): {
|
||||||
selectY7();
|
selectY7();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_4): {
|
case (gpioIds::RTD_IC_4): {
|
||||||
selectY6();
|
selectY6();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_5): {
|
case (gpioIds::RTD_IC_5): {
|
||||||
selectY5();
|
selectY5();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_6): {
|
case (gpioIds::RTD_IC_6): {
|
||||||
selectY4();
|
selectY4();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_7): {
|
case (gpioIds::RTD_IC_7): {
|
||||||
selectY3();
|
selectY3();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_8): {
|
case (gpioIds::RTD_IC_8): {
|
||||||
selectY2();
|
selectY2();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_9): {
|
case (gpioIds::RTD_IC_9): {
|
||||||
selectY1();
|
selectY1();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_10): {
|
case (gpioIds::RTD_IC_10): {
|
||||||
selectY0();
|
selectY0();
|
||||||
enableDecoderTcsIc1();
|
enableDecoderTcsIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_11): {
|
case (gpioIds::RTD_IC_11): {
|
||||||
selectY7();
|
selectY7();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_12): {
|
case (gpioIds::RTD_IC_12): {
|
||||||
selectY6();
|
selectY6();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_13): {
|
case (gpioIds::RTD_IC_13): {
|
||||||
selectY5();
|
selectY5();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_14): {
|
case (gpioIds::RTD_IC_14): {
|
||||||
selectY4();
|
selectY4();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_15): {
|
case (gpioIds::RTD_IC_15): {
|
||||||
selectY3();
|
selectY3();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_16): {
|
case (gpioIds::RTD_IC_16): {
|
||||||
selectY2();
|
selectY2();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_17): {
|
case (gpioIds::RTD_IC_17): {
|
||||||
selectY1();
|
selectY1();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::RTD_IC_18): {
|
case (gpioIds::RTD_IC_18): {
|
||||||
selectY0();
|
selectY0();
|
||||||
enableDecoderTcsIc2();
|
enableDecoderTcsIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_1): {
|
case (gpioIds::CS_SUS_1): {
|
||||||
selectY0();
|
selectY0();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_2): {
|
case (gpioIds::CS_SUS_2): {
|
||||||
selectY1();
|
selectY1();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_3): {
|
case (gpioIds::CS_SUS_3): {
|
||||||
selectY0();
|
selectY0();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_4): {
|
case (gpioIds::CS_SUS_4): {
|
||||||
selectY1();
|
selectY1();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_5): {
|
case (gpioIds::CS_SUS_5): {
|
||||||
selectY2();
|
selectY2();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_6): {
|
case (gpioIds::CS_SUS_6): {
|
||||||
selectY2();
|
selectY2();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_7): {
|
case (gpioIds::CS_SUS_7): {
|
||||||
selectY3();
|
selectY3();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_8): {
|
case (gpioIds::CS_SUS_8): {
|
||||||
selectY3();
|
selectY3();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_9): {
|
case (gpioIds::CS_SUS_9): {
|
||||||
selectY4();
|
selectY4();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_10): {
|
case (gpioIds::CS_SUS_10): {
|
||||||
selectY5();
|
selectY5();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_11): {
|
case (gpioIds::CS_SUS_11): {
|
||||||
selectY4();
|
selectY4();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_12): {
|
case (gpioIds::CS_SUS_12): {
|
||||||
selectY5();
|
selectY5();
|
||||||
enableDecoderInterfaceBoardIc2();
|
enableDecoderInterfaceBoardIc2();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_SUS_13): {
|
case (gpioIds::CS_SUS_13): {
|
||||||
selectY6();
|
selectY6();
|
||||||
enableDecoderInterfaceBoardIc1();
|
enableDecoderInterfaceBoardIc1();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW1): {
|
case (gpioIds::CS_RW1): {
|
||||||
selectY0();
|
selectY0();
|
||||||
enableRwDecoder();
|
enableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW2): {
|
case (gpioIds::CS_RW2): {
|
||||||
selectY1();
|
selectY1();
|
||||||
enableRwDecoder();
|
enableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW3): {
|
case (gpioIds::CS_RW3): {
|
||||||
selectY2();
|
selectY2();
|
||||||
enableRwDecoder();
|
enableRwDecoder();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(gpioIds::CS_RW4): {
|
case (gpioIds::CS_RW4): {
|
||||||
selectY3();
|
selectY3();
|
||||||
enableRwDecoder();
|
enableRwDecoder();
|
||||||
break;
|
break;
|
||||||
@ -391,8 +388,7 @@ void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Lev
|
|||||||
default:
|
default:
|
||||||
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
|
sif::debug << "spiCsDecoderCallback: Invalid gpio id " << gpioId << std::endl;
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::debug << "spiCsDecoderCallback: Invalid value. Must be 0 or 1" << std::endl;
|
sif::debug << "spiCsDecoderCallback: Invalid value. Must be 0 or 1" << std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -446,13 +442,9 @@ void disableDecoderInterfaceBoardIc2() {
|
|||||||
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3);
|
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_3);
|
||||||
}
|
}
|
||||||
|
|
||||||
void enableRwDecoder() {
|
void enableRwDecoder() { gpioComInterface->pullHigh(gpioIds::EN_RW_CS); }
|
||||||
gpioComInterface->pullHigh(gpioIds::EN_RW_CS);
|
|
||||||
}
|
|
||||||
|
|
||||||
void disableRwDecoder() {
|
void disableRwDecoder() { gpioComInterface->pullLow(gpioIds::EN_RW_CS); }
|
||||||
gpioComInterface->pullLow(gpioIds::EN_RW_CS);
|
|
||||||
}
|
|
||||||
|
|
||||||
void selectY0() {
|
void selectY0() {
|
||||||
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4);
|
gpioComInterface->pullLow(gpioIds::SPI_MUX_BIT_4);
|
||||||
@ -509,4 +501,4 @@ void disableAllDecoder() {
|
|||||||
gpioComInterface->pullLow(gpioIds::EN_RW_CS);
|
gpioComInterface->pullLow(gpioIds::EN_RW_CS);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
} // namespace gpioCallbacks
|
||||||
|
@ -1,74 +1,73 @@
|
|||||||
#ifndef LINUX_GPIO_GPIOCALLBACKS_H_
|
#ifndef LINUX_GPIO_GPIOCALLBACKS_H_
|
||||||
#define LINUX_GPIO_GPIOCALLBACKS_H_
|
#define LINUX_GPIO_GPIOCALLBACKS_H_
|
||||||
|
|
||||||
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
|
|
||||||
#include <fsfw_hal/common/gpio/GpioIF.h>
|
#include <fsfw_hal/common/gpio/GpioIF.h>
|
||||||
|
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
|
||||||
|
|
||||||
namespace gpioCallbacks {
|
namespace gpioCallbacks {
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on
|
* @brief This function initializes the GPIOs used to control the SN74LVC138APWR decoders on
|
||||||
* the TCS Board and the interface board.
|
* the TCS Board and the interface board.
|
||||||
*/
|
*/
|
||||||
void initSpiCsDecoder(GpioIF* gpioComIF);
|
void initSpiCsDecoder(GpioIF* gpioComIF);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function implements the decoding to multiply gpios by using the decoder
|
* @brief This function implements the decoding to multiply gpios by using the decoder
|
||||||
* chips SN74LVC138APWR on the TCS board and the interface board.
|
* chips SN74LVC138APWR on the TCS board and the interface board.
|
||||||
*/
|
*/
|
||||||
void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp,
|
void spiCsDecoderCallback(gpioId_t gpioId, gpio::GpioOperation gpioOp, gpio::Levels value,
|
||||||
gpio::Levels value, void* args);
|
void* args);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
||||||
* on the TCS board which is named to IC1 in the schematic.
|
* on the TCS board which is named to IC1 in the schematic.
|
||||||
*/
|
*/
|
||||||
void enableDecoderTcsIc1();
|
void enableDecoderTcsIc1();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
||||||
* on the TCS board which is named to IC2 in the schematic.
|
* on the TCS board which is named to IC2 in the schematic.
|
||||||
*/
|
*/
|
||||||
void enableDecoderTcsIc2();
|
void enableDecoderTcsIc2();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
||||||
* on the inteface board board which is named to IC21 in the schematic.
|
* on the inteface board board which is named to IC21 in the schematic.
|
||||||
*/
|
*/
|
||||||
void enableDecoderInterfaceBoardIc1();
|
void enableDecoderInterfaceBoardIc1();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
* @brief This function sets mux bits 1-3 to a state which will only enable the decoder
|
||||||
* on the inteface board board which is named to IC22 in the schematic.
|
* on the inteface board board which is named to IC22 in the schematic.
|
||||||
*/
|
*/
|
||||||
void enableDecoderInterfaceBoardIc2();
|
void enableDecoderInterfaceBoardIc2();
|
||||||
|
|
||||||
void disableDecoderTcsIc1();
|
void disableDecoderTcsIc1();
|
||||||
void disableDecoderTcsIc2();
|
void disableDecoderTcsIc2();
|
||||||
void disableDecoderInterfaceBoardIc1();
|
void disableDecoderInterfaceBoardIc1();
|
||||||
void disableDecoderInterfaceBoardIc2();
|
void disableDecoderInterfaceBoardIc2();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief Enables the reaction wheel chip select decoder (IC3).
|
* @brief Enables the reaction wheel chip select decoder (IC3).
|
||||||
*/
|
*/
|
||||||
void enableRwDecoder();
|
void enableRwDecoder();
|
||||||
void disableRwDecoder();
|
void disableRwDecoder();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function disables all decoder.
|
* @brief This function disables all decoder.
|
||||||
*/
|
*/
|
||||||
void disableAllDecoder();
|
void disableAllDecoder();
|
||||||
|
|
||||||
/** The following functions enable the appropriate channel of the currently enabled decoder */
|
/** The following functions enable the appropriate channel of the currently enabled decoder */
|
||||||
void selectY0();
|
void selectY0();
|
||||||
void selectY1();
|
void selectY1();
|
||||||
void selectY2();
|
void selectY2();
|
||||||
void selectY3();
|
void selectY3();
|
||||||
void selectY4();
|
void selectY4();
|
||||||
void selectY5();
|
void selectY5();
|
||||||
void selectY6();
|
void selectY6();
|
||||||
void selectY7();
|
void selectY7();
|
||||||
}
|
} // namespace gpioCallbacks
|
||||||
|
|
||||||
#endif /* LINUX_GPIO_GPIOCALLBACKS_H_ */
|
#endif /* LINUX_GPIO_GPIOCALLBACKS_H_ */
|
||||||
|
@ -12,8 +12,7 @@
|
|||||||
* @brief This is the main program for the target hardware.
|
* @brief This is the main program for the target hardware.
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
int main(void)
|
int main(void) {
|
||||||
{
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
#if Q7S_SIMPLE_MODE == 0
|
#if Q7S_SIMPLE_MODE == 0
|
||||||
return obsw::obsw();
|
return obsw::obsw();
|
||||||
|
@ -1,65 +1,58 @@
|
|||||||
#include "FileSystemHandler.h"
|
#include "FileSystemHandler.h"
|
||||||
|
|
||||||
#include "bsp_q7s/core/CoreController.h"
|
|
||||||
|
|
||||||
#include "fsfw/tasks/TaskFactory.h"
|
|
||||||
#include "fsfw/memory/GenericFileSystemMessage.h"
|
|
||||||
#include "fsfw/ipc/QueueFactory.h"
|
|
||||||
|
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
#include <fstream>
|
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
|
#include <fstream>
|
||||||
|
|
||||||
FileSystemHandler::FileSystemHandler(object_id_t fileSystemHandler):
|
#include "bsp_q7s/core/CoreController.h"
|
||||||
SystemObject(fileSystemHandler) {
|
#include "fsfw/ipc/QueueFactory.h"
|
||||||
|
#include "fsfw/memory/GenericFileSystemMessage.h"
|
||||||
|
#include "fsfw/tasks/TaskFactory.h"
|
||||||
|
|
||||||
|
FileSystemHandler::FileSystemHandler(object_id_t fileSystemHandler)
|
||||||
|
: SystemObject(fileSystemHandler) {
|
||||||
mq = QueueFactory::instance()->createMessageQueue(FS_MAX_QUEUE_SIZE);
|
mq = QueueFactory::instance()->createMessageQueue(FS_MAX_QUEUE_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
FileSystemHandler::~FileSystemHandler() {
|
FileSystemHandler::~FileSystemHandler() { QueueFactory::instance()->deleteMessageQueue(mq); }
|
||||||
QueueFactory::instance()->deleteMessageQueue(mq);
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::performOperation(uint8_t unsignedChar) {
|
ReturnValue_t FileSystemHandler::performOperation(uint8_t unsignedChar) {
|
||||||
while(true) {
|
while (true) {
|
||||||
try {
|
try {
|
||||||
fileSystemHandlerLoop();
|
fileSystemHandlerLoop();
|
||||||
}
|
} catch (std::bad_alloc& e) {
|
||||||
catch(std::bad_alloc& e) {
|
|
||||||
// Restart OBSW, hints at a memory leak
|
// Restart OBSW, hints at a memory leak
|
||||||
sif::error << "Allocation error in FileSystemHandler::performOperation"
|
sif::error << "Allocation error in FileSystemHandler::performOperation" << e.what()
|
||||||
<< e.what() << std::endl;
|
<< std::endl;
|
||||||
// Set up an error file or a special flag in the scratch buffer for these cases
|
// Set up an error file or a special flag in the scratch buffer for these cases
|
||||||
triggerEvent(CoreController::ALLOC_FAILURE, 0 , 0);
|
triggerEvent(CoreController::ALLOC_FAILURE, 0, 0);
|
||||||
CoreController::incrementAllocationFailureCount();
|
CoreController::incrementAllocationFailureCount();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void FileSystemHandler::fileSystemHandlerLoop() {
|
void FileSystemHandler::fileSystemHandlerLoop() {
|
||||||
CommandMessage filemsg;
|
CommandMessage filemsg;
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
while(true) {
|
while (true) {
|
||||||
if(opCounter % 5 == 0) {
|
if (opCounter % 5 == 0) {
|
||||||
if(coreCtrl->sdInitFinished()) {
|
if (coreCtrl->sdInitFinished()) {
|
||||||
fileSystemCheckup();
|
fileSystemCheckup();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
result = mq->receiveMessage(&filemsg);
|
result = mq->receiveMessage(&filemsg);
|
||||||
if(result == MessageQueueIF::EMPTY) {
|
if (result == MessageQueueIF::EMPTY) {
|
||||||
break;
|
break;
|
||||||
}
|
} else if (result != HasReturnvaluesIF::RETURN_FAILED) {
|
||||||
else if(result != HasReturnvaluesIF::RETURN_FAILED) {
|
sif::warning << "FileSystemHandler::performOperation: Message reception failed!" << std::endl;
|
||||||
sif::warning << "FileSystemHandler::performOperation: Message reception failed!"
|
|
||||||
<< std::endl;
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Command_t command = filemsg.getCommand();
|
Command_t command = filemsg.getCommand();
|
||||||
switch(command) {
|
switch (command) {
|
||||||
case(GenericFileSystemMessage::CMD_CREATE_DIRECTORY): {
|
case (GenericFileSystemMessage::CMD_CREATE_DIRECTORY): {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case(GenericFileSystemMessage::CMD_CREATE_FILE): {
|
case (GenericFileSystemMessage::CMD_CREATE_FILE): {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -78,29 +71,26 @@ void FileSystemHandler::fileSystemCheckup() {
|
|||||||
sdcMan->getSdCardActiveStatus(statusPair);
|
sdcMan->getSdCardActiveStatus(statusPair);
|
||||||
sd::SdCard preferredSdCard;
|
sd::SdCard preferredSdCard;
|
||||||
sdcMan->getPreferredSdCard(preferredSdCard);
|
sdcMan->getPreferredSdCard(preferredSdCard);
|
||||||
if((preferredSdCard == sd::SdCard::SLOT_0) and
|
if ((preferredSdCard == sd::SdCard::SLOT_0) and (statusPair.first == sd::SdState::MOUNTED)) {
|
||||||
(statusPair.first == sd::SdState::MOUNTED)) {
|
|
||||||
currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
||||||
}
|
} else if ((preferredSdCard == sd::SdCard::SLOT_1) and
|
||||||
else if((preferredSdCard == sd::SdCard::SLOT_1) and
|
|
||||||
(statusPair.second == sd::SdState::MOUNTED)) {
|
(statusPair.second == sd::SdState::MOUNTED)) {
|
||||||
currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT;
|
currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
std::string sdString;
|
std::string sdString;
|
||||||
if(preferredSdCard == sd::SdCard::SLOT_0) {
|
if (preferredSdCard == sd::SdCard::SLOT_0) {
|
||||||
sdString = "0";
|
sdString = "0";
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sdString = "1";
|
sdString = "1";
|
||||||
}
|
}
|
||||||
sif::warning << "FileSystemHandler::performOperation: "
|
sif::warning << "FileSystemHandler::performOperation: "
|
||||||
"Inconsistent state detected" << std::endl;
|
"Inconsistent state detected"
|
||||||
sif::warning << "Preferred SD card is " << sdString <<
|
<< std::endl;
|
||||||
" but does not appear to be mounted. Attempting fix.." << std::endl;
|
sif::warning << "Preferred SD card is " << sdString
|
||||||
|
<< " but does not appear to be mounted. Attempting fix.." << std::endl;
|
||||||
// This function will appear to fix the inconsistent state
|
// This function will appear to fix the inconsistent state
|
||||||
ReturnValue_t result = sdcMan->sanitizeState(&statusPair, preferredSdCard);
|
ReturnValue_t result = sdcMan->sanitizeState(&statusPair, preferredSdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
// Oh no.
|
// Oh no.
|
||||||
triggerEvent(SdCardManager::SANITIZATION_FAILED, 0, 0);
|
triggerEvent(SdCardManager::SANITIZATION_FAILED, 0, 0);
|
||||||
sif::error << "FileSystemHandler::fileSystemCheckup: Sanitization failed" << std::endl;
|
sif::error << "FileSystemHandler::fileSystemCheckup: Sanitization failed" << std::endl;
|
||||||
@ -108,81 +98,79 @@ void FileSystemHandler::fileSystemCheckup() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageQueueId_t FileSystemHandler::getCommandQueue() const {
|
MessageQueueId_t FileSystemHandler::getCommandQueue() const { return mq->getId(); }
|
||||||
return mq->getId();
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::initialize() {
|
ReturnValue_t FileSystemHandler::initialize() {
|
||||||
coreCtrl = ObjectManager::instance()->get<CoreController>(objects::CORE_CONTROLLER);
|
coreCtrl = ObjectManager::instance()->get<CoreController>(objects::CORE_CONTROLLER);
|
||||||
if(coreCtrl == nullptr) {
|
if (coreCtrl == nullptr) {
|
||||||
sif::error << "FileSystemHandler::initialize: Could not retrieve core controller handle" <<
|
sif::error << "FileSystemHandler::initialize: Could not retrieve core controller handle"
|
||||||
std::endl;
|
<< std::endl;
|
||||||
}
|
}
|
||||||
sdcMan = SdCardManager::instance();
|
sdcMan = SdCardManager::instance();
|
||||||
sd::SdCard preferredSdCard;
|
sd::SdCard preferredSdCard;
|
||||||
ReturnValue_t result = sdcMan->getPreferredSdCard(preferredSdCard);
|
ReturnValue_t result = sdcMan->getPreferredSdCard(preferredSdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if(preferredSdCard == sd::SdCard::SLOT_0) {
|
if (preferredSdCard == sd::SdCard::SLOT_0) {
|
||||||
currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
||||||
}
|
} else if (preferredSdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(preferredSdCard == sd::SdCard::SLOT_1) {
|
|
||||||
currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT;
|
currentMountPrefix = SdCardManager::SD_1_MOUNT_POINT;
|
||||||
}
|
}
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::appendToFile(const char* repositoryPath,
|
ReturnValue_t FileSystemHandler::appendToFile(const char* repositoryPath, const char* filename,
|
||||||
const char* filename, const uint8_t* data, size_t size,
|
const uint8_t* data, size_t size,
|
||||||
uint16_t packetNumber, FileSystemArgsIF* args) {
|
uint16_t packetNumber, FileSystemArgsIF* args) {
|
||||||
auto path = getInitPath(args) / repositoryPath / filename;
|
auto path = getInitPath(args) / repositoryPath / filename;
|
||||||
if(not std::filesystem::exists(path)) {
|
if (not std::filesystem::exists(path)) {
|
||||||
return FILE_DOES_NOT_EXIST;
|
return FILE_DOES_NOT_EXIST;
|
||||||
}
|
}
|
||||||
std::ofstream file(path, std::ios_base::app|std::ios_base::out);
|
std::ofstream file(path, std::ios_base::app | std::ios_base::out);
|
||||||
file.write(reinterpret_cast<const char*>(data), size);
|
file.write(reinterpret_cast<const char*>(data), size);
|
||||||
if(not file.good()) {
|
if (not file.good()) {
|
||||||
return GENERIC_FILE_ERROR;
|
return GENERIC_FILE_ERROR;
|
||||||
}
|
}
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::createFile(const char* repositoryPath,
|
ReturnValue_t FileSystemHandler::createFile(const char* repositoryPath, const char* filename,
|
||||||
const char* filename, const uint8_t* data, size_t size, FileSystemArgsIF* args) {
|
const uint8_t* data, size_t size,
|
||||||
|
FileSystemArgsIF* args) {
|
||||||
auto path = getInitPath(args) / filename;
|
auto path = getInitPath(args) / filename;
|
||||||
if(std::filesystem::exists(path)) {
|
if (std::filesystem::exists(path)) {
|
||||||
return FILE_ALREADY_EXISTS;
|
return FILE_ALREADY_EXISTS;
|
||||||
}
|
}
|
||||||
std::ofstream file(path);
|
std::ofstream file(path);
|
||||||
file.write(reinterpret_cast<const char*>(data), size);
|
file.write(reinterpret_cast<const char*>(data), size);
|
||||||
if(not file.good()) {
|
if (not file.good()) {
|
||||||
return GENERIC_FILE_ERROR;
|
return GENERIC_FILE_ERROR;
|
||||||
}
|
}
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::removeFile(const char* repositoryPath,
|
ReturnValue_t FileSystemHandler::removeFile(const char* repositoryPath, const char* filename,
|
||||||
const char* filename, FileSystemArgsIF* args) {
|
FileSystemArgsIF* args) {
|
||||||
auto path = getInitPath(args) / repositoryPath / filename;
|
auto path = getInitPath(args) / repositoryPath / filename;
|
||||||
if(not std::filesystem::exists(path)) {
|
if (not std::filesystem::exists(path)) {
|
||||||
return FILE_DOES_NOT_EXIST;
|
return FILE_DOES_NOT_EXIST;
|
||||||
}
|
}
|
||||||
int result = std::remove(path.c_str());
|
int result = std::remove(path.c_str());
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
sif::warning << "FileSystemHandler::deleteFile: Failed with code " << result << std::endl;
|
sif::warning << "FileSystemHandler::deleteFile: Failed with code " << result << std::endl;
|
||||||
return GENERIC_FILE_ERROR;
|
return GENERIC_FILE_ERROR;
|
||||||
}
|
}
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler:: createDirectory(const char* repositoryPath, const char* dirname,
|
ReturnValue_t FileSystemHandler::createDirectory(const char* repositoryPath, const char* dirname,
|
||||||
bool createParentDirs, FileSystemArgsIF* args) {
|
bool createParentDirs, FileSystemArgsIF* args) {
|
||||||
auto path = getInitPath(args) / repositoryPath / dirname;
|
auto path = getInitPath(args) / repositoryPath / dirname;
|
||||||
if(std::filesystem::exists(path)) {
|
if (std::filesystem::exists(path)) {
|
||||||
return DIRECTORY_ALREADY_EXISTS;
|
return DIRECTORY_ALREADY_EXISTS;
|
||||||
}
|
}
|
||||||
if(std::filesystem::create_directory(path)) {
|
if (std::filesystem::create_directory(path)) {
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
sif::warning << "Creating directory " << path << " failed" << std::endl;
|
sif::warning << "Creating directory " << path << " failed" << std::endl;
|
||||||
@ -192,39 +180,35 @@ ReturnValue_t FileSystemHandler:: createDirectory(const char* repositoryPath, co
|
|||||||
ReturnValue_t FileSystemHandler::removeDirectory(const char* repositoryPath, const char* dirname,
|
ReturnValue_t FileSystemHandler::removeDirectory(const char* repositoryPath, const char* dirname,
|
||||||
bool deleteRecurively, FileSystemArgsIF* args) {
|
bool deleteRecurively, FileSystemArgsIF* args) {
|
||||||
auto path = getInitPath(args) / repositoryPath / dirname;
|
auto path = getInitPath(args) / repositoryPath / dirname;
|
||||||
if(not std::filesystem::exists(path)) {
|
if (not std::filesystem::exists(path)) {
|
||||||
return DIRECTORY_DOES_NOT_EXIST;
|
return DIRECTORY_DOES_NOT_EXIST;
|
||||||
}
|
}
|
||||||
std::error_code err;
|
std::error_code err;
|
||||||
if(not deleteRecurively) {
|
if (not deleteRecurively) {
|
||||||
if(std::filesystem::remove(path, err)) {
|
if (std::filesystem::remove(path, err)) {
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
// Check error code. Most probably denied permissions because folder is not empty
|
// Check error code. Most probably denied permissions because folder is not empty
|
||||||
sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with "
|
sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with "
|
||||||
"code " << err.value() << ": " << strerror(err.value()) << std::endl;
|
"code "
|
||||||
if(err.value() == ENOTEMPTY) {
|
<< err.value() << ": " << strerror(err.value()) << std::endl;
|
||||||
|
if (err.value() == ENOTEMPTY) {
|
||||||
return DIRECTORY_NOT_EMPTY;
|
return DIRECTORY_NOT_EMPTY;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
return GENERIC_FILE_ERROR;
|
return GENERIC_FILE_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
if (std::filesystem::remove_all(path, err)) {
|
||||||
if(std::filesystem::remove_all(path, err)) {
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with "
|
sif::warning << "FileSystemHandler::removeDirectory: Deleting directory failed with "
|
||||||
"code " << err.value() << ": " << strerror(err.value()) << std::endl;
|
"code "
|
||||||
|
<< err.value() << ": " << strerror(err.value()) << std::endl;
|
||||||
// Check error code
|
// Check error code
|
||||||
if(err.value() == ENOTEMPTY) {
|
if (err.value() == ENOTEMPTY) {
|
||||||
return DIRECTORY_NOT_EMPTY;
|
return DIRECTORY_NOT_EMPTY;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
return GENERIC_FILE_ERROR;
|
return GENERIC_FILE_ERROR;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -233,15 +217,15 @@ ReturnValue_t FileSystemHandler::removeDirectory(const char* repositoryPath, con
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t FileSystemHandler::renameFile(const char *repositoryPath, const char *oldFilename,
|
ReturnValue_t FileSystemHandler::renameFile(const char* repositoryPath, const char* oldFilename,
|
||||||
const char *newFilename, FileSystemArgsIF *args) {
|
const char* newFilename, FileSystemArgsIF* args) {
|
||||||
auto basepath = getInitPath(args) / repositoryPath;
|
auto basepath = getInitPath(args) / repositoryPath;
|
||||||
std::filesystem::rename(basepath / oldFilename, basepath / newFilename);
|
std::filesystem::rename(basepath / oldFilename, basepath / newFilename);
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
void FileSystemHandler::parseCfg(FsCommandCfg *cfg, bool& useMountPrefix) {
|
void FileSystemHandler::parseCfg(FsCommandCfg* cfg, bool& useMountPrefix) {
|
||||||
if(cfg != nullptr) {
|
if (cfg != nullptr) {
|
||||||
useMountPrefix = cfg->useMountPrefix;
|
useMountPrefix = cfg->useMountPrefix;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -250,7 +234,7 @@ std::filesystem::path FileSystemHandler::getInitPath(FileSystemArgsIF* args) {
|
|||||||
bool useMountPrefix = true;
|
bool useMountPrefix = true;
|
||||||
parseCfg(reinterpret_cast<FsCommandCfg*>(args), useMountPrefix);
|
parseCfg(reinterpret_cast<FsCommandCfg*>(args), useMountPrefix);
|
||||||
std::string path;
|
std::string path;
|
||||||
if(useMountPrefix) {
|
if (useMountPrefix) {
|
||||||
path = currentMountPrefix;
|
path = currentMountPrefix;
|
||||||
}
|
}
|
||||||
return std::filesystem::path(path);
|
return std::filesystem::path(path);
|
||||||
|
@ -1,31 +1,28 @@
|
|||||||
#ifndef BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_
|
#ifndef BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_
|
||||||
#define BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_
|
#define BSP_Q7S_MEMORY_FILESYSTEMHANDLER_H_
|
||||||
|
|
||||||
#include "SdCardManager.h"
|
|
||||||
#include "OBSWConfig.h"
|
|
||||||
|
|
||||||
#include "fsfw/ipc/MessageQueueIF.h"
|
|
||||||
#include "fsfw/tasks/ExecutableObjectIF.h"
|
|
||||||
#include "fsfw/objectmanager/SystemObject.h"
|
|
||||||
#include "fsfw/memory/HasFileSystemIF.h"
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <filesystem>
|
#include <filesystem>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#include "OBSWConfig.h"
|
||||||
|
#include "SdCardManager.h"
|
||||||
|
#include "fsfw/ipc/MessageQueueIF.h"
|
||||||
|
#include "fsfw/memory/HasFileSystemIF.h"
|
||||||
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
|
#include "fsfw/tasks/ExecutableObjectIF.h"
|
||||||
|
|
||||||
class CoreController;
|
class CoreController;
|
||||||
|
|
||||||
class FileSystemHandler: public SystemObject,
|
class FileSystemHandler : public SystemObject, public ExecutableObjectIF, public HasFileSystemIF {
|
||||||
public ExecutableObjectIF,
|
public:
|
||||||
public HasFileSystemIF {
|
struct FsCommandCfg : public FileSystemArgsIF {
|
||||||
public:
|
|
||||||
struct FsCommandCfg: public FileSystemArgsIF {
|
|
||||||
// Can be used to automatically use mount prefix of active SD card.
|
// Can be used to automatically use mount prefix of active SD card.
|
||||||
// Otherwise, the operator has to specify the full path to the mounted SD card as well.
|
// Otherwise, the operator has to specify the full path to the mounted SD card as well.
|
||||||
bool useMountPrefix = false;
|
bool useMountPrefix = false;
|
||||||
};
|
};
|
||||||
|
|
||||||
FileSystemHandler(object_id_t fileSystemHandler);
|
FileSystemHandler(object_id_t fileSystemHandler);
|
||||||
virtual~ FileSystemHandler();
|
virtual ~FileSystemHandler();
|
||||||
|
|
||||||
ReturnValue_t performOperation(uint8_t) override;
|
ReturnValue_t performOperation(uint8_t) override;
|
||||||
|
|
||||||
@ -36,22 +33,23 @@ public:
|
|||||||
* @return MessageQueueId_t of the object
|
* @return MessageQueueId_t of the object
|
||||||
*/
|
*/
|
||||||
MessageQueueId_t getCommandQueue() const override;
|
MessageQueueId_t getCommandQueue() const override;
|
||||||
ReturnValue_t appendToFile(const char* repositoryPath,
|
ReturnValue_t appendToFile(const char* repositoryPath, const char* filename, const uint8_t* data,
|
||||||
const char* filename, const uint8_t* data, size_t size,
|
size_t size, uint16_t packetNumber,
|
||||||
uint16_t packetNumber, FileSystemArgsIF* args = nullptr) override;
|
FileSystemArgsIF* args = nullptr) override;
|
||||||
ReturnValue_t createFile(const char* repositoryPath,
|
ReturnValue_t createFile(const char* repositoryPath, const char* filename,
|
||||||
const char* filename, const uint8_t* data = nullptr,
|
const uint8_t* data = nullptr, size_t size = 0,
|
||||||
size_t size = 0, FileSystemArgsIF* args = nullptr) override;
|
FileSystemArgsIF* args = nullptr) override;
|
||||||
ReturnValue_t removeFile(const char* repositoryPath,
|
ReturnValue_t removeFile(const char* repositoryPath, const char* filename,
|
||||||
const char* filename, FileSystemArgsIF* args = nullptr) override;
|
FileSystemArgsIF* args = nullptr) override;
|
||||||
ReturnValue_t createDirectory(const char* repositoryPath, const char* dirname,
|
ReturnValue_t createDirectory(const char* repositoryPath, const char* dirname,
|
||||||
bool createParentDirs, FileSystemArgsIF* args = nullptr) override;
|
bool createParentDirs, FileSystemArgsIF* args = nullptr) override;
|
||||||
ReturnValue_t removeDirectory(const char* repositoryPath, const char* dirname,
|
ReturnValue_t removeDirectory(const char* repositoryPath, const char* dirname,
|
||||||
bool deleteRecurively = false, FileSystemArgsIF* args = nullptr) override;
|
bool deleteRecurively = false,
|
||||||
|
FileSystemArgsIF* args = nullptr) override;
|
||||||
ReturnValue_t renameFile(const char* repositoryPath, const char* oldFilename,
|
ReturnValue_t renameFile(const char* repositoryPath, const char* oldFilename,
|
||||||
const char* newFilename, FileSystemArgsIF* args = nullptr) override;
|
const char* newFilename, FileSystemArgsIF* args = nullptr) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
CoreController* coreCtrl = nullptr;
|
CoreController* coreCtrl = nullptr;
|
||||||
MessageQueueIF* mq = nullptr;
|
MessageQueueIF* mq = nullptr;
|
||||||
std::string currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
std::string currentMountPrefix = SdCardManager::SD_0_MOUNT_POINT;
|
||||||
@ -66,6 +64,4 @@ private:
|
|||||||
void parseCfg(FsCommandCfg* cfg, bool& useMountPrefix);
|
void parseCfg(FsCommandCfg* cfg, bool& useMountPrefix);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif /* BSP_Q7S_MEMORY_FILESYSTEMMANAGER_H_ */
|
#endif /* BSP_Q7S_MEMORY_FILESYSTEMMANAGER_H_ */
|
||||||
|
@ -1,28 +1,25 @@
|
|||||||
#include "SdCardManager.h"
|
#include "SdCardManager.h"
|
||||||
#include "scratchApi.h"
|
|
||||||
|
|
||||||
#include "linux/utility/utility.h"
|
|
||||||
|
|
||||||
#include "fsfw/ipc/MutexFactory.h"
|
|
||||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
|
||||||
|
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#include <cstring>
|
||||||
|
#include <filesystem>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include <filesystem>
|
|
||||||
#include <cstring>
|
#include "fsfw/ipc/MutexFactory.h"
|
||||||
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
|
#include "linux/utility/utility.h"
|
||||||
|
#include "scratchApi.h"
|
||||||
|
|
||||||
SdCardManager* SdCardManager::factoryInstance = nullptr;
|
SdCardManager* SdCardManager::factoryInstance = nullptr;
|
||||||
|
|
||||||
SdCardManager::SdCardManager(): cmdExecutor(256) {
|
SdCardManager::SdCardManager() : cmdExecutor(256) {}
|
||||||
}
|
|
||||||
|
|
||||||
SdCardManager::~SdCardManager() {
|
SdCardManager::~SdCardManager() {}
|
||||||
}
|
|
||||||
|
|
||||||
void SdCardManager::create() {
|
void SdCardManager::create() {
|
||||||
if(factoryInstance == nullptr) {
|
if (factoryInstance == nullptr) {
|
||||||
factoryInstance = new SdCardManager();
|
factoryInstance = new SdCardManager();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -35,62 +32,57 @@ SdCardManager* SdCardManager::instance() {
|
|||||||
ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard,
|
ReturnValue_t SdCardManager::switchOnSdCard(sd::SdCard sdCard, bool doMountSdCard,
|
||||||
SdStatePair* statusPair) {
|
SdStatePair* statusPair) {
|
||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
if(doMountSdCard) {
|
if (doMountSdCard) {
|
||||||
if(not blocking) {
|
if (not blocking) {
|
||||||
sif::warning << "SdCardManager::switchOnSdCard: Two-step command but manager is"
|
sif::warning << "SdCardManager::switchOnSdCard: Two-step command but manager is"
|
||||||
" not configured for blocking operation. "
|
" not configured for blocking operation. "
|
||||||
"Forcing blocking mode.." << std::endl;
|
"Forcing blocking mode.."
|
||||||
|
<< std::endl;
|
||||||
blocking = true;
|
blocking = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
std::unique_ptr<SdStatePair> sdStatusPtr;
|
std::unique_ptr<SdStatePair> sdStatusPtr;
|
||||||
if(statusPair == nullptr) {
|
if (statusPair == nullptr) {
|
||||||
sdStatusPtr = std::make_unique<SdStatePair>();
|
sdStatusPtr = std::make_unique<SdStatePair>();
|
||||||
statusPair = sdStatusPtr.get();
|
statusPair = sdStatusPtr.get();
|
||||||
result = getSdCardActiveStatus(*statusPair);
|
result = getSdCardActiveStatus(*statusPair);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Not allowed, this function turns on one SD card
|
// Not allowed, this function turns on one SD card
|
||||||
if(sdCard == sd::SdCard::BOTH) {
|
if (sdCard == sd::SdCard::BOTH) {
|
||||||
sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH"
|
sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
sd::SdState currentState;
|
sd::SdState currentState;
|
||||||
if(sdCard == sd::SdCard::SLOT_0) {
|
if (sdCard == sd::SdCard::SLOT_0) {
|
||||||
currentState = statusPair->first;
|
currentState = statusPair->first;
|
||||||
}
|
} else if (sdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(sdCard == sd::SdCard::SLOT_1) {
|
|
||||||
currentState = statusPair->second;
|
currentState = statusPair->second;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
// Should not happen
|
// Should not happen
|
||||||
currentState = sd::SdState::OFF;
|
currentState = sd::SdState::OFF;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(currentState == sd::SdState::ON) {
|
if (currentState == sd::SdState::ON) {
|
||||||
if(not doMountSdCard) {
|
if (not doMountSdCard) {
|
||||||
return ALREADY_ON;
|
return ALREADY_ON;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
return mountSdCard(sdCard);
|
return mountSdCard(sdCard);
|
||||||
}
|
}
|
||||||
}
|
} else if (currentState == sd::SdState::MOUNTED) {
|
||||||
else if(currentState == sd::SdState::MOUNTED) {
|
|
||||||
result = ALREADY_MOUNTED;
|
result = ALREADY_MOUNTED;
|
||||||
}
|
} else if (currentState == sd::SdState::OFF) {
|
||||||
else if(currentState == sd::SdState::OFF) {
|
|
||||||
result = setSdCardState(sdCard, true);
|
result = setSdCardState(sdCard, true);
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
result = HasReturnvaluesIF::RETURN_FAILED;
|
result = HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK or not doMountSdCard) {
|
if (result != HasReturnvaluesIF::RETURN_OK or not doMountSdCard) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -101,36 +93,36 @@ ReturnValue_t SdCardManager::switchOffSdCard(sd::SdCard sdCard, bool doUnmountSd
|
|||||||
SdStatePair* statusPair) {
|
SdStatePair* statusPair) {
|
||||||
std::pair<sd::SdState, sd::SdState> active;
|
std::pair<sd::SdState, sd::SdState> active;
|
||||||
ReturnValue_t result = getSdCardActiveStatus(active);
|
ReturnValue_t result = getSdCardActiveStatus(active);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
if(doUnmountSdCard) {
|
if (doUnmountSdCard) {
|
||||||
if(not blocking) {
|
if (not blocking) {
|
||||||
sif::warning << "SdCardManager::switchOffSdCard: Two-step command but manager is"
|
sif::warning << "SdCardManager::switchOffSdCard: Two-step command but manager is"
|
||||||
" not configured for blocking operation. Forcing blocking mode.." << std::endl;
|
" not configured for blocking operation. Forcing blocking mode.."
|
||||||
|
<< std::endl;
|
||||||
blocking = true;
|
blocking = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Not allowed, this function turns off one SD card
|
// Not allowed, this function turns off one SD card
|
||||||
if(sdCard == sd::SdCard::BOTH) {
|
if (sdCard == sd::SdCard::BOTH) {
|
||||||
sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH"
|
sif::warning << "SdCardManager::switchOffSdCard: API does not allow sd::SdStatus::BOTH"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
if(sdCard == sd::SdCard::SLOT_0) {
|
if (sdCard == sd::SdCard::SLOT_0) {
|
||||||
if(active.first == sd::SdState::OFF) {
|
if (active.first == sd::SdState::OFF) {
|
||||||
return ALREADY_OFF;
|
return ALREADY_OFF;
|
||||||
}
|
}
|
||||||
}
|
} else if (sdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(sdCard == sd::SdCard::SLOT_1) {
|
if (active.second == sd::SdState::OFF) {
|
||||||
if(active.second == sd::SdState::OFF) {
|
|
||||||
return ALREADY_OFF;
|
return ALREADY_OFF;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if(doUnmountSdCard) {
|
if (doUnmountSdCard) {
|
||||||
result = unmountSdCard(sdCard);
|
result = unmountSdCard(sdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -140,22 +132,20 @@ ReturnValue_t SdCardManager::switchOffSdCard(sd::SdCard sdCard, bool doUnmountSd
|
|||||||
|
|
||||||
ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) {
|
ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
||||||
return CommandExecutor::COMMAND_PENDING;
|
return CommandExecutor::COMMAND_PENDING;
|
||||||
}
|
}
|
||||||
string sdstring = "";
|
string sdstring = "";
|
||||||
string statestring = "";
|
string statestring = "";
|
||||||
if(sdCard == sd::SdCard::SLOT_0) {
|
if (sdCard == sd::SdCard::SLOT_0) {
|
||||||
sdstring = "0";
|
sdstring = "0";
|
||||||
}
|
} else if (sdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(sdCard == sd::SdCard::SLOT_1) {
|
|
||||||
sdstring = "1";
|
sdstring = "1";
|
||||||
}
|
}
|
||||||
if(on) {
|
if (on) {
|
||||||
currentOp = Operations::SWITCHING_ON;
|
currentOp = Operations::SWITCHING_ON;
|
||||||
statestring = "on";
|
statestring = "on";
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
currentOp = Operations::SWITCHING_OFF;
|
currentOp = Operations::SWITCHING_OFF;
|
||||||
statestring = "off";
|
statestring = "off";
|
||||||
}
|
}
|
||||||
@ -163,7 +153,7 @@ ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) {
|
|||||||
command << "q7hw sd set " << sdstring << " " << statestring;
|
command << "q7hw sd set " << sdstring << " " << statestring;
|
||||||
cmdExecutor.load(command.str(), blocking, printCmdOutput);
|
cmdExecutor.load(command.str(), blocking, printCmdOutput);
|
||||||
ReturnValue_t result = cmdExecutor.execute();
|
ReturnValue_t result = cmdExecutor.execute();
|
||||||
if(blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
if (blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::setSdCardState");
|
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::setSdCardState");
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
@ -171,7 +161,7 @@ ReturnValue_t SdCardManager::setSdCardState(sd::SdCard sdCard, bool on) {
|
|||||||
|
|
||||||
ReturnValue_t SdCardManager::getSdCardActiveStatus(SdStatePair& active) {
|
ReturnValue_t SdCardManager::getSdCardActiveStatus(SdStatePair& active) {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
if(not filesystem::exists(SD_STATE_FILE)) {
|
if (not filesystem::exists(SD_STATE_FILE)) {
|
||||||
return STATUS_FILE_NEXISTS;
|
return STATUS_FILE_NEXISTS;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -192,76 +182,75 @@ ReturnValue_t SdCardManager::getSdCardActiveStatus(SdStatePair& active) {
|
|||||||
|
|
||||||
ReturnValue_t SdCardManager::mountSdCard(sd::SdCard sdCard) {
|
ReturnValue_t SdCardManager::mountSdCard(sd::SdCard sdCard) {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
||||||
return CommandExecutor::COMMAND_PENDING;
|
return CommandExecutor::COMMAND_PENDING;
|
||||||
}
|
}
|
||||||
if(sdCard == sd::SdCard::BOTH) {
|
if (sdCard == sd::SdCard::BOTH) {
|
||||||
sif::warning << "SdCardManager::mountSdCard: API does not allow sd::SdStatus::BOTH"
|
sif::warning << "SdCardManager::mountSdCard: API does not allow sd::SdStatus::BOTH"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
string mountDev;
|
string mountDev;
|
||||||
string mountPoint;
|
string mountPoint;
|
||||||
if(sdCard == sd::SdCard::SLOT_0) {
|
if (sdCard == sd::SdCard::SLOT_0) {
|
||||||
mountDev = SD_0_DEV_NAME;
|
mountDev = SD_0_DEV_NAME;
|
||||||
mountPoint = SD_0_MOUNT_POINT;
|
mountPoint = SD_0_MOUNT_POINT;
|
||||||
}
|
} else if (sdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(sdCard == sd::SdCard::SLOT_1) {
|
|
||||||
mountDev = SD_1_DEV_NAME;
|
mountDev = SD_1_DEV_NAME;
|
||||||
mountPoint = SD_1_MOUNT_POINT;
|
mountPoint = SD_1_MOUNT_POINT;
|
||||||
}
|
}
|
||||||
if(not filesystem::exists(mountDev)) {
|
if (not filesystem::exists(mountDev)) {
|
||||||
sif::warning << "SdCardManager::mountSdCard: Device file does not exists. Make sure to"
|
sif::warning << "SdCardManager::mountSdCard: Device file does not exists. Make sure to"
|
||||||
" turn on the SD card" << std::endl;
|
" turn on the SD card"
|
||||||
|
<< std::endl;
|
||||||
return MOUNT_ERROR;
|
return MOUNT_ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(not blocking) {
|
if (not blocking) {
|
||||||
currentOp = Operations::MOUNTING;
|
currentOp = Operations::MOUNTING;
|
||||||
}
|
}
|
||||||
string sdMountCommand = "mount " + mountDev + " " + mountPoint;
|
string sdMountCommand = "mount " + mountDev + " " + mountPoint;
|
||||||
cmdExecutor.load(sdMountCommand, blocking, printCmdOutput);
|
cmdExecutor.load(sdMountCommand, blocking, printCmdOutput);
|
||||||
ReturnValue_t result = cmdExecutor.execute();
|
ReturnValue_t result = cmdExecutor.execute();
|
||||||
if(blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
if (blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard");
|
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard");
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t SdCardManager::unmountSdCard(sd::SdCard sdCard) {
|
ReturnValue_t SdCardManager::unmountSdCard(sd::SdCard sdCard) {
|
||||||
if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
||||||
return CommandExecutor::COMMAND_PENDING;
|
return CommandExecutor::COMMAND_PENDING;
|
||||||
}
|
}
|
||||||
using namespace std;
|
using namespace std;
|
||||||
if(sdCard == sd::SdCard::BOTH) {
|
if (sdCard == sd::SdCard::BOTH) {
|
||||||
sif::warning << "SdCardManager::unmountSdCard: API does not allow sd::SdStatus::BOTH"
|
sif::warning << "SdCardManager::unmountSdCard: API does not allow sd::SdStatus::BOTH"
|
||||||
<< std::endl;
|
<< std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
string mountPoint;
|
string mountPoint;
|
||||||
if(sdCard == sd::SdCard::SLOT_0) {
|
if (sdCard == sd::SdCard::SLOT_0) {
|
||||||
mountPoint = SD_0_MOUNT_POINT;
|
mountPoint = SD_0_MOUNT_POINT;
|
||||||
}
|
} else if (sdCard == sd::SdCard::SLOT_1) {
|
||||||
else if(sdCard == sd::SdCard::SLOT_1) {
|
|
||||||
mountPoint = SD_1_MOUNT_POINT;
|
mountPoint = SD_1_MOUNT_POINT;
|
||||||
}
|
}
|
||||||
if(not filesystem::exists(mountPoint)) {
|
if (not filesystem::exists(mountPoint)) {
|
||||||
sif::error << "SdCardManager::unmountSdCard: Default mount point " << mountPoint <<
|
sif::error << "SdCardManager::unmountSdCard: Default mount point " << mountPoint
|
||||||
"does not exist" << std::endl;
|
<< "does not exist" << std::endl;
|
||||||
return UNMOUNT_ERROR;
|
return UNMOUNT_ERROR;
|
||||||
}
|
}
|
||||||
if(filesystem::is_empty(mountPoint)) {
|
if (filesystem::is_empty(mountPoint)) {
|
||||||
// The mount point will always exist, but if it is empty, that is strong hint that
|
// The mount point will always exist, but if it is empty, that is strong hint that
|
||||||
// the SD card was not mounted properly. Still proceed with operation.
|
// the SD card was not mounted properly. Still proceed with operation.
|
||||||
sif::warning << "SdCardManager::unmountSdCard: Mount point is empty!" << std::endl;
|
sif::warning << "SdCardManager::unmountSdCard: Mount point is empty!" << std::endl;
|
||||||
}
|
}
|
||||||
string sdUnmountCommand = "umount " + mountPoint;
|
string sdUnmountCommand = "umount " + mountPoint;
|
||||||
if(not blocking) {
|
if (not blocking) {
|
||||||
currentOp = Operations::UNMOUNTING;
|
currentOp = Operations::UNMOUNTING;
|
||||||
}
|
}
|
||||||
cmdExecutor.load(sdUnmountCommand, blocking, printCmdOutput);
|
cmdExecutor.load(sdUnmountCommand, blocking, printCmdOutput);
|
||||||
ReturnValue_t result = cmdExecutor.execute();
|
ReturnValue_t result = cmdExecutor.execute();
|
||||||
if(blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
if (blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::unmountSdCard");
|
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::unmountSdCard");
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
@ -272,26 +261,27 @@ ReturnValue_t SdCardManager::sanitizeState(SdStatePair* statusPair, sd::SdCard p
|
|||||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||||
// Enforce blocking operation for now. Be careful to reset it when returning prematurely!
|
// Enforce blocking operation for now. Be careful to reset it when returning prematurely!
|
||||||
bool resetNonBlockingState = false;
|
bool resetNonBlockingState = false;
|
||||||
if(not this->blocking) {
|
if (not this->blocking) {
|
||||||
blocking = true;
|
blocking = true;
|
||||||
resetNonBlockingState = true;
|
resetNonBlockingState = true;
|
||||||
}
|
}
|
||||||
if(prefSdCard == sd::SdCard::NONE) {
|
if (prefSdCard == sd::SdCard::NONE) {
|
||||||
result = getPreferredSdCard(prefSdCard);
|
result = getPreferredSdCard(prefSdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {}
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
}
|
}
|
||||||
if(statusPair == nullptr) {
|
}
|
||||||
|
if (statusPair == nullptr) {
|
||||||
sdStatusPtr = std::make_unique<SdStatePair>();
|
sdStatusPtr = std::make_unique<SdStatePair>();
|
||||||
statusPair = sdStatusPtr.get();
|
statusPair = sdStatusPtr.get();
|
||||||
getSdCardActiveStatus(*statusPair);
|
getSdCardActiveStatus(*statusPair);
|
||||||
}
|
}
|
||||||
|
|
||||||
if(statusPair->first == sd::SdState::ON) {
|
if (statusPair->first == sd::SdState::ON) {
|
||||||
result = mountSdCard(prefSdCard);
|
result = mountSdCard(prefSdCard);
|
||||||
}
|
}
|
||||||
|
|
||||||
result = switchOnSdCard(prefSdCard, true, statusPair);
|
result = switchOnSdCard(prefSdCard, true, statusPair);
|
||||||
if(resetNonBlockingState) {
|
if (resetNonBlockingState) {
|
||||||
blocking = false;
|
blocking = false;
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
@ -302,56 +292,53 @@ void SdCardManager::resetState() {
|
|||||||
currentOp = Operations::IDLE;
|
currentOp = Operations::IDLE;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SdCardManager::processSdStatusLine(std::pair<sd::SdState, sd::SdState> &active,
|
void SdCardManager::processSdStatusLine(std::pair<sd::SdState, sd::SdState>& active,
|
||||||
std::string& line, uint8_t& idx, sd::SdCard& currentSd) {
|
std::string& line, uint8_t& idx, sd::SdCard& currentSd) {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
istringstream iss(line);
|
istringstream iss(line);
|
||||||
string word;
|
string word;
|
||||||
bool slotLine = false;
|
bool slotLine = false;
|
||||||
bool mountLine = false;
|
bool mountLine = false;
|
||||||
while(iss >> word) {
|
while (iss >> word) {
|
||||||
if (word == "Slot") {
|
if (word == "Slot") {
|
||||||
slotLine = true;
|
slotLine = true;
|
||||||
}
|
}
|
||||||
if(word == "Mounted") {
|
if (word == "Mounted") {
|
||||||
mountLine = true;
|
mountLine = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(slotLine) {
|
if (slotLine) {
|
||||||
if (word == "1:") {
|
if (word == "1:") {
|
||||||
currentSd = sd::SdCard::SLOT_1;
|
currentSd = sd::SdCard::SLOT_1;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(word == "on") {
|
if (word == "on") {
|
||||||
if(currentSd == sd::SdCard::SLOT_0) {
|
if (currentSd == sd::SdCard::SLOT_0) {
|
||||||
active.first = sd::SdState::ON;
|
active.first = sd::SdState::ON;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
active.second = sd::SdState::ON;
|
active.second = sd::SdState::ON;
|
||||||
}
|
}
|
||||||
}
|
} else if (word == "off") {
|
||||||
else if (word == "off") {
|
if (currentSd == sd::SdCard::SLOT_0) {
|
||||||
if(currentSd == sd::SdCard::SLOT_0) {
|
|
||||||
active.first = sd::SdState::OFF;
|
active.first = sd::SdState::OFF;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
active.second = sd::SdState::OFF;
|
active.second = sd::SdState::OFF;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if(mountLine) {
|
if (mountLine) {
|
||||||
if(currentSd == sd::SdCard::SLOT_0) {
|
if (currentSd == sd::SdCard::SLOT_0) {
|
||||||
active.first = sd::SdState::MOUNTED;
|
active.first = sd::SdState::MOUNTED;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
active.second = sd::SdState::MOUNTED;
|
active.second = sd::SdState::MOUNTED;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if(idx > 5) {
|
if (idx > 5) {
|
||||||
sif::warning << "SdCardManager::sdCardActive: /tmp/sd_status.txt has more than 6 "
|
sif::warning << "SdCardManager::sdCardActive: /tmp/sd_status.txt has more than 6 "
|
||||||
"lines and might be invalid!" << std::endl;
|
"lines and might be invalid!"
|
||||||
|
<< std::endl;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
idx++;
|
idx++;
|
||||||
@ -360,7 +347,7 @@ void SdCardManager::processSdStatusLine(std::pair<sd::SdState, sd::SdState> &act
|
|||||||
ReturnValue_t SdCardManager::getPreferredSdCard(sd::SdCard& sdCard) const {
|
ReturnValue_t SdCardManager::getPreferredSdCard(sd::SdCard& sdCard) const {
|
||||||
uint8_t prefSdCard = 0;
|
uint8_t prefSdCard = 0;
|
||||||
ReturnValue_t result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdCard);
|
ReturnValue_t result = scratch::readNumber(scratch::PREFERED_SDC_KEY, prefSdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
sdCard = static_cast<sd::SdCard>(prefSdCard);
|
sdCard = static_cast<sd::SdCard>(prefSdCard);
|
||||||
@ -368,44 +355,43 @@ ReturnValue_t SdCardManager::getPreferredSdCard(sd::SdCard& sdCard) const {
|
|||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) {
|
ReturnValue_t SdCardManager::setPreferredSdCard(sd::SdCard sdCard) {
|
||||||
if(sdCard == sd::SdCard::BOTH) {
|
if (sdCard == sd::SdCard::BOTH) {
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast<uint8_t>(sdCard));
|
return scratch::writeNumber(scratch::PREFERED_SDC_KEY, static_cast<uint8_t>(sdCard));
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t SdCardManager::updateSdCardStateFile() {
|
ReturnValue_t SdCardManager::updateSdCardStateFile() {
|
||||||
if(cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
if (cmdExecutor.getCurrentState() == CommandExecutor::States::PENDING) {
|
||||||
return CommandExecutor::COMMAND_PENDING;
|
return CommandExecutor::COMMAND_PENDING;
|
||||||
}
|
}
|
||||||
// Use q7hw utility and pipe the command output into the state file
|
// Use q7hw utility and pipe the command output into the state file
|
||||||
std::string updateCmd = "q7hw sd info all > " + std::string(SD_STATE_FILE);
|
std::string updateCmd = "q7hw sd info all > " + std::string(SD_STATE_FILE);
|
||||||
cmdExecutor.load(updateCmd, blocking, printCmdOutput);
|
cmdExecutor.load(updateCmd, blocking, printCmdOutput);
|
||||||
ReturnValue_t result = cmdExecutor.execute();
|
ReturnValue_t result = cmdExecutor.execute();
|
||||||
if(blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
if (blocking and result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard");
|
utility::handleSystemError(cmdExecutor.getLastError(), "SdCardManager::mountSdCard");
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::string SdCardManager::getCurrentMountPrefix(sd::SdCard prefSdCard) {
|
std::string SdCardManager::getCurrentMountPrefix(sd::SdCard prefSdCard) {
|
||||||
if(prefSdCard == sd::SdCard::NONE) {
|
if (prefSdCard == sd::SdCard::NONE) {
|
||||||
ReturnValue_t result = getPreferredSdCard(prefSdCard);
|
ReturnValue_t result = getPreferredSdCard(prefSdCard);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return SD_0_MOUNT_POINT;
|
return SD_0_MOUNT_POINT;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(prefSdCard == sd::SdCard::SLOT_0) {
|
if (prefSdCard == sd::SdCard::SLOT_0) {
|
||||||
return SD_0_MOUNT_POINT;
|
return SD_0_MOUNT_POINT;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
return SD_1_MOUNT_POINT;
|
return SD_1_MOUNT_POINT;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations ¤tOp) {
|
SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations& currentOp) {
|
||||||
CommandExecutor::States state = cmdExecutor.getCurrentState();
|
CommandExecutor::States state = cmdExecutor.getCurrentState();
|
||||||
if(state == CommandExecutor::States::IDLE or state == CommandExecutor::States::COMMAND_LOADED) {
|
if (state == CommandExecutor::States::IDLE or state == CommandExecutor::States::COMMAND_LOADED) {
|
||||||
return OpStatus::IDLE;
|
return OpStatus::IDLE;
|
||||||
}
|
}
|
||||||
currentOp = this->currentOp;
|
currentOp = this->currentOp;
|
||||||
@ -416,27 +402,27 @@ SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations ¤tOp) {
|
|||||||
timer.setTimer(100);
|
timer.setTimer(100);
|
||||||
uint32_t remainingTimeMs = 0;
|
uint32_t remainingTimeMs = 0;
|
||||||
#endif
|
#endif
|
||||||
while(true) {
|
while (true) {
|
||||||
ReturnValue_t result = cmdExecutor.check(bytesRead);
|
ReturnValue_t result = cmdExecutor.check(bytesRead);
|
||||||
// This timer can prevent deadlocks due to missconfigurations
|
// This timer can prevent deadlocks due to missconfigurations
|
||||||
#if OBSW_ENABLE_TIMERS == 1
|
#if OBSW_ENABLE_TIMERS == 1
|
||||||
timer.getTimer(&remainingTimeMs);
|
timer.getTimer(&remainingTimeMs);
|
||||||
if(remainingTimeMs == 0) {
|
if (remainingTimeMs == 0) {
|
||||||
sif::error << "SdCardManager::checkCurrentOp: Timeout!" << std::endl;
|
sif::error << "SdCardManager::checkCurrentOp: Timeout!" << std::endl;
|
||||||
return OpStatus::FAIL;
|
return OpStatus::FAIL;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
switch(result) {
|
switch (result) {
|
||||||
case(CommandExecutor::BYTES_READ): {
|
case (CommandExecutor::BYTES_READ): {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
case(CommandExecutor::EXECUTION_FINISHED): {
|
case (CommandExecutor::EXECUTION_FINISHED): {
|
||||||
return OpStatus::SUCCESS;
|
return OpStatus::SUCCESS;
|
||||||
}
|
}
|
||||||
case(HasReturnvaluesIF::RETURN_OK): {
|
case (HasReturnvaluesIF::RETURN_OK): {
|
||||||
return OpStatus::ONGOING;
|
return OpStatus::ONGOING;
|
||||||
}
|
}
|
||||||
case(HasReturnvaluesIF::RETURN_FAILED): {
|
case (HasReturnvaluesIF::RETURN_FAILED): {
|
||||||
return OpStatus::FAIL;
|
return OpStatus::FAIL;
|
||||||
}
|
}
|
||||||
default: {
|
default: {
|
||||||
@ -446,12 +432,31 @@ SdCardManager::OpStatus SdCardManager::checkCurrentOp(Operations ¤tOp) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SdCardManager::setBlocking(bool blocking) {
|
void SdCardManager::setBlocking(bool blocking) { this->blocking = blocking; }
|
||||||
this->blocking = blocking;
|
|
||||||
|
void SdCardManager::setPrintCommandOutput(bool print) { this->printCmdOutput = print; }
|
||||||
|
|
||||||
|
bool SdCardManager::isSdCardMounted(sd::SdCard sdCard) {
|
||||||
|
SdCardManager::SdStatePair active;
|
||||||
|
ReturnValue_t result = this->getSdCardActiveStatus(active);
|
||||||
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
sif::debug << "SdCardManager::isSdCardMounted: Failed to get SD card active state";
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (sdCard == sd::SLOT_0) {
|
||||||
|
if (active.first == sd::MOUNTED) {
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else if (sdCard == sd::SLOT_1) {
|
||||||
|
if (active.second == sd::MOUNTED) {
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
sif::debug << "SdCardManager::isSdCardMounted: Unknown SD card specified" << std::endl;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SdCardManager::setPrintCommandOutput(bool print) {
|
|
||||||
this->printCmdOutput = print;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
@ -1,21 +1,20 @@
|
|||||||
#ifndef BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_
|
#ifndef BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_
|
||||||
#define BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_
|
#define BSP_Q7S_MEMORY_SDCARDACCESSMANAGER_H_
|
||||||
|
|
||||||
#include "fsfw_hal/linux/CommandExecutor.h"
|
|
||||||
#include "definitions.h"
|
|
||||||
#include "returnvalues/classIds.h"
|
|
||||||
#include "events/subsystemIdRanges.h"
|
|
||||||
|
|
||||||
#include "fsfw/events/Event.h"
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
|
||||||
|
|
||||||
#include <poll.h>
|
#include <poll.h>
|
||||||
|
|
||||||
#include <cstdint>
|
|
||||||
#include <utility>
|
|
||||||
#include <string>
|
|
||||||
#include <optional>
|
|
||||||
#include <array>
|
#include <array>
|
||||||
|
#include <cstdint>
|
||||||
|
#include <optional>
|
||||||
|
#include <string>
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
|
#include "definitions.h"
|
||||||
|
#include "events/subsystemIdRanges.h"
|
||||||
|
#include "fsfw/events/Event.h"
|
||||||
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
|
#include "fsfw_hal/linux/CommandExecutor.h"
|
||||||
|
#include "returnvalues/classIds.h"
|
||||||
|
|
||||||
class MutexIF;
|
class MutexIF;
|
||||||
|
|
||||||
@ -25,41 +24,26 @@ class MutexIF;
|
|||||||
*/
|
*/
|
||||||
class SdCardManager {
|
class SdCardManager {
|
||||||
friend class SdCardAccess;
|
friend class SdCardAccess;
|
||||||
public:
|
|
||||||
enum class Operations {
|
|
||||||
SWITCHING_ON,
|
|
||||||
SWITCHING_OFF,
|
|
||||||
MOUNTING,
|
|
||||||
UNMOUNTING,
|
|
||||||
IDLE
|
|
||||||
};
|
|
||||||
|
|
||||||
enum class OpStatus {
|
public:
|
||||||
IDLE,
|
enum class Operations { SWITCHING_ON, SWITCHING_OFF, MOUNTING, UNMOUNTING, IDLE };
|
||||||
TIMEOUT,
|
|
||||||
ONGOING,
|
enum class OpStatus { IDLE, TIMEOUT, ONGOING, SUCCESS, FAIL };
|
||||||
SUCCESS,
|
|
||||||
FAIL
|
|
||||||
};
|
|
||||||
|
|
||||||
using SdStatePair = std::pair<sd::SdState, sd::SdState>;
|
using SdStatePair = std::pair<sd::SdState, sd::SdState>;
|
||||||
|
|
||||||
static constexpr uint8_t INTERFACE_ID = CLASS_ID::SD_CARD_MANAGER;
|
static constexpr uint8_t INTERFACE_ID = CLASS_ID::SD_CARD_MANAGER;
|
||||||
|
|
||||||
static constexpr ReturnValue_t OP_ONGOING =
|
static constexpr ReturnValue_t OP_ONGOING = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 0);
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 0);
|
static constexpr ReturnValue_t ALREADY_ON = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 1);
|
||||||
static constexpr ReturnValue_t ALREADY_ON =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 1);
|
|
||||||
static constexpr ReturnValue_t ALREADY_MOUNTED =
|
static constexpr ReturnValue_t ALREADY_MOUNTED =
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 2);
|
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 2);
|
||||||
static constexpr ReturnValue_t ALREADY_OFF =
|
static constexpr ReturnValue_t ALREADY_OFF = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 3);
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 3);
|
|
||||||
static constexpr ReturnValue_t STATUS_FILE_NEXISTS =
|
static constexpr ReturnValue_t STATUS_FILE_NEXISTS =
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 10);
|
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 10);
|
||||||
static constexpr ReturnValue_t STATUS_FILE_FORMAT_INVALID =
|
static constexpr ReturnValue_t STATUS_FILE_FORMAT_INVALID =
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 11);
|
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 11);
|
||||||
static constexpr ReturnValue_t MOUNT_ERROR =
|
static constexpr ReturnValue_t MOUNT_ERROR = HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 12);
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 12);
|
|
||||||
static constexpr ReturnValue_t UNMOUNT_ERROR =
|
static constexpr ReturnValue_t UNMOUNT_ERROR =
|
||||||
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 13);
|
HasReturnvaluesIF::makeReturnCode(INTERFACE_ID, 13);
|
||||||
static constexpr ReturnValue_t SYSTEM_CALL_ERROR =
|
static constexpr ReturnValue_t SYSTEM_CALL_ERROR =
|
||||||
@ -195,7 +179,17 @@ public:
|
|||||||
|
|
||||||
void setBlocking(bool blocking);
|
void setBlocking(bool blocking);
|
||||||
void setPrintCommandOutput(bool print);
|
void setPrintCommandOutput(bool print);
|
||||||
private:
|
|
||||||
|
/**
|
||||||
|
* @brief Checks if an SD card is mounted
|
||||||
|
*
|
||||||
|
* @param sdCard The SD crad to check
|
||||||
|
*
|
||||||
|
* @return true if mounted, otherwise false
|
||||||
|
*/
|
||||||
|
bool isSdCardMounted(sd::SdCard sdCard);
|
||||||
|
|
||||||
|
private:
|
||||||
CommandExecutor cmdExecutor;
|
CommandExecutor cmdExecutor;
|
||||||
Operations currentOp = Operations::IDLE;
|
Operations currentOp = Operations::IDLE;
|
||||||
bool blocking = false;
|
bool blocking = false;
|
||||||
|
@ -5,22 +5,15 @@
|
|||||||
|
|
||||||
namespace sd {
|
namespace sd {
|
||||||
|
|
||||||
enum SdState: uint8_t {
|
enum SdState : uint8_t {
|
||||||
OFF = 0,
|
OFF = 0,
|
||||||
ON = 1,
|
ON = 1,
|
||||||
// A mounted SD card is on as well
|
// A mounted SD card is on as well
|
||||||
MOUNTED = 2
|
MOUNTED = 2
|
||||||
};
|
};
|
||||||
|
|
||||||
enum SdCard: uint8_t {
|
enum SdCard : uint8_t { SLOT_0 = 0, SLOT_1 = 1, BOTH, NONE };
|
||||||
SLOT_0 = 0,
|
|
||||||
SLOT_1 = 1,
|
|
||||||
BOTH,
|
|
||||||
NONE
|
|
||||||
};
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
} // namespace sd
|
||||||
|
|
||||||
#endif /* BSP_Q7S_MEMORY_DEFINITIONS_H_ */
|
#endif /* BSP_Q7S_MEMORY_DEFINITIONS_H_ */
|
||||||
|
@ -4,7 +4,7 @@ ReturnValue_t scratch::writeString(std::string name, std::string string) {
|
|||||||
std::ostringstream oss;
|
std::ostringstream oss;
|
||||||
oss << "xsc_scratch write " << name << " \"" << string << "\"";
|
oss << "xsc_scratch write " << name << " \"" << string << "\"";
|
||||||
int result = std::system(oss.str().c_str());
|
int result = std::system(oss.str().c_str());
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
utility::handleSystemError(result, "scratch::writeString");
|
utility::handleSystemError(result, "scratch::writeString");
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
@ -15,7 +15,7 @@ ReturnValue_t scratch::readString(std::string key, std::string &string) {
|
|||||||
std::ifstream file;
|
std::ifstream file;
|
||||||
std::string filename;
|
std::string filename;
|
||||||
ReturnValue_t result = readToFile(key, file, filename);
|
ReturnValue_t result = readToFile(key, file, filename);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -26,9 +26,10 @@ ReturnValue_t scratch::readString(std::string key, std::string &string) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
size_t pos = line.find("=");
|
size_t pos = line.find("=");
|
||||||
if(pos == std::string::npos) {
|
if (pos == std::string::npos) {
|
||||||
sif::warning << "scratch::readNumber: Output file format invalid, "
|
sif::warning << "scratch::readNumber: Output file format invalid, "
|
||||||
"no \"=\" found" << std::endl;
|
"no \"=\" found"
|
||||||
|
<< std::endl;
|
||||||
// Could not find value
|
// Could not find value
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return KEY_NOT_FOUND;
|
return KEY_NOT_FOUND;
|
||||||
@ -41,7 +42,7 @@ ReturnValue_t scratch::clearValue(std::string key) {
|
|||||||
std::ostringstream oss;
|
std::ostringstream oss;
|
||||||
oss << "xsc_scratch clear " << key;
|
oss << "xsc_scratch clear " << key;
|
||||||
int result = std::system(oss.str().c_str());
|
int result = std::system(oss.str().c_str());
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
utility::handleSystemError(result, "scratch::clearValue");
|
utility::handleSystemError(result, "scratch::clearValue");
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
@ -1,17 +1,17 @@
|
|||||||
#ifndef BSP_Q7S_MEMORY_SCRATCHAPI_H_
|
#ifndef BSP_Q7S_MEMORY_SCRATCHAPI_H_
|
||||||
#define BSP_Q7S_MEMORY_SCRATCHAPI_H_
|
#define BSP_Q7S_MEMORY_SCRATCHAPI_H_
|
||||||
|
|
||||||
|
#include <cstdlib>
|
||||||
|
#include <fstream>
|
||||||
|
#include <iostream>
|
||||||
|
#include <sstream>
|
||||||
|
#include <type_traits>
|
||||||
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
||||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
#include "linux/utility/utility.h"
|
#include "linux/utility/utility.h"
|
||||||
#include "returnvalues/classIds.h"
|
#include "returnvalues/classIds.h"
|
||||||
|
|
||||||
#include <iostream>
|
|
||||||
#include <fstream>
|
|
||||||
#include <sstream>
|
|
||||||
#include <type_traits>
|
|
||||||
#include <cstdlib>
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief API for the scratch buffer
|
* @brief API for the scratch buffer
|
||||||
*/
|
*/
|
||||||
@ -48,7 +48,7 @@ ReturnValue_t readString(std::string key, std::string& string);
|
|||||||
* @param num Number. Template allows to set signed, unsigned and floating point numbers
|
* @param num Number. Template allows to set signed, unsigned and floating point numbers
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
template<typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
template <typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
||||||
inline ReturnValue_t writeNumber(std::string key, T num) noexcept;
|
inline ReturnValue_t writeNumber(std::string key, T num) noexcept;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -59,10 +59,9 @@ inline ReturnValue_t writeNumber(std::string key, T num) noexcept;
|
|||||||
* @param num
|
* @param num
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
template<typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
template <typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
||||||
inline ReturnValue_t readNumber(std::string key, T& num) noexcept;
|
inline ReturnValue_t readNumber(std::string key, T& num) noexcept;
|
||||||
|
|
||||||
|
|
||||||
// Anonymous namespace
|
// Anonymous namespace
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
@ -75,14 +74,13 @@ ReturnValue_t readToFile(std::string name, std::ifstream& file, std::string& fil
|
|||||||
oss << "xsc_scratch read " << name << " > " << filename;
|
oss << "xsc_scratch read " << name << " > " << filename;
|
||||||
|
|
||||||
int result = std::system(oss.str().c_str());
|
int result = std::system(oss.str().c_str());
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
if(result == 256) {
|
if (result == 256) {
|
||||||
sif::warning << "scratch::readNumber: Key " << name << " does not exist" << std::endl;
|
sif::warning << "scratch::readNumber: Key " << name << " does not exist" << std::endl;
|
||||||
// Could not find value
|
// Could not find value
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return KEY_NOT_FOUND;
|
return KEY_NOT_FOUND;
|
||||||
}
|
} else {
|
||||||
else {
|
|
||||||
utility::handleSystemError(result, "scratch::readNumber");
|
utility::handleSystemError(result, "scratch::readNumber");
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
@ -94,25 +92,25 @@ ReturnValue_t readToFile(std::string name, std::ifstream& file, std::string& fil
|
|||||||
|
|
||||||
} // End of anonymous namespace
|
} // End of anonymous namespace
|
||||||
|
|
||||||
template<typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
template <typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
||||||
inline ReturnValue_t writeNumber(std::string key, T num) noexcept {
|
inline ReturnValue_t writeNumber(std::string key, T num) noexcept {
|
||||||
std::ostringstream oss;
|
std::ostringstream oss;
|
||||||
oss << "xsc_scratch write " << key << " " << std::to_string(num);
|
oss << "xsc_scratch write " << key << " " << std::to_string(num);
|
||||||
int result = std::system(oss.str().c_str());
|
int result = std::system(oss.str().c_str());
|
||||||
if(result != 0) {
|
if (result != 0) {
|
||||||
utility::handleSystemError(result, "scratch::writeNumber");
|
utility::handleSystemError(result, "scratch::writeNumber");
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
template<typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
template <typename T, class = typename std::enable_if<std::is_integral<T>::value>::type>
|
||||||
inline ReturnValue_t readNumber(std::string key, T& num) noexcept {
|
inline ReturnValue_t readNumber(std::string key, T& num) noexcept {
|
||||||
using namespace std;
|
using namespace std;
|
||||||
ifstream file;
|
ifstream file;
|
||||||
std::string filename;
|
std::string filename;
|
||||||
ReturnValue_t result = readToFile(key, file, filename);
|
ReturnValue_t result = readToFile(key, file, filename);
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if (result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
@ -124,9 +122,10 @@ inline ReturnValue_t readNumber(std::string key, T& num) noexcept {
|
|||||||
}
|
}
|
||||||
|
|
||||||
size_t pos = line.find("=");
|
size_t pos = line.find("=");
|
||||||
if(pos == string::npos) {
|
if (pos == string::npos) {
|
||||||
sif::warning << "scratch::readNumber: Output file format invalid, "
|
sif::warning << "scratch::readNumber: Output file format invalid, "
|
||||||
"no \"=\" found" << std::endl;
|
"no \"=\" found"
|
||||||
|
<< std::endl;
|
||||||
// Could not find value
|
// Could not find value
|
||||||
std::remove(filename.c_str());
|
std::remove(filename.c_str());
|
||||||
return KEY_NOT_FOUND;
|
return KEY_NOT_FOUND;
|
||||||
@ -134,8 +133,7 @@ inline ReturnValue_t readNumber(std::string key, T& num) noexcept {
|
|||||||
std::string valueAsString = line.substr(pos + 1);
|
std::string valueAsString = line.substr(pos + 1);
|
||||||
try {
|
try {
|
||||||
num = std::stoi(valueAsString);
|
num = std::stoi(valueAsString);
|
||||||
}
|
} catch (std::invalid_argument& e) {
|
||||||
catch(std::invalid_argument& e) {
|
|
||||||
sif::warning << "scratch::readNumber: stoi call failed with " << e.what() << std::endl;
|
sif::warning << "scratch::readNumber: stoi call failed with " << e.what() << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -143,6 +141,6 @@ inline ReturnValue_t readNumber(std::string key, T& num) noexcept {
|
|||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
} // namespace scratch
|
||||||
|
|
||||||
#endif /* BSP_Q7S_MEMORY_SCRATCHAPI_H_ */
|
#endif /* BSP_Q7S_MEMORY_SCRATCHAPI_H_ */
|
||||||
|
@ -1,4 +1,5 @@
|
|||||||
#include "simple.h"
|
#include "simple.h"
|
||||||
|
|
||||||
#include "q7sConfig.h"
|
#include "q7sConfig.h"
|
||||||
|
|
||||||
#if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1
|
#if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1
|
||||||
@ -8,9 +9,7 @@
|
|||||||
int simple::simple() {
|
int simple::simple() {
|
||||||
cout << "-- Q7S Simple Application --" << endl;
|
cout << "-- Q7S Simple Application --" << endl;
|
||||||
#if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1
|
#if Q7S_SIMPLE_ADD_FILE_SYSTEM_TEST == 1
|
||||||
{
|
{ FileSystemTest fileSystemTest; }
|
||||||
FileSystemTest fileSystemTest;
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TE0720_GPIO_TEST
|
#if TE0720_GPIO_TEST
|
||||||
@ -18,4 +17,3 @@ int simple::simple() {
|
|||||||
#endif
|
#endif
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,9 +1,5 @@
|
|||||||
#include <bsp_q7s/spi/Q7sSpiComIF.h>
|
#include <bsp_q7s/spi/Q7sSpiComIF.h>
|
||||||
|
|
||||||
Q7sSpiComIF::Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF) :
|
Q7sSpiComIF::Q7sSpiComIF(object_id_t objectId, GpioIF* gpioComIF) : SpiComIF(objectId, gpioComIF) {}
|
||||||
SpiComIF(objectId, gpioComIF) {
|
|
||||||
}
|
|
||||||
|
|
||||||
Q7sSpiComIF::~Q7sSpiComIF() {
|
|
||||||
}
|
|
||||||
|
|
||||||
|
Q7sSpiComIF::~Q7sSpiComIF() {}
|
||||||
|
@ -3,7 +3,6 @@
|
|||||||
|
|
||||||
#include <fsfw_hal/linux/spi/SpiComIF.h>
|
#include <fsfw_hal/linux/spi/SpiComIF.h>
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This additional communication interface is required because the SPI busses behind the
|
* @brief This additional communication interface is required because the SPI busses behind the
|
||||||
* devices "/dev/spi2.0" and "dev/spidev3.0" are multiplexed to one SPI interface.
|
* devices "/dev/spi2.0" and "dev/spidev3.0" are multiplexed to one SPI interface.
|
||||||
@ -17,8 +16,8 @@
|
|||||||
* the SPI interface. The multiplexing is performed via a GPIO connected to a VHDL
|
* the SPI interface. The multiplexing is performed via a GPIO connected to a VHDL
|
||||||
* module responsible for switching between the to SPI peripherals.
|
* module responsible for switching between the to SPI peripherals.
|
||||||
*/
|
*/
|
||||||
class Q7sSpiComIF: public SpiComIF {
|
class Q7sSpiComIF : public SpiComIF {
|
||||||
public:
|
public:
|
||||||
/**
|
/**
|
||||||
* @brief Constructor
|
* @brief Constructor
|
||||||
*
|
*
|
||||||
|
@ -19,10 +19,13 @@ enum commonClassIds: uint8_t {
|
|||||||
CCSDS_IP_CORE_BRIDGE, //IPCI
|
CCSDS_IP_CORE_BRIDGE, //IPCI
|
||||||
PTME, //PTME
|
PTME, //PTME
|
||||||
PLOC_UPDATER, //PLUD
|
PLOC_UPDATER, //PLUD
|
||||||
|
STR_HELPER, //STRHLP
|
||||||
GOM_SPACE_HANDLER, //GOMS
|
GOM_SPACE_HANDLER, //GOMS
|
||||||
PLOC_MEMORY_DUMPER, //PLMEMDUMP
|
PLOC_MEMORY_DUMPER, //PLMEMDUMP
|
||||||
PDEC_HANDLER, //PDEC
|
PDEC_HANDLER, //PDEC
|
||||||
CCSDS_HANDLER, //PDEC
|
CCSDS_HANDLER, //CCSDS
|
||||||
|
ARCSEC_JSON_BASE, //JSONBASE
|
||||||
|
NVM_PARAM_BASE, //NVMB
|
||||||
COMMON_CLASS_ID_END // [EXPORT] : [END]
|
COMMON_CLASS_ID_END // [EXPORT] : [END]
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -79,18 +79,18 @@ 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,
|
||||||
RW3 = 0x44120249,
|
RW3 = 0x44120249,
|
||||||
RW4 = 0x44120350,
|
RW4 = 0x44120350,
|
||||||
|
|
||||||
START_TRACKER = 0x44130001,
|
STAR_TRACKER = 0x44130001,
|
||||||
|
|
||||||
PLOC_UPDATER = 0x44330000,
|
PLOC_UPDATER = 0x44330000,
|
||||||
PLOC_MEMORY_DUMPER = 0x44330001
|
PLOC_MEMORY_DUMPER = 0x44330001,
|
||||||
|
STR_HELPER = 0x44330002
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -18,6 +18,7 @@ enum: uint8_t {
|
|||||||
PLOC_UPDATER = 117,
|
PLOC_UPDATER = 117,
|
||||||
PLOC_MEMORY_DUMPER = 118,
|
PLOC_MEMORY_DUMPER = 118,
|
||||||
PDEC_HANDLER = 119,
|
PDEC_HANDLER = 119,
|
||||||
|
STR_HELPER = 120,
|
||||||
COMMON_SUBSYSTEM_ID_END
|
COMMON_SUBSYSTEM_ID_END
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
@ -12,15 +12,15 @@ namespace spi {
|
|||||||
|
|
||||||
// Default values, changing them is not supported for now
|
// Default values, changing them is not supported for now
|
||||||
static constexpr uint32_t DEFAULT_LIS3_SPEED = 976'000;
|
static constexpr uint32_t DEFAULT_LIS3_SPEED = 976'000;
|
||||||
static constexpr uint32_t LIS3_TRANSITION_DELAY = 10000;
|
static constexpr uint32_t LIS3_TRANSITION_DELAY = 5000;
|
||||||
static constexpr spi::SpiModes DEFAULT_LIS3_MODE = spi::SpiModes::MODE_3;
|
static constexpr spi::SpiModes DEFAULT_LIS3_MODE = spi::SpiModes::MODE_3;
|
||||||
|
|
||||||
static constexpr uint32_t DEFAULT_RM3100_SPEED = 976'000;
|
static constexpr uint32_t DEFAULT_RM3100_SPEED = 976'000;
|
||||||
static constexpr uint32_t RM3100_TRANSITION_DELAY = 10000;
|
static constexpr uint32_t RM3100_TRANSITION_DELAY = 5000;
|
||||||
static constexpr spi::SpiModes DEFAULT_RM3100_MODE = spi::SpiModes::MODE_3;
|
static constexpr spi::SpiModes DEFAULT_RM3100_MODE = spi::SpiModes::MODE_3;
|
||||||
|
|
||||||
static constexpr uint32_t DEFAULT_L3G_SPEED = 976'000;
|
static constexpr uint32_t DEFAULT_L3G_SPEED = 976'000;
|
||||||
static constexpr uint32_t L3G_TRANSITION_DELAY = 10000;
|
static constexpr uint32_t L3G_TRANSITION_DELAY = 5000;
|
||||||
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;
|
||||||
|
2
fsfw
2
fsfw
@ -1 +1 @@
|
|||||||
Subproject commit a45fb1bb1ff839c487581e1b787db966a1cf80cb
|
Subproject commit c1e0bcee6db652d6c474c87a4099e61ecf86b694
|
@ -1,120 +1,140 @@
|
|||||||
2200;STORE_SEND_WRITE_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2200;STORE_SEND_WRITE_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2201;STORE_WRITE_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2201;STORE_WRITE_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2202;STORE_SEND_READ_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2202;STORE_SEND_READ_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2203;STORE_READ_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2203;STORE_READ_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2204;UNEXPECTED_MSG;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2204;UNEXPECTED_MSG;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2205;STORING_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2205;STORING_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2206;TM_DUMP_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2206;TM_DUMP_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2207;STORE_INIT_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2207;STORE_INIT_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2208;STORE_INIT_EMPTY;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2208;STORE_INIT_EMPTY;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2209;STORE_CONTENT_CORRUPTED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2209;STORE_CONTENT_CORRUPTED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2210;STORE_INITIALIZE;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2210;STORE_INITIALIZE;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2211;INIT_DONE;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2211;INIT_DONE;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2212;DUMP_FINISHED;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2212;DUMP_FINISHED;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2213;DELETION_FINISHED;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2213;DELETION_FINISHED;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2214;DELETION_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2214;DELETION_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2215;AUTO_CATALOGS_SENDING_FAILED;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
2215;AUTO_CATALOGS_SENDING_FAILED;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
|
||||||
2600;GET_DATA_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h
|
2600;GET_DATA_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h
|
||||||
2601;STORE_DATA_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h
|
2601;STORE_DATA_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/storagemanager/StorageManagerIF.h
|
||||||
2800;DEVICE_BUILDING_COMMAND_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2800;DEVICE_BUILDING_COMMAND_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2801;DEVICE_SENDING_COMMAND_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2801;DEVICE_SENDING_COMMAND_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2802;DEVICE_REQUESTING_REPLY_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2802;DEVICE_REQUESTING_REPLY_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2803;DEVICE_READING_REPLY_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2803;DEVICE_READING_REPLY_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2804;DEVICE_INTERPRETING_REPLY_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2804;DEVICE_INTERPRETING_REPLY_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2805;DEVICE_MISSED_REPLY;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2805;DEVICE_MISSED_REPLY;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2806;DEVICE_UNKNOWN_REPLY;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2806;DEVICE_UNKNOWN_REPLY;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2807;DEVICE_UNREQUESTED_REPLY;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2807;DEVICE_UNREQUESTED_REPLY;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2808;INVALID_DEVICE_COMMAND;LOW;Indicates a SW bug in child class.;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2808;INVALID_DEVICE_COMMAND;LOW;Indicates a SW bug in child class.;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2809;MONITORING_LIMIT_EXCEEDED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2809;MONITORING_LIMIT_EXCEEDED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
2810;MONITORING_AMBIGUOUS;HIGH;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
2810;MONITORING_AMBIGUOUS;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
|
||||||
4201;FUSE_CURRENT_HIGH;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/power/Fuse.h
|
4201;FUSE_CURRENT_HIGH;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h
|
||||||
4202;FUSE_WENT_OFF;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/power/Fuse.h
|
4202;FUSE_WENT_OFF;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h
|
||||||
4204;POWER_ABOVE_HIGH_LIMIT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/power/Fuse.h
|
4204;POWER_ABOVE_HIGH_LIMIT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h
|
||||||
4205;POWER_BELOW_LOW_LIMIT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/power/Fuse.h
|
4205;POWER_BELOW_LOW_LIMIT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/Fuse.h
|
||||||
4300;SWITCH_WENT_OFF;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/power/PowerSwitchIF.h
|
4300;SWITCH_WENT_OFF;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/power/PowerSwitchIF.h
|
||||||
5000;HEATER_ON;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/Heater.h
|
5000;HEATER_ON;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h
|
||||||
5001;HEATER_OFF;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/Heater.h
|
5001;HEATER_OFF;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h
|
||||||
5002;HEATER_TIMEOUT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/Heater.h
|
5002;HEATER_TIMEOUT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h
|
||||||
5003;HEATER_STAYED_ON;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/Heater.h
|
5003;HEATER_STAYED_ON;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h
|
||||||
5004;HEATER_STAYED_OFF;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/Heater.h
|
5004;HEATER_STAYED_OFF;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/Heater.h
|
||||||
5200;TEMP_SENSOR_HIGH;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
5200;TEMP_SENSOR_HIGH;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
||||||
5201;TEMP_SENSOR_LOW;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
5201;TEMP_SENSOR_LOW;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
||||||
5202;TEMP_SENSOR_GRADIENT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
5202;TEMP_SENSOR_GRADIENT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/AbstractTemperatureSensor.h
|
||||||
5901;COMPONENT_TEMP_LOW;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
5901;COMPONENT_TEMP_LOW;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
||||||
5902;COMPONENT_TEMP_HIGH;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
5902;COMPONENT_TEMP_HIGH;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
||||||
5903;COMPONENT_TEMP_OOL_LOW;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
5903;COMPONENT_TEMP_OOL_LOW;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
||||||
5904;COMPONENT_TEMP_OOL_HIGH;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
5904;COMPONENT_TEMP_OOL_HIGH;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
||||||
5905;TEMP_NOT_IN_OP_RANGE;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
5905;TEMP_NOT_IN_OP_RANGE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/thermal/ThermalComponentIF.h
|
||||||
7101;FDIR_CHANGED_STATE;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
7101;FDIR_CHANGED_STATE;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
||||||
7102;FDIR_STARTS_RECOVERY;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
7102;FDIR_STARTS_RECOVERY;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
||||||
7103;FDIR_TURNS_OFF_DEVICE;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
7103;FDIR_TURNS_OFF_DEVICE;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/fdir/FailureIsolationBase.h
|
||||||
7201;MONITOR_CHANGED_STATE;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
7201;MONITOR_CHANGED_STATE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
||||||
7202;VALUE_BELOW_LOW_LIMIT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
7202;VALUE_BELOW_LOW_LIMIT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
||||||
7203;VALUE_ABOVE_HIGH_LIMIT;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
7203;VALUE_ABOVE_HIGH_LIMIT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
||||||
7204;VALUE_OUT_OF_RANGE;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
7204;VALUE_OUT_OF_RANGE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/monitoring/MonitoringIF.h
|
||||||
7301;SWITCHING_TM_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datapool/HkSwitchHelper.h
|
7301;SWITCHING_TM_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datapool/HkSwitchHelper.h
|
||||||
7400;CHANGING_MODE;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7400;CHANGING_MODE;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7401;MODE_INFO;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7401;MODE_INFO;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7402;FALLBACK_FAILED;HIGH;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7402;FALLBACK_FAILED;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7403;MODE_TRANSITION_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7403;MODE_TRANSITION_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7404;CANT_KEEP_MODE;HIGH;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7404;CANT_KEEP_MODE;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7405;OBJECT_IN_INVALID_MODE;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7405;OBJECT_IN_INVALID_MODE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7406;FORCING_MODE;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7406;FORCING_MODE;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7407;MODE_CMD_REJECTED;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
7407;MODE_CMD_REJECTED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/modes/HasModesIF.h
|
||||||
7506;HEALTH_INFO;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7506;HEALTH_INFO;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7507;CHILD_CHANGED_HEALTH;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7507;CHILD_CHANGED_HEALTH;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7508;CHILD_PROBLEMS;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7508;CHILD_PROBLEMS;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7509;OVERWRITING_HEALTH;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7509;OVERWRITING_HEALTH;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7510;TRYING_RECOVERY;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7510;TRYING_RECOVERY;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7511;RECOVERY_STEP;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7511;RECOVERY_STEP;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7512;RECOVERY_DONE;MEDIUM;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
7512;RECOVERY_DONE;MEDIUM;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/health/HasHealthIF.h
|
||||||
7900;RF_AVAILABLE;INFO;A RF available signal was detected. P1: raw RFA state, P2: 0;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
7900;RF_AVAILABLE;INFO;A RF available signal was detected. P1: raw RFA state, P2: 0;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
||||||
7901;RF_LOST;INFO;A previously found RF available signal was lost. P1: raw RFA state, P2: 0;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
7901;RF_LOST;INFO;A previously found RF available signal was lost. P1: raw RFA state, P2: 0;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
||||||
7902;BIT_LOCK;INFO;A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
7902;BIT_LOCK;INFO;A Bit Lock signal. Was detected. P1: raw BLO state, P2: 0;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
||||||
7903;BIT_LOCK_LOST;INFO;A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
7903;BIT_LOCK_LOST;INFO;A previously found Bit Lock signal was lost. P1: raw BLO state, P2: 0;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
||||||
7905;FRAME_PROCESSING_FAILED;LOW;The CCSDS Board could not interpret a TC;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
7905;FRAME_PROCESSING_FAILED;LOW;The CCSDS Board could not interpret a TC;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/datalinklayer/DataLinkLayer.h
|
||||||
8900;CLOCK_SET;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h
|
8900;CLOCK_SET;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h
|
||||||
8901;CLOCK_SET_FAILURE;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h
|
8901;CLOCK_SET_FAILURE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service9TimeManagement.h
|
||||||
9700;TEST;INFO;;/home/eive/EIVE/Robin/eive-obsw/fsfw/src/fsfw/pus/Service17Test.h
|
9700;TEST;INFO;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/src/fsfw/pus/Service17Test.h
|
||||||
10600;CHANGE_OF_SETUP_PARAMETER;LOW;;/home/eive/EIVE/Robin/eive-obsw/fsfw/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h
|
10600;CHANGE_OF_SETUP_PARAMETER;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/fsfw/hal/src/fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h
|
||||||
10900;GPIO_PULL_HIGH_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/HeaterHandler.h
|
10900;GPIO_PULL_HIGH_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/HeaterHandler.h
|
||||||
10901;GPIO_PULL_LOW_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/HeaterHandler.h
|
10901;GPIO_PULL_LOW_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/HeaterHandler.h
|
||||||
10902;SWITCH_ALREADY_ON;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/HeaterHandler.h
|
10902;SWITCH_ALREADY_ON;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/HeaterHandler.h
|
||||||
10903;SWITCH_ALREADY_OFF;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/HeaterHandler.h
|
10903;SWITCH_ALREADY_OFF;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/HeaterHandler.h
|
||||||
10904;MAIN_SWITCH_TIMEOUT;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/HeaterHandler.h
|
10904;MAIN_SWITCH_TIMEOUT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/HeaterHandler.h
|
||||||
11000;MAIN_SWITCH_ON_TIMEOUT;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/SolarArrayDeploymentHandler.h
|
11000;MAIN_SWITCH_ON_TIMEOUT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h
|
||||||
11001;MAIN_SWITCH_OFF_TIMEOUT;LOW;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/SolarArrayDeploymentHandler.h
|
11001;MAIN_SWITCH_OFF_TIMEOUT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h
|
||||||
11002;DEPLOYMENT_FAILED;HIGH;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/SolarArrayDeploymentHandler.h
|
11002;DEPLOYMENT_FAILED;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h
|
||||||
11003;DEPL_SA1_GPIO_SWTICH_ON_FAILED;HIGH;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/SolarArrayDeploymentHandler.h
|
11003;DEPL_SA1_GPIO_SWTICH_ON_FAILED;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h
|
||||||
11004;DEPL_SA2_GPIO_SWTICH_ON_FAILED;HIGH;;/home/eive/EIVE/Robin/eive-obsw/linux/devices/SolarArrayDeploymentHandler.h
|
11004;DEPL_SA2_GPIO_SWTICH_ON_FAILED;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/devices/SolarArrayDeploymentHandler.h
|
||||||
11101;MEMORY_READ_RPT_CRC_FAILURE;LOW;;/home/eive/EIVE/Robin/eive-obsw/mission/devices/PlocMPSoCHandler.h
|
11101;MEMORY_READ_RPT_CRC_FAILURE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h
|
||||||
11102;ACK_FAILURE;LOW;;/home/eive/EIVE/Robin/eive-obsw/mission/devices/PlocMPSoCHandler.h
|
11102;ACK_FAILURE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h
|
||||||
11103;EXE_FAILURE;LOW;;/home/eive/EIVE/Robin/eive-obsw/mission/devices/PlocMPSoCHandler.h
|
11103;EXE_FAILURE;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h
|
||||||
11104;CRC_FAILURE_EVENT;LOW;;/home/eive/EIVE/Robin/eive-obsw/mission/devices/PlocMPSoCHandler.h
|
11104;CRC_FAILURE_EVENT;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/PlocMPSoCHandler.h
|
||||||
11201;SELF_TEST_I2C_FAILURE;LOW;Get self test result returns I2C failure P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11201;SELF_TEST_I2C_FAILURE;LOW;Get self test result returns I2C failure P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11202;SELF_TEST_SPI_FAILURE;LOW;Get self test result returns SPI failure. This concerns the MTM connectivity. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11202;SELF_TEST_SPI_FAILURE;LOW;Get self test result returns SPI failure. This concerns the MTM connectivity. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11203;SELF_TEST_ADC_FAILURE;LOW;Get self test result returns failure in measurement of current and temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11203;SELF_TEST_ADC_FAILURE;LOW;Get self test result returns failure in measurement of current and temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11204;SELF_TEST_PWM_FAILURE;LOW;Get self test result returns PWM failure which concerns the coil actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11204;SELF_TEST_PWM_FAILURE;LOW;Get self test result returns PWM failure which concerns the coil actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11205;SELF_TEST_TC_FAILURE;LOW;Get self test result returns TC failure (system failure) P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11205;SELF_TEST_TC_FAILURE;LOW;Get self test result returns TC failure (system failure) P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11206;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11206;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11207;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11207;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11208;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;/home/eive/EIVE/Robin/eive-obsw/mission/devices/IMTQHandler.h
|
11208;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/IMTQHandler.h
|
||||||
11301;ERROR_STATE;HIGH;Reaction wheel signals an error state;/home/eive/EIVE/Robin/eive-obsw/mission/devices/RwHandler.h
|
11301;ERROR_STATE;HIGH;Reaction wheel signals an error state;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/mission/devices/RwHandler.h
|
||||||
11501;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
11501;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
||||||
11502;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
11502;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
||||||
11503;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
11503;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
||||||
11504;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
11504;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocSupervisorHandler.h
|
||||||
11600;SANITIZATION_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/memory/SdCardManager.h
|
11600;SANITIZATION_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/memory/SdCardManager.h
|
||||||
11700;UPDATE_FILE_NOT_EXISTS;LOW;;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11700;UPDATE_FILE_NOT_EXISTS;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11701;ACTION_COMMANDING_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11701;ACTION_COMMANDING_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11702;UPDATE_AVAILABLE_FAILED;LOW;Supervisor handler replied action message indicating a command execution failure of the update available command;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11702;UPDATE_AVAILABLE_FAILED;LOW;Supervisor handler replied action message indicating a command execution failure of the update available command;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11703;UPDATE_TRANSFER_FAILED;LOW;Supervisor handler failed to transfer an update space packet. P1: Parameter holds the number of update packets already sent (inclusive the failed packet);/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11703;UPDATE_TRANSFER_FAILED;LOW;Supervisor handler failed to transfer an update space packet. P1: Parameter holds the number of update packets already sent (inclusive the failed packet);C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11704;UPDATE_VERIFY_FAILED;LOW;Supervisor failed to execute the update verify command.;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11704;UPDATE_VERIFY_FAILED;LOW;Supervisor failed to execute the update verify command.;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11705;UPDATE_FINISHED;INFO;MPSoC update successful completed;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocUpdater.h
|
11705;UPDATE_FINISHED;INFO;MPSoC update successful completed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocUpdater.h
|
||||||
11800;SEND_MRAM_DUMP_FAILED;LOW;;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
11800;SEND_MRAM_DUMP_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
||||||
11801;MRAM_DUMP_FAILED;LOW;Received completion failure report form PLOC supervisor handler P1: MRAM start address of failing dump command;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
11801;MRAM_DUMP_FAILED;LOW;Received completion failure report form PLOC supervisor handler P1: MRAM start address of failing dump command;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
||||||
11802;MRAM_DUMP_FINISHED;LOW;MRAM dump finished successfully;/home/eive/EIVE/Robin/eive-obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
11802;MRAM_DUMP_FINISHED;LOW;MRAM dump finished successfully;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/PlocMemoryDumper.h
|
||||||
11901;INVALID_TC_FRAME;HIGH;;/home/eive/EIVE/Robin/eive-obsw/linux/obc/PdecHandler.h
|
11901;INVALID_TC_FRAME;HIGH;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/obc/PdecHandler.h
|
||||||
11902;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;/home/eive/EIVE/Robin/eive-obsw/linux/obc/PdecHandler.h
|
11902;INVALID_FAR;HIGH;Read invalid FAR from PDEC after startup;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/obc/PdecHandler.h
|
||||||
11903;CARRIER_LOCK;INFO;Carrier lock detected;/home/eive/EIVE/Robin/eive-obsw/linux/obc/PdecHandler.h
|
11903;CARRIER_LOCK;INFO;Carrier lock detected;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/obc/PdecHandler.h
|
||||||
11904;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);/home/eive/EIVE/Robin/eive-obsw/linux/obc/PdecHandler.h
|
11904;BIT_LOCK_PDEC;INFO;Bit lock detected (data valid);C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/linux/obc/PdecHandler.h
|
||||||
|
12000;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12001;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12002;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12003;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12004;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12005;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12006;FLASH_WRITE_FAILED;LOW;Flash write procedure failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12007;FLASH_READ_FAILED;LOW;Flash read procedure failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12008;FPGA_DOWNLOAD_SUCCESSFUL;LOW;Download of FPGA image successful;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12009;FPGA_DOWNLOAD_FAILED;LOW;Download of FPGA image failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12010;FPGA_UPLOAD_SUCCESSFUL;LOW;Upload of FPGA image successful;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12011;FPGA_UPLOAD_FAILED;LOW;Upload of FPGA image failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12012;STR_HELPER_READING_REPLY_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12013;STR_HELPER_COM_ERROR;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12014;STR_HELPER_NO_REPLY;LOW;Star tracker did not send replies (maybe device is powered off)P1: Position of upload or download packet for which no reply was sent;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12015;STR_HELPER_DEC_ERROR;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12016;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12017;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not existP1: Internal state of str helper;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12018;STR_HELPER_SENDING_PACKET_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
12019;STR_HELPER_REQUESTING_MSG_FAILED;LOW;;C:\Users\jakob\OneDrive\Work\EIVE\Q7S\Software\eive_obsw/bsp_q7s/devices/startracker/StrHelper.h
|
||||||
|
|
@ -27,7 +27,7 @@
|
|||||||
0x44120309;MGM_3_RM3100_HANDLER
|
0x44120309;MGM_3_RM3100_HANDLER
|
||||||
0x44120313;GYRO_3_L3G_HANDLER
|
0x44120313;GYRO_3_L3G_HANDLER
|
||||||
0x44120350;RW4
|
0x44120350;RW4
|
||||||
0x44130001;START_TRACKER
|
0x44130001;STAR_TRACKER
|
||||||
0x44130045;GPS0_HANDLER
|
0x44130045;GPS0_HANDLER
|
||||||
0x44130146;GPS1_HANDLER
|
0x44130146;GPS1_HANDLER
|
||||||
0x44140014;IMTQ_HANDLER
|
0x44140014;IMTQ_HANDLER
|
||||||
@ -39,6 +39,7 @@
|
|||||||
0x443200A5;RAD_SENSOR
|
0x443200A5;RAD_SENSOR
|
||||||
0x44330000;PLOC_UPDATER
|
0x44330000;PLOC_UPDATER
|
||||||
0x44330001;PLOC_MEMORY_DUMPER
|
0x44330001;PLOC_MEMORY_DUMPER
|
||||||
|
0x44330002;STR_HELPER
|
||||||
0x44330015;PLOC_MPSOC_HANDLER
|
0x44330015;PLOC_MPSOC_HANDLER
|
||||||
0x44330016;PLOC_SUPERVISOR_HANDLER
|
0x44330016;PLOC_SUPERVISOR_HANDLER
|
||||||
0x444100A2;SOLAR_ARRAY_DEPL_HANDLER
|
0x444100A2;SOLAR_ARRAY_DEPL_HANDLER
|
||||||
|
|
@ -1,7 +1,7 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated event translation file. Contains 120 translations.
|
* @brief Auto-generated event translation file. Contains 140 translations.
|
||||||
* @details
|
* @details
|
||||||
* Generated on: 2021-11-25 14:09:00
|
* Generated on: 2021-12-29 20:24:08
|
||||||
*/
|
*/
|
||||||
#include "translateEvents.h"
|
#include "translateEvents.h"
|
||||||
|
|
||||||
@ -125,6 +125,26 @@ const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME";
|
|||||||
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
const char *INVALID_FAR_STRING = "INVALID_FAR";
|
||||||
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
const char *CARRIER_LOCK_STRING = "CARRIER_LOCK";
|
||||||
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC";
|
||||||
|
const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED";
|
||||||
|
const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED";
|
||||||
|
const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL";
|
||||||
|
const char *IMAGE_DOWNLOAD_SUCCESSFUL_STRING = "IMAGE_DOWNLOAD_SUCCESSFUL";
|
||||||
|
const char *FLASH_WRITE_SUCCESSFUL_STRING = "FLASH_WRITE_SUCCESSFUL";
|
||||||
|
const char *FLASH_READ_SUCCESSFUL_STRING = "FLASH_READ_SUCCESSFUL";
|
||||||
|
const char *FLASH_WRITE_FAILED_STRING = "FLASH_WRITE_FAILED";
|
||||||
|
const char *FLASH_READ_FAILED_STRING = "FLASH_READ_FAILED";
|
||||||
|
const char *FPGA_DOWNLOAD_SUCCESSFUL_STRING = "FPGA_DOWNLOAD_SUCCESSFUL";
|
||||||
|
const char *FPGA_DOWNLOAD_FAILED_STRING = "FPGA_DOWNLOAD_FAILED";
|
||||||
|
const char *FPGA_UPLOAD_SUCCESSFUL_STRING = "FPGA_UPLOAD_SUCCESSFUL";
|
||||||
|
const char *FPGA_UPLOAD_FAILED_STRING = "FPGA_UPLOAD_FAILED";
|
||||||
|
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
|
||||||
|
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
|
||||||
|
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
|
||||||
|
const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR";
|
||||||
|
const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH";
|
||||||
|
const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS";
|
||||||
|
const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET_FAILED";
|
||||||
|
const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED";
|
||||||
|
|
||||||
const char * translateEvents(Event event) {
|
const char * translateEvents(Event event) {
|
||||||
switch( (event & 0xffff) ) {
|
switch( (event & 0xffff) ) {
|
||||||
@ -368,6 +388,46 @@ const char * translateEvents(Event event) {
|
|||||||
return CARRIER_LOCK_STRING;
|
return CARRIER_LOCK_STRING;
|
||||||
case(11904):
|
case(11904):
|
||||||
return BIT_LOCK_PDEC_STRING;
|
return BIT_LOCK_PDEC_STRING;
|
||||||
|
case(12000):
|
||||||
|
return IMAGE_UPLOAD_FAILED_STRING;
|
||||||
|
case(12001):
|
||||||
|
return IMAGE_DOWNLOAD_FAILED_STRING;
|
||||||
|
case(12002):
|
||||||
|
return IMAGE_UPLOAD_SUCCESSFUL_STRING;
|
||||||
|
case(12003):
|
||||||
|
return IMAGE_DOWNLOAD_SUCCESSFUL_STRING;
|
||||||
|
case(12004):
|
||||||
|
return FLASH_WRITE_SUCCESSFUL_STRING;
|
||||||
|
case(12005):
|
||||||
|
return FLASH_READ_SUCCESSFUL_STRING;
|
||||||
|
case(12006):
|
||||||
|
return FLASH_WRITE_FAILED_STRING;
|
||||||
|
case(12007):
|
||||||
|
return FLASH_READ_FAILED_STRING;
|
||||||
|
case(12008):
|
||||||
|
return FPGA_DOWNLOAD_SUCCESSFUL_STRING;
|
||||||
|
case(12009):
|
||||||
|
return FPGA_DOWNLOAD_FAILED_STRING;
|
||||||
|
case(12010):
|
||||||
|
return FPGA_UPLOAD_SUCCESSFUL_STRING;
|
||||||
|
case(12011):
|
||||||
|
return FPGA_UPLOAD_FAILED_STRING;
|
||||||
|
case(12012):
|
||||||
|
return STR_HELPER_READING_REPLY_FAILED_STRING;
|
||||||
|
case(12013):
|
||||||
|
return STR_HELPER_COM_ERROR_STRING;
|
||||||
|
case(12014):
|
||||||
|
return STR_HELPER_NO_REPLY_STRING;
|
||||||
|
case(12015):
|
||||||
|
return STR_HELPER_DEC_ERROR_STRING;
|
||||||
|
case(12016):
|
||||||
|
return POSITION_MISMATCH_STRING;
|
||||||
|
case(12017):
|
||||||
|
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||||
|
case(12018):
|
||||||
|
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||||
|
case(12019):
|
||||||
|
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
|
||||||
default:
|
default:
|
||||||
return "UNKNOWN_EVENT";
|
return "UNKNOWN_EVENT";
|
||||||
}
|
}
|
||||||
|
@ -1,8 +1,8 @@
|
|||||||
/**
|
/**
|
||||||
* @brief Auto-generated object translation file.
|
* @brief Auto-generated object translation file.
|
||||||
* @details
|
* @details
|
||||||
* Contains 112 translations.
|
* Contains 113 translations.
|
||||||
* Generated on: 2021-11-22 17:04:51
|
* Generated on: 2021-12-21 17:21:23
|
||||||
*/
|
*/
|
||||||
#include "translateObjects.h"
|
#include "translateObjects.h"
|
||||||
|
|
||||||
@ -35,7 +35,7 @@ const char *RW3_STRING = "RW3";
|
|||||||
const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER";
|
const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER";
|
||||||
const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER";
|
const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER";
|
||||||
const char *RW4_STRING = "RW4";
|
const char *RW4_STRING = "RW4";
|
||||||
const char *START_TRACKER_STRING = "START_TRACKER";
|
const char *STAR_TRACKER_STRING = "STAR_TRACKER";
|
||||||
const char *GPS0_HANDLER_STRING = "GPS0_HANDLER";
|
const char *GPS0_HANDLER_STRING = "GPS0_HANDLER";
|
||||||
const char *GPS1_HANDLER_STRING = "GPS1_HANDLER";
|
const char *GPS1_HANDLER_STRING = "GPS1_HANDLER";
|
||||||
const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER";
|
const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER";
|
||||||
@ -47,6 +47,7 @@ const char *ACU_HANDLER_STRING = "ACU_HANDLER";
|
|||||||
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
|
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
|
||||||
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
|
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
|
||||||
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
|
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
|
||||||
|
const char *STR_HELPER_STRING = "STR_HELPER";
|
||||||
const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER";
|
const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER";
|
||||||
const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER";
|
const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER";
|
||||||
const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER";
|
const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER";
|
||||||
@ -180,7 +181,7 @@ const char* translateObject(object_id_t object) {
|
|||||||
case 0x44120350:
|
case 0x44120350:
|
||||||
return RW4_STRING;
|
return RW4_STRING;
|
||||||
case 0x44130001:
|
case 0x44130001:
|
||||||
return START_TRACKER_STRING;
|
return STAR_TRACKER_STRING;
|
||||||
case 0x44130045:
|
case 0x44130045:
|
||||||
return GPS0_HANDLER_STRING;
|
return GPS0_HANDLER_STRING;
|
||||||
case 0x44130146:
|
case 0x44130146:
|
||||||
@ -203,6 +204,8 @@ const char* translateObject(object_id_t object) {
|
|||||||
return PLOC_UPDATER_STRING;
|
return PLOC_UPDATER_STRING;
|
||||||
case 0x44330001:
|
case 0x44330001:
|
||||||
return PLOC_MEMORY_DUMPER_STRING;
|
return PLOC_MEMORY_DUMPER_STRING;
|
||||||
|
case 0x44330002:
|
||||||
|
return STR_HELPER_STRING;
|
||||||
case 0x44330015:
|
case 0x44330015:
|
||||||
return PLOC_MPSOC_HANDLER_STRING;
|
return PLOC_MPSOC_HANDLER_STRING;
|
||||||
case 0x44330016:
|
case 0x44330016:
|
||||||
|
@ -1,21 +1,21 @@
|
|||||||
#include "GpioCookie.h"
|
#include "GpioCookie.h"
|
||||||
|
|
||||||
#include <fsfw/serviceinterface/ServiceInterface.h>
|
#include <fsfw/serviceinterface/ServiceInterface.h>
|
||||||
|
|
||||||
GpioCookie::GpioCookie() {
|
GpioCookie::GpioCookie() {}
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig){
|
ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig) {
|
||||||
if (gpioConfig == nullptr) {
|
if (gpioConfig == nullptr) {
|
||||||
sif::debug << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl;
|
sif::debug << "GpioCookie::addGpio: gpioConfig is nullpointer" << std::endl;
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
auto gpioMapIter = gpioMap.find(gpioId);
|
auto gpioMapIter = gpioMap.find(gpioId);
|
||||||
if(gpioMapIter == gpioMap.end()) {
|
if (gpioMapIter == gpioMap.end()) {
|
||||||
auto statusPair = gpioMap.emplace(gpioId, gpioConfig);
|
auto statusPair = gpioMap.emplace(gpioId, gpioConfig);
|
||||||
if (statusPair.second == false) {
|
if (statusPair.second == false) {
|
||||||
#if FSFW_VERBOSE_LEVEL >= 1
|
#if FSFW_VERBOSE_LEVEL >= 1
|
||||||
sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId <<
|
sif::error << "GpioCookie::addGpio: Failed to add GPIO " << gpioId << " to GPIO map"
|
||||||
" to GPIO map" << std::endl;
|
<< std::endl;
|
||||||
#endif
|
#endif
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
@ -27,8 +27,6 @@ ReturnValue_t GpioCookie::addGpio(gpioId_t gpioId, GpioBase* gpioConfig){
|
|||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return HasReturnvaluesIF::RETURN_FAILED;
|
||||||
}
|
}
|
||||||
|
|
||||||
GpioMap GpioCookie::getGpioMap() const {
|
GpioMap GpioCookie::getGpioMap() const { return gpioMap; }
|
||||||
return gpioMap;
|
|
||||||
}
|
|
||||||
|
|
||||||
GpioCookie::~GpioCookie() {}
|
GpioCookie::~GpioCookie() {}
|
||||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user