Errors fixed in both controller and device handler. Data are now read correctly in the test code but not here in the framework. Problem in reading one variable from datapool for the controller. General cleaning of the code and documentation.

This commit is contained in:
mmode 2021-09-15 17:31:20 +02:00
parent 04cfb85311
commit 510949b54d
25 changed files with 90 additions and 341 deletions

View File

@ -3,4 +3,18 @@
This repository contains the example of the device handler for the Arduino managing the temperaure, environmental and accelerometer sensors.
It is employed the fsfw with the release 0.01.
The code has the obejective of reading the serial data output of the Arduino (in SPC format) and saving them in global data pool.
The data will be then exploited by the termal controller.
The data will be then exploited by the termal controller.
# RUN
In order to run the code it is necessary to connect the computer to the Arduino through USB interface.
Before building and running the code, the serial port should be open through the terminal.
In my case the name of my port is: /dev/ttyACM0
The command to open the serial port in the terminal is: sudo chmod a+rw /dev/ttyACM0
In conclusion it is firstly necessary to know the name of the computer serial port.
This name should be substituted in line 52 of mission/DeviceHandler/ArduinoComIF.cpp as:
int serial_port = open("WRITE_SERIAL_PORT_NAME", O_RDWR);
Finally the command described here above must be inserted in the terminal.

Binary file not shown.

View File

@ -111,7 +111,7 @@ void InitMission::createTasks(){
FixedTimeslotTaskIF* arduinoTask = TaskFactory::instance()->
createFixedTimeslotTask("ARDUINO_TASK",40,
PeriodicTaskIF::MINIMUM_STACK_SIZE, 2, nullptr);
PeriodicTaskIF::MINIMUM_STACK_SIZE, 3.2, nullptr);
result = pollingSequenceArduinoFunction(arduinoTask);
if(result != HasReturnvaluesIF::RETURN_OK) {
sif::error << "InitMission::createTasks:ArduinoPST initialization failed!"
@ -120,7 +120,7 @@ void InitMission::createTasks(){
PeriodicTaskIF* controllerTask = TaskFactory::instance()->
createPeriodicTask("CONTROLLER_TASK",40,
PeriodicTaskIF::MINIMUM_STACK_SIZE, 2, nullptr);
PeriodicTaskIF::MINIMUM_STACK_SIZE, 3, nullptr);
//result = pollingSequenceControllerFunction(controllerTask);
result = controllerTask->addComponent(objects::THERMAL_CONTROLLER);
if(result != HasReturnvaluesIF::RETURN_OK) {

View File

@ -58,15 +58,15 @@ namespace datapool {
TEMP_SENSOR_CH1 = 0x100014,
TEMP_SENSOR_CH2 = 0x100015,
TargetState_COMPONENT_1 = 0x100016,
CurrentState_COMPONENT_1 = 0x100017,
HeaterRequest_COMPONENT_1 = 0x100018,
TargetState_COMPONENT_2 = 0x100019,
CurrentState_COMPONENT_2 = 0x100020,
HeaterRequest_COMPONENT_2 = 0x100021
//Temp_COMPONENT_1 = 0x100098,
TargetState_COMPONENT_1 = 0x100017,
CurrentState_COMPONENT_1 = 0x100018,
HeaterRequest_COMPONENT_1 = 0x100019,
//Temp_COMPONENT_2 = 0x100099,
TargetState_COMPONENT_2 = 0x100021,
CurrentState_COMPONENT_2 = 0x100022,
HeaterRequest_COMPONENT_2 = 0x100023
};
}

View File

@ -17,9 +17,9 @@ ReturnValue_t pollingSequenceArduinoFunction(
uint32_t length = thisSequence->getPeriodMs();
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0, 0);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.8, 1);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.8, 2);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.8, 3);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.3, 1);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.3, 2);
thisSequence->addSlot(objects::ARDUINO_DEVICE_HANDLER, length * 0.4, 3);
if (thisSequence->checkSequence() == HasReturnvaluesIF::RETURN_OK) {
return HasReturnvaluesIF::RETURN_OK;

View File

@ -23,18 +23,8 @@ TCS_ThermalComponent::TCS_ThermalComponent(object_id_t reportingObjectId,
parameters.heaterSwitchoff }, priority,
ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL),
Heater(Heater), RedundantHeater(RedundantHeater),
nopParameters({ parameters.lowerNopLimit, parameters.upperNopLimit }) {
//Set thermal state once, then leave to operator.
/*DataSet mySet;
PoolVariable<int8_t> writableTargetState(targetStatePoolId, &mySet, PoolVariableIF::VAR_WRITE);
writableTargetState = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL;
mySet.commit(PoolVariableIF::VALID);*/
}
TCS_ThermalComponent::~TCS_ThermalComponent() {
}
nopParameters({ parameters.lowerNopLimit, parameters.upperNopLimit }) {}
TCS_ThermalComponent::~TCS_ThermalComponent() {}
ThermalComponentIF::HeaterRequest TCS_ThermalComponent::performOperation(uint8_t opCode, bool redundancy, bool dual) {

View File

@ -5,7 +5,6 @@
#include <fsfw/thermal/ThermalModuleIF.h>
#include <mission/Controller/ArduinoTCSTemperatureSensor.h>
#include <mission/Controller/TCS_Heater.h>
//#include <fsfw/thermal/Heater.h>
class TCS_ThermalComponent: public CoreComponent {
public:
@ -29,7 +28,7 @@ public:
ArduinoTCSTemperatureSensor *secondRedundantSensor,
TCS_Heater *Heater, TCS_Heater *RedundantHeater,
ThermalModuleIF *thermalModule, Parameters parameters,
Priority priority);
Priority priority);
virtual ~TCS_ThermalComponent();

View File

@ -122,11 +122,6 @@ ReturnValue_t ThermalController::performOperation(uint8_t opCode) {
return HasReturnvaluesIF::RETURN_OK;
}
/*MessageQueueId_t ThermalController::getCommandQueue() const {
return commandQueue.getId();
}*/
void ThermalController::performControlOperation() {
//Done by overwritten performOperation!
}

View File

@ -15,7 +15,6 @@
#include <mission/Controller/ArduinoTCSTemperatureSensor.h>
#include <mission/Controller/TCS_ThermalComponent.h>
#include <mission/Controller/TCS_Heater.h>
//#include <fsfw/thermal/ThermalModule.h>
#include <bsp_linux/fsfwconfig/objects/systemObjectList.h>
#include <bsp_linux/fsfwconfig/datapool/dataPoolInit.h>
@ -23,24 +22,15 @@
class ThermalController: public ControllerBase {
public:
//static const Mode_t MODE_ON = 1;
//static const Mode_t MODE_OFF = 2;
static const Submode_t NO_REDUNDANCY = 1;
static const Submode_t HEATER_REDUNDANCY = 2;
static const uint8_t COMPONENT_DOMAIN_ID = 1; //!< First number n of component domain IDs
//static const Event TCS_CONTROL_STRATEGY = MAKE_EVENT(0, SEVERITY::INFO); //!< Announcement mode for the TCS controller strategy, strategy is in p1
//static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::ARDUINO_TCS;
//static const uint8_t INTERFACE_ID = CLASS_ID::THERMAL_CONTROLLER;
ThermalController(object_id_t objectId, object_id_t powerSwitcher, size_t commandQueueDepth);
virtual~ ThermalController();
ReturnValue_t initialize() override;
ReturnValue_t performOperation(uint8_t opCode) override;
//virtual MessageQueueId_t getCommandQueue() const;
private:
@ -71,31 +61,15 @@ private:
TCS_Heater REDUNDANT_HEATER_2;
std::list<TCS_Heater> heaters;
std::list<TCS_Heater> redundant_heaters;
/*--------------------------------------------------------------------------------*/
/*const float T_min = -50 + 273.15; // [K]
const float T_max = 50 + 273.15; // [K]
static const uint8_t margin = 5; // ESA qualification margin [K]
static const uint8_t DT_heater = 10; // margin of heater activation [K]
static const uint8_t DT_redundancy = 5; // margin of redundancy activation [K]*/
// Start of the clock when heater is turned-on (one clock defined for each heater), reset when heater turned-off
// const float Dt[36] = {0.0}; // time interval for check of heater activation [s]
//ThermalComponentIF* findComponentByObjectId(object_id_t id);
protected:
//Mode_t mode;
//Submode_t submode;
/* Extended Controller Base overrides */
ReturnValue_t handleCommandMessage(CommandMessage *message) override;
void performControlOperation() override;
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t *msToReachTheMode) override;
void startTransition(Mode_t mode, Submode_t submode) override;
//void calculateStrategy(bool announce, bool redundancy);
//void modeChanged(Mode_t mode, Submode_t submode) override;
//void getMode(Mode_t *mode, Submode_t *submode) override;
//void changeHK(Mode_t mode, Submode_t submode, bool enable) override;

View File

@ -8,25 +8,20 @@
#include <mission/DeviceHandler/ArduinoComIF.h>
#include <mission/DeviceHandler/ArduinoCookie.h>
#include <fsfw/serialize/SerializeAdapter.h>
#include <fsfw/tmtcservices/CommandingServiceBase.h>
#include <fsfw/tmtcpacket/pus/TmPacketStored.h>
// C library headers
#include <stdio.h>
#include <string.h>
#include <vector>
#include <algorithm>
#include <cstdint>
// Linux headers
#include <fcntl.h> // Contains file controls like O_RDWR
#include <errno.h> // Error integer and strerror() function
#include <termios.h> // Contains POSIX terminal control definitions
#include <unistd.h> // write(), read(), close()
#include <algorithm>
#include <cstdint>
ArduinoComIF::ArduinoComIF(object_id_t objectId) :
SystemObject(objectId) {
}
@ -50,7 +45,7 @@ ReturnValue_t ArduinoComIF::initializeInterface(CookieIF *cookie) {
// Here the serial port parameters are defined exploiting a
// special tty configuration struct.
// Open the serial port. Change device path as needed.
// Open the serial port. Change device path as needed (see README in InterfaceCode/testArduino/testArduino/ ).
int serial_port = open("/dev/ttyACM0", O_RDWR);
// Create new termios struc, we call it 'tty' for convention.
@ -122,14 +117,10 @@ ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
ArduinoCookie *Cookie = dynamic_cast<ArduinoCookie*>(cookie);
// The buffer array to store the data read are initialized.
// The whole data packet to be read is 2034 bytes, but
// the limit for one reading (VMAX) is 255 bytes.
// Therefore the reading is divided in 8 separate stages
// which employ 8 different buffer array.
// At the end these 8 arrays are concatenated in
// the main buffer array read_buf.
uint8_t read_buf[2034]; // 2034 bytes from SPC serial output
// The whole data packet to be read is 2580 bytes, but the limit for one reading (VMAX) is 255 bytes.
// Therefore the reading is divided in 11 separate stages which employ 11 different buffer array.
// At the end these 11 arrays are concatenated in the main buffer array read_buf.
uint8_t read_buf[2580]; // 2580 bytes from SPC serial output
uint8_t read_buf1[255]; // 255 bytes
uint8_t read_buf2[255]; // 255 bytes
uint8_t read_buf3[255]; // 255 bytes
@ -137,42 +128,43 @@ ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
uint8_t read_buf5[255]; // 255 bytes
uint8_t read_buf6[255]; // 255 bytes
uint8_t read_buf7[255]; // 255 bytes
uint8_t read_buf8[249]; // 249 bytes
uint8_t read_buf8[255]; // 255 bytes
uint8_t read_buf9[255]; // 255 bytes
uint8_t read_buf10[255]; // 255 bytes
uint8_t read_buf11[30]; // 30 bytes
// The buffer elements are initially set to 0 so we can call printf() easily.
// The buffer elements are initially set to 0.
memset(&read_buf, '\0', sizeof(read_buf));
memset(&read_buf1, '\0', sizeof(read_buf));
memset(&read_buf2, '\0', sizeof(read_buf));
memset(&read_buf3, '\0', sizeof(read_buf));
memset(&read_buf4, '\0', sizeof(read_buf));
memset(&read_buf5, '\0', sizeof(read_buf));
memset(&read_buf6, '\0', sizeof(read_buf));
memset(&read_buf7, '\0', sizeof(read_buf));
memset(&read_buf8, '\0', sizeof(read_buf));
memset(&read_buf1, '\0', sizeof(read_buf1));
memset(&read_buf2, '\0', sizeof(read_buf2));
memset(&read_buf3, '\0', sizeof(read_buf3));
memset(&read_buf4, '\0', sizeof(read_buf4));
memset(&read_buf5, '\0', sizeof(read_buf5));
memset(&read_buf6, '\0', sizeof(read_buf6));
memset(&read_buf7, '\0', sizeof(read_buf7));
memset(&read_buf8, '\0', sizeof(read_buf8));
memset(&read_buf9, '\0', sizeof(read_buf9));
memset(&read_buf10, '\0', sizeof(read_buf10));
memset(&read_buf11, '\0', sizeof(read_buf11));
// Read bytes. The behaviour of read() (e.g. does it block?, how long does it block for?)
// depends on the configuration settings above, specifically VMIN and VTIME.
int num_bytes1 = read(Cookie->Serial_port_number, &read_buf1,
sizeof(read_buf1));
int num_bytes2 = read(Cookie->Serial_port_number, &read_buf2,
sizeof(read_buf2));
int num_bytes3 = read(Cookie->Serial_port_number, &read_buf3,
sizeof(read_buf3));
int num_bytes4 = read(Cookie->Serial_port_number, &read_buf4,
sizeof(read_buf4));
int num_bytes5 = read(Cookie->Serial_port_number, &read_buf5,
sizeof(read_buf5));
int num_bytes6 = read(Cookie->Serial_port_number, &read_buf6,
sizeof(read_buf6));
int num_bytes7 = read(Cookie->Serial_port_number, &read_buf7,
sizeof(read_buf7));
int num_bytes8 = read(Cookie->Serial_port_number, &read_buf8,
sizeof(read_buf8));
int num_bytes1 = read(Cookie->Serial_port_number, &read_buf1, sizeof(read_buf1));
int num_bytes2 = read(Cookie->Serial_port_number, &read_buf2, sizeof(read_buf2));
int num_bytes3 = read(Cookie->Serial_port_number, &read_buf3, sizeof(read_buf3));
int num_bytes4 = read(Cookie->Serial_port_number, &read_buf4, sizeof(read_buf4));
int num_bytes5 = read(Cookie->Serial_port_number, &read_buf5, sizeof(read_buf5));
int num_bytes6 = read(Cookie->Serial_port_number, &read_buf6, sizeof(read_buf6));
int num_bytes7 = read(Cookie->Serial_port_number, &read_buf7, sizeof(read_buf7));
int num_bytes8 = read(Cookie->Serial_port_number, &read_buf8, sizeof(read_buf8));
int num_bytes9 = read(Cookie->Serial_port_number, &read_buf9, sizeof(read_buf9));
int num_bytes10 = read(Cookie->Serial_port_number, &read_buf10, sizeof(read_buf10));
int num_bytes11 = read(Cookie->Serial_port_number, &read_buf11, sizeof(read_buf11));
int num_bytes = num_bytes1 + num_bytes2 + num_bytes3 + num_bytes4
+ num_bytes5 + num_bytes6 + num_bytes7 + num_bytes8;
+ num_bytes5 + num_bytes6 + num_bytes7 + num_bytes8
+ num_bytes9 + num_bytes10 + num_bytes11;
// The 8 buffer arrays are here concatenated in one single vector.
// The 11 buffer arrays are here concatenated in one single vector.
std::copy(read_buf1, read_buf1 + 255, read_buf);
std::copy(read_buf2, read_buf2 + 255, read_buf + 255);
std::copy(read_buf3, read_buf3 + 255, read_buf + 2 * 255);
@ -180,7 +172,10 @@ ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
std::copy(read_buf5, read_buf5 + 255, read_buf + 4 * 255);
std::copy(read_buf6, read_buf6 + 255, read_buf + 5 * 255);
std::copy(read_buf7, read_buf7 + 255, read_buf + 6 * 255);
std::copy(read_buf8, read_buf8 + 249, read_buf + 7 * 255);
std::copy(read_buf8, read_buf8 + 255, read_buf + 7 * 255);
std::copy(read_buf9, read_buf9 + 255, read_buf + 8 * 255);
std::copy(read_buf10, read_buf10 + 255, read_buf + 9 * 255);
std::copy(read_buf11, read_buf11 + 30, read_buf + 10 * 255);
// num_bytes is the number of bytes read (n=0: no bytes received, n=-1: error).
if (num_bytes < 0) {
@ -191,15 +186,9 @@ ReturnValue_t ArduinoComIF::readReceivedMessage(CookieIF *cookie,
printf("Read %i bytes.\n", num_bytes);
// Definition of buffer array and buffer size to return after reading.
*size = 2034;
/*uint8_t *buf_ptr;
buf_ptr = read_buf;
buffer = &buf_ptr;*/
*size = 2580;
*buffer = read_buf;
//close(Cookie->Serial_port_number);
return RETURN_OK;
}

View File

@ -43,24 +43,6 @@ public:
ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
size_t *size) override;
private:
// DELETE
/**
* Send TM packet which contains received data as TM[17,130].
* Wiretapping will do the same.
* @param data
* @param len
*/
//void sendTmPacket(const uint8_t *data,uint32_t len);
/*AcceptsTelemetryIF* funnel = nullptr;
MessageQueueIF* tmQueue = nullptr;
size_t replyMaxLen = 0;
using ReplyBuffer = std::vector<uint8_t>;
std::map<address_t, ReplyBuffer> replyMap;
uint8_t dummyReplyCounter = 0;
uint16_t packetSubCounter = 0;*/
};

View File

@ -1,5 +1,5 @@
/*
* Cookie.cpp
* ArduinoCookie.cpp
*
* Created on: 02/06/2021
* Author: Marco Modè
@ -14,17 +14,3 @@
ArduinoCookie::ArduinoCookie() {}
ArduinoCookie::~ArduinoCookie() {}
/*
address_t ArduinoCookie::getAddress() const {
return address;
}
size_t ArduinoCookie::getReplyMaxLen() const {
return replyMaxLen;
}
int ArduinoCookie::getSerialPort() const {
return Serial_port_number;
}
*/

View File

@ -14,7 +14,7 @@
#include <cstddef>
/**
* @brief Simple cookie which initialie the variables
* @brief Simple cookie which initialize the variables
* for the Linux serial port.
*/
class ArduinoCookie: public CookieIF {
@ -22,14 +22,7 @@ public:
ArduinoCookie();
virtual ~ArduinoCookie();
address_t getAddress() const;
size_t getReplyMaxLen() const;
int getSerialPort() const;
int Serial_port_number;
private:
address_t address = 0;
size_t replyMaxLen = 0;
};

View File

@ -11,23 +11,14 @@
#include <fsfw/datapool/DataSet.h>
#include <fsfw/datapool/PoolVector.h>
#include <bsp_linux/fsfwconfig/datapool/dataPoolInit.h>
//#include <fsfw/datapool/PoolReadGuard.h>
#include <cstdlib>
ArduinoDH::ArduinoDH(object_id_t objectId, object_id_t comIF, CookieIF *cookie) :
DeviceHandlerBase(objectId, comIF, cookie)/*, foundId(&bufferId), foundLen(&bufferLen)*/ {
DeviceHandlerBase(objectId, comIF, cookie) {
mode = _MODE_START_UP;
}
ArduinoDH::~ArduinoDH() {
}
/*void ArduinoDH::performOperationHook() {
}*/
ArduinoDH::~ArduinoDH() {}
void ArduinoDH::doStartUp() {
std::cout<<"Arduino device -> Switching-ON"<<std::endl;
@ -62,37 +53,16 @@ ReturnValue_t ArduinoDH::buildCommandFromCommand(
return HasActionsIF::EXECUTION_FINISHED;
}
/*ReturnValue_t ArduinoDH::buildNormalModeCommand(
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) {
return RETURN_OK;
}*/
void ArduinoDH::passOnCommand(DeviceCommandId_t command,
const uint8_t *commandData, size_t commandDataLen) {
}
void ArduinoDH::fillCommandAndReplyMap() {
}
void ArduinoDH::fillCommandAndReplyMap() {}
ReturnValue_t ArduinoDH::scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) {
/* Unless a command was sent explicitely, we don't expect any replies and ignore
the packet. On a real device, there might be replies which are sent without a previous
command. */
//sif::debug<<"DEBUG_DH: scan for reply"<<std::endl;
/*if (not commandSent) {
sif::debug<<" DH: scan for reply2"<<std::endl;
return DeviceHandlerBase::IGNORE_FULL_PACKET;
} else {
commandSent = false;
}*/
//Unless a command was sent explicitely, we don't expect any replies and ignore
//the packet. On a real device, there might be replies which are sent without a previous
//command.
//foundId = &bufferID;
//foundLen = &foundLen;
*foundLen = 2034;
*foundLen = 2580;
// check validity
if (len == *foundLen){
@ -104,7 +74,6 @@ ReturnValue_t ArduinoDH::scanForReply(const uint8_t *start, size_t len,
}
} else {
return IGNORE_REPLY_DATA;
//break;
}
}
@ -114,7 +83,6 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
//sif::debug<<"DEBUG_DH: interprete for reply"<<std::endl;
// The data stored in the read buffer are here copied in the variables with the SPC format.
// After copying, the data of temperature, environment and accelerometer are stored in three separated vectors.
for (int i = 0; i < 36; i++) {
memcpy(&Temp_ch.start_string, &packet[27 * i + 0], 8);
memcpy(&Temp_ch.Typ, &packet[27 * i + 8], 1);
@ -123,13 +91,9 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
memcpy(&Temp_ch.temperature, &packet[27 * i + 11], 4);
memcpy(&Temp_ch.Timestamp, &packet[27 * i + 15], 4);
memcpy(&Temp_ch.end_string, &packet[27 * i + 19], 8);
/*vecTemp.emplace_back(Temp_ch.start_string, Temp_ch.Typ,
Temp_ch.SPCChNumber, Temp_ch.Value_Cnt, Temp_ch.temperature,
Temp_ch.Timestamp, Temp_ch.end_string);*/
vecTemp.emplace_back(Temp_ch);
}
/*for (int j = 0; j < 9; j++) {
for (int j = 0; j < 9; j++) {
memcpy(&Env_ch.start_string, &packet[27 * (36 + j) + 0], 8);
memcpy(&Env_ch.Typ, &packet[27 * (36 + j) + 8], 1);
memcpy(&Env_ch.SPCChNumber, &packet[27 * (36 + j) + 9], 1);
@ -137,9 +101,6 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
memcpy(&Env_ch.Value, &packet[27 * (36 + j) + 11], 4);
memcpy(&Env_ch.Timestamp, &packet[27 * (36 + j) + 15], 4);
memcpy(&Env_ch.end_string, &packet[27 * (36 + j) + 19], 8);
//vecEnv.emplace_back(Env_ch.start_string, Env_ch.Typ, Env_ch.SPCChNumber,
//Env_ch.Value_Cnt, Env_ch.Value, Env_ch.Timestamp,
//Env_ch.end_string);
vecEnv.emplace_back(Env_ch);
}
for (int k = 0; k < 15; k++) {
@ -150,15 +111,11 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
memcpy(&Acc_ch.Value, &packet[27 * (36 + 9) + 91 * k + 11], 36);
memcpy(&Acc_ch.Timestamp, &packet[27 * (36 + 9) + 91 * k + 47], 36);
memcpy(&Acc_ch.end_string, &packet[27 * (36 + 9) + 91 * k + 83], 8);
//vecAcc.emplace_back(Acc_ch.start_string, Acc_ch.Typ, Acc_ch.SPCChNumber,
//Acc_ch.Value_Cnt, Acc_ch.Value, Acc_ch.Timestamp,
//Acc_ch.end_string);
vecAcc.emplace_back(Acc_ch);
}*/
}
// All data are here printed to monitor from the three vectors of data measurements.
/*printf(
printf(
"\n***********************************************************************************************\n");
printf("TEMPERATURE parameters are: ");
@ -170,8 +127,8 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
printf("\nTemperature: %f", vecTemp[i].temperature);
printf("\nTimestamp: %u", vecTemp[i].Timestamp);
printf("\nEnd: %7s", vecTemp[i].end_string);
}*/
/*printf(
}
printf(
"\n\n***********************************************************************************************\n");
printf("ENVIRONMENTAL parameters are: ");
@ -263,7 +220,7 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
printf("\nEnd: %7s", vecAcc[3 * k + 2].end_string);
}
std::cout << "\n\nEnd reading data.\n" << std::endl;*/
std::cout << "\n\nEnd reading data.\n" << std::endl;
// The data are here written to the data pool where they would be available to be used for other objects
@ -312,50 +269,9 @@ ReturnValue_t ArduinoDH::interpretDeviceReply(DeviceCommandId_t id,
ArduinoDataSet.commit(PoolVariableIF::VALID);
sif::debug<<"\nDEBUG_DHk2: End of copy to datapool"<<std::endl;*/
//sif::debug<<"DEBUG_DH: End of copy to datapool"<<std::endl;
sif::debug<<"DEBUG_DH: End of copy to datapool"<<std::endl;
return RETURN_OK;
}
ReturnValue_t ArduinoDH::interpretingNormalModeReply() {
return RETURN_OK;
}
/*ReturnValue_t ArduinoDH::interpretingTestReply0(DeviceCommandId_t id,
const uint8_t *packet) {
return RETURN_OK;
}*/
/*ReturnValue_t ArduinoDH::interpretingTestReply1(DeviceCommandId_t id,
const uint8_t *packet) {
return RETURN_OK;
}*/
uint32_t ArduinoDH::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) {
return 0;
}
void ArduinoDH::setNormalDatapoolEntriesInvalid() {
}
// ??remove//
/*void ArduinoDH::enableFullDebugOutput(bool enable) {
this->fullInfoPrintout = enable;
}*/
/*ReturnValue_t ArduinoDH::initializeLocalDataPool(
localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) {
return RETURN_OK;
}*/
/*ReturnValue_t ArduinoDH::getParameter(uint8_t domainId, uint8_t uniqueId,
ParameterWrapper *parameterWrapper, const ParameterWrapper *newValues,
uint16_t startAtIndex) {
return RETURN_OK;
}*/
/*LocalPoolObjectBase* ArduinoDH::getPoolObjectHandle(lp_id_t localPoolId) {
return RETURN_OK;
}*/
void ArduinoDH::setNormalDatapoolEntriesInvalid() {}

View File

@ -42,27 +42,12 @@ public:
* in development to reduce need of commanding while debugging.
*/
ArduinoDH(object_id_t objectId, object_id_t comIF, CookieIF *cookie);
/**
* This can be used to enable and disable a lot of demo print output.
* @param enable
*/
void enableFullDebugOutput(bool enable);
virtual ~ ArduinoDH();
//! Size of internal buffer used for communication.
static constexpr uint8_t MAX_BUFFER_SIZE = 255;
//! Unique index if the device handler is created multiple times.
/*testdevice::DeviceIndex deviceIdx = testdevice::DeviceIndex::DEVICE_0;*/
// Definiton of data structure for SPC communication. Three different structures are defined for measurements of:
// - Temperature,
// - Environmental data,
// - Accelerometer data.
struct Temperature {
char start_string[8];
uint8_t Typ;
@ -121,7 +106,6 @@ public:
// Three vectors are defined to store the three type of classes sequentially
// during the phase of reading copying data from the buffers
std::vector<Temperature> vecTemp;
std::vector<Environmental> vecEnv;
std::vector<Accelerometer> vecAcc;
@ -132,7 +116,6 @@ public:
// Then, they are overwritten by the data of next iteration and the process is
// repeated ,until all the data from the buffer are copied to the three vectors
// using the three different structures.
Temperature Temp_ch;
Environmental Env_ch;
Accelerometer Acc_ch;
@ -140,30 +123,13 @@ public:
protected:
/*DeviceCommandId_t bufferId = 0x01;
size_t bufferLen = 2034;
DeviceCommandId_t *foundId;
size_t *foundLen;*/
//testdevice::TestDataSet dataset;
//! This is used to reset the dataset after a commanded change has been made.
bool resetAfterChange = false;
bool commandSent = false;
/** DeviceHandlerBase overrides (see DHB documentation) */
/**
* Hook into the DHB #performOperation call which is executed
* periodically.
*/
/*void buildNormalModeCommands() override;*/
virtual void doStartUp() override;
virtual void doShutDown() override;
virtual ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id)
override;
virtual ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t *id)
override;
virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
virtual ReturnValue_t buildCommandFromCommand(
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) override;
@ -172,63 +138,8 @@ protected:
DeviceCommandId_t *foundId, size_t *foundLen) override;
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) override;
virtual uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo)
override;
virtual void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
virtual void setNormalDatapoolEntriesInvalid() override;
/*virtual ReturnValue_t initializeLocalDataPool(
localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;*/
/*virtual LocalPoolObjectBase* getPoolObjectHandle(lp_id_t localPoolId)
override;*/
/* HasParametersIF overrides */
/*virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId,
ParameterWrapper *parameterWrapper,
const ParameterWrapper *newValues, uint16_t startAtIndex) override;*/
uint8_t commandBuffer[MAX_BUFFER_SIZE];
// ******************************************************************
// delete this stuff
bool oneShot = true;
/* Variables for parameter service */
uint32_t testParameter0 = 0;
int32_t testParameter1 = -2;
float vectorFloatParams2[3] = { };
/* Change device handler functionality, changeable via parameter service */
uint8_t periodicPrintout = false;
/*ReturnValue_t buildNormalModeCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen);*/
/*ReturnValue_t buildTestCommand0(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen);*/
/*ReturnValue_t buildTestCommand1(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen);*/
void passOnCommand(DeviceCommandId_t command, const uint8_t *commandData,
size_t commandDataLen);
ReturnValue_t interpretingNormalModeReply();
/*ReturnValue_t interpretingTestReply0(DeviceCommandId_t id,
const uint8_t *packet);*/
/*ReturnValue_t interpretingTestReply1(DeviceCommandId_t id,
const uint8_t *packet);*/
/*ReturnValue_t interpretingTestReply2(DeviceCommandId_t id,
const uint8_t *packet);*/
/* Some timer utilities */
static constexpr uint8_t divider1 = 2;
PeriodicOperationDivider opDivider1 = PeriodicOperationDivider(divider1);
static constexpr uint8_t divider2 = 10;
PeriodicOperationDivider opDivider2 = PeriodicOperationDivider(divider2);
static constexpr uint32_t initTimeout = 2000;
Countdown countdown1 = Countdown(initTimeout);
// *******************************************************************************
};
#endif /* MISSION_DEVICEHANDLER_ARDUINODEVICEHANDLER_H_ */