commit
fc6fc5b2ca
|
|
@ -98,17 +98,6 @@ if(CUSTOM_COMPILE_OPTIONS)
|
||||||
add_compile_options(${CUSTOM_COMPILE_OPTIONS})
|
add_compile_options(${CUSTOM_COMPILE_OPTIONS})
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
#
|
|
||||||
# MMUHeaders
|
|
||||||
#
|
|
||||||
|
|
||||||
# add_library(MMUHeaders INTERFACE) target_include_directories( MMUHeaders INTERFACE include
|
|
||||||
# include/stm32f4_hal include/usb_host include/usb_device include/marlin include/freertos )
|
|
||||||
|
|
||||||
# target_link_libraries(A3idesHeaders INTERFACE STM32F4::HAL FreeRTOS::FreeRTOS)
|
|
||||||
|
|
||||||
# target_compile_definitions( A3idesHeaders INTERFACE PRINTER_TYPE=PRINTER_PRUSA_${PRINTER} )
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Global Compiler & Linker Configuration
|
# Global Compiler & Linker Configuration
|
||||||
#
|
#
|
||||||
|
|
@ -117,13 +106,13 @@ endif()
|
||||||
add_compile_options(-g)
|
add_compile_options(-g)
|
||||||
|
|
||||||
# optimizations
|
# optimizations
|
||||||
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
|
||||||
add_compile_options(-Og)
|
|
||||||
else()
|
|
||||||
add_compile_options(-Os)
|
|
||||||
endif()
|
|
||||||
|
|
||||||
if(CMAKE_CROSSCOMPILING)
|
if(CMAKE_CROSSCOMPILING)
|
||||||
|
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||||
|
add_compile_options(-Og)
|
||||||
|
else()
|
||||||
|
add_compile_options(-Os)
|
||||||
|
endif()
|
||||||
|
|
||||||
# mcu related settings
|
# mcu related settings
|
||||||
set(MCU_FLAGS -mmcu=atmega32u4 -DF_CPU=16000000L)
|
set(MCU_FLAGS -mmcu=atmega32u4 -DF_CPU=16000000L)
|
||||||
add_compile_options(${MCU_FLAGS})
|
add_compile_options(${MCU_FLAGS})
|
||||||
|
|
@ -136,6 +125,12 @@ if(CMAKE_CROSSCOMPILING)
|
||||||
# disable exceptions and related metadata
|
# disable exceptions and related metadata
|
||||||
add_compile_options(-fno-exceptions -fno-unwind-tables)
|
add_compile_options(-fno-exceptions -fno-unwind-tables)
|
||||||
add_link_options(-Wl,--defsym,__exidx_start=0,--defsym,__exidx_end=0)
|
add_link_options(-Wl,--defsym,__exidx_start=0,--defsym,__exidx_end=0)
|
||||||
|
else()
|
||||||
|
if(CMAKE_BUILD_TYPE STREQUAL "Debug")
|
||||||
|
add_compile_options(-O0)
|
||||||
|
else()
|
||||||
|
add_compile_options(-O2)
|
||||||
|
endif()
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
# enable all warnings (well, not all, but some)
|
# enable all warnings (well, not all, but some)
|
||||||
|
|
@ -165,18 +160,34 @@ add_executable(firmware)
|
||||||
|
|
||||||
set_target_properties(firmware PROPERTIES CXX_STANDARD 14)
|
set_target_properties(firmware PROPERTIES CXX_STANDARD 14)
|
||||||
|
|
||||||
# generate firmware.bin file
|
if(CMAKE_CROSSCOMPILING)
|
||||||
objcopy(firmware "ihex" ".hex")
|
# generate firmware.bin file
|
||||||
|
objcopy(firmware "ihex" ".hex")
|
||||||
|
|
||||||
add_custom_command(TARGET firmware POST_BUILD COMMAND avr-objdump ARGS -CSd firmware > firmware.txt)
|
# produce ASM listing
|
||||||
|
add_custom_command(
|
||||||
|
TARGET firmware POST_BUILD COMMAND avr-objdump ARGS -CSd firmware > firmware.asm
|
||||||
|
)
|
||||||
|
|
||||||
add_custom_command(TARGET firmware POST_BUILD COMMAND avr-size ARGS -C --mcu=atmega32u4 firmware)
|
# inform about the firmware's size in terminal
|
||||||
|
add_custom_command(TARGET firmware POST_BUILD COMMAND avr-size ARGS -C --mcu=atmega32u4 firmware)
|
||||||
|
report_size(firmware)
|
||||||
|
|
||||||
# generate linker map file
|
# generate linker map file
|
||||||
target_link_options(firmware PUBLIC -Wl,-Map=firmware.map)
|
target_link_options(firmware PUBLIC -Wl,-Map=firmware.map)
|
||||||
|
|
||||||
# inform about the firmware's size in terminal
|
target_sources(firmware PRIVATE src/main.cpp src/hal/avr/cpu.cpp src/modules/protocol.cpp)
|
||||||
report_size(firmware)
|
|
||||||
|
else()
|
||||||
|
enable_testing()
|
||||||
|
add_subdirectory(tests)
|
||||||
|
# TODO - still need to decide about the dummy_main.cpp - for unit tests it should not be necessary
|
||||||
|
# to make a separate main.cpp file
|
||||||
|
target_sources(
|
||||||
|
firmware PRIVATE tests/unit/dummy_main.cpp src/hal/avr/cpu.cpp src/modules/protocol.cpp
|
||||||
|
)
|
||||||
|
|
||||||
|
endif()
|
||||||
|
|
||||||
# add_link_dependency(firmware "${LINKER_SCRIPT}")
|
# add_link_dependency(firmware "${LINKER_SCRIPT}")
|
||||||
|
|
||||||
|
|
@ -184,10 +195,6 @@ target_include_directories(firmware PRIVATE include src)
|
||||||
|
|
||||||
target_compile_options(firmware PRIVATE -Wdouble-promotion)
|
target_compile_options(firmware PRIVATE -Wdouble-promotion)
|
||||||
|
|
||||||
# target_link_libraries( firmware PRIVATE A3idesHeaders )
|
|
||||||
|
|
||||||
target_sources(firmware PRIVATE src/main.cpp src/hal/avr/cpu.cpp)
|
|
||||||
|
|
||||||
set_property(
|
set_property(
|
||||||
SOURCE src/version.c
|
SOURCE src/version.c
|
||||||
APPEND
|
APPEND
|
||||||
|
|
@ -198,8 +205,3 @@ set_property(
|
||||||
FW_VERSION_SUFFIX=${PROJECT_VERSION_SUFFIX}
|
FW_VERSION_SUFFIX=${PROJECT_VERSION_SUFFIX}
|
||||||
FW_VERSION_SUFFIX_SHORT=${PROJECT_VERSION_SUFFIX_SHORT}
|
FW_VERSION_SUFFIX_SHORT=${PROJECT_VERSION_SUFFIX_SHORT}
|
||||||
)
|
)
|
||||||
|
|
||||||
if(NOT CMAKE_CROSSCOMPILING)
|
|
||||||
enable_testing()
|
|
||||||
add_subdirectory(tests)
|
|
||||||
endif()
|
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1,221 @@
|
||||||
|
#include "protocol.h"
|
||||||
|
|
||||||
|
// protocol definition
|
||||||
|
// command: Q0
|
||||||
|
// meaning: query operation status
|
||||||
|
// Query/command: query
|
||||||
|
// Expected reply from the MMU:
|
||||||
|
// any of the running operation statuses: OID: [T|L|U|E|C|W|K][0-4]
|
||||||
|
// <OID> P[0-9] : command being processed i.e. operation running, may contain a state number
|
||||||
|
// <OID> E[0-9][0-9] : error 1-9 while doing a tool change
|
||||||
|
// <OID> F : operation finished - will be repeated to "Q" messages until a new command is issued
|
||||||
|
|
||||||
|
namespace modules {
|
||||||
|
|
||||||
|
// decoding automaton
|
||||||
|
// states: input -> transition into state
|
||||||
|
// Code QTLMUXPSBEWK -> msgcode
|
||||||
|
// \n ->start
|
||||||
|
// * ->error
|
||||||
|
// error \n ->start
|
||||||
|
// * ->error
|
||||||
|
// msgcode 0-9 ->msgvalue
|
||||||
|
// * ->error
|
||||||
|
// msgvalue 0-9 ->msgvalue
|
||||||
|
// \n ->start successfully accepted command
|
||||||
|
|
||||||
|
Protocol::DecodeStatus Protocol::DecodeRequest(uint8_t c) {
|
||||||
|
switch (rqState) {
|
||||||
|
case RequestStates::Code:
|
||||||
|
switch (c) {
|
||||||
|
case 'Q':
|
||||||
|
case 'T':
|
||||||
|
case 'L':
|
||||||
|
case 'M':
|
||||||
|
case 'U':
|
||||||
|
case 'X':
|
||||||
|
case 'P':
|
||||||
|
case 'S':
|
||||||
|
case 'B':
|
||||||
|
case 'E':
|
||||||
|
case 'W':
|
||||||
|
case 'K':
|
||||||
|
requestMsg.code = (RequestMsgCodes)c;
|
||||||
|
requestMsg.value = 0;
|
||||||
|
rqState = RequestStates::Value;
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
default:
|
||||||
|
requestMsg.code = RequestMsgCodes::unknown;
|
||||||
|
rqState = RequestStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
case RequestStates::Value:
|
||||||
|
if (c >= '0' && c <= '9') {
|
||||||
|
requestMsg.value *= 10;
|
||||||
|
requestMsg.value += c - '0';
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
} else if (c == '\n') {
|
||||||
|
rqState = RequestStates::Code;
|
||||||
|
return DecodeStatus::MessageCompleted;
|
||||||
|
} else {
|
||||||
|
requestMsg.code = RequestMsgCodes::unknown;
|
||||||
|
rqState = RequestStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
default: //case error:
|
||||||
|
if (c == '\n') {
|
||||||
|
rqState = RequestStates::Code;
|
||||||
|
return DecodeStatus::MessageCompleted;
|
||||||
|
} else {
|
||||||
|
requestMsg.code = RequestMsgCodes::unknown;
|
||||||
|
rqState = RequestStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Protocol::EncodeRequest(const RequestMsg &msg, uint8_t *txbuff) {
|
||||||
|
txbuff[0] = (uint8_t)msg.code;
|
||||||
|
txbuff[1] = msg.value + '0';
|
||||||
|
txbuff[2] = '\n';
|
||||||
|
return 3;
|
||||||
|
}
|
||||||
|
|
||||||
|
Protocol::DecodeStatus Protocol::DecodeResponse(uint8_t c) {
|
||||||
|
switch (rspState) {
|
||||||
|
case ResponseStates::RequestCode:
|
||||||
|
switch (c) {
|
||||||
|
case 'Q':
|
||||||
|
case 'T':
|
||||||
|
case 'L':
|
||||||
|
case 'M':
|
||||||
|
case 'U':
|
||||||
|
case 'X':
|
||||||
|
case 'P':
|
||||||
|
case 'S':
|
||||||
|
case 'B':
|
||||||
|
case 'E':
|
||||||
|
case 'W':
|
||||||
|
case 'K':
|
||||||
|
responseMsg.request.code = (RequestMsgCodes)c;
|
||||||
|
responseMsg.request.value = 0;
|
||||||
|
rspState = ResponseStates::RequestValue;
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
default:
|
||||||
|
rspState = ResponseStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
case ResponseStates::RequestValue:
|
||||||
|
if (c >= '0' && c <= '9') {
|
||||||
|
responseMsg.request.value *= 10;
|
||||||
|
responseMsg.request.value += c - '0';
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
} else if (c == ' ') {
|
||||||
|
rspState = ResponseStates::ParamCode;
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
} else {
|
||||||
|
rspState = ResponseStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
case ResponseStates::ParamCode:
|
||||||
|
switch (c) {
|
||||||
|
case 'P':
|
||||||
|
case 'E':
|
||||||
|
case 'F':
|
||||||
|
case 'A':
|
||||||
|
case 'R':
|
||||||
|
rspState = ResponseStates::ParamValue;
|
||||||
|
responseMsg.paramCode = (ResponseMsgParamCodes)c;
|
||||||
|
responseMsg.paramValue = 0;
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
default:
|
||||||
|
responseMsg.paramCode = ResponseMsgParamCodes::unknown;
|
||||||
|
rspState = ResponseStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
case ResponseStates::ParamValue:
|
||||||
|
if (c >= '0' && c <= '9') {
|
||||||
|
responseMsg.paramValue *= 10;
|
||||||
|
responseMsg.paramValue += c - '0';
|
||||||
|
return DecodeStatus::NeedMoreData;
|
||||||
|
} else if (c == '\n') {
|
||||||
|
rspState = ResponseStates::RequestCode;
|
||||||
|
return DecodeStatus::MessageCompleted;
|
||||||
|
} else {
|
||||||
|
responseMsg.paramCode = ResponseMsgParamCodes::unknown;
|
||||||
|
rspState = ResponseStates::Error;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
default: //case error:
|
||||||
|
if (c == '\n') {
|
||||||
|
rspState = ResponseStates::RequestCode;
|
||||||
|
return DecodeStatus::MessageCompleted;
|
||||||
|
} else {
|
||||||
|
responseMsg.paramCode = ResponseMsgParamCodes::unknown;
|
||||||
|
return DecodeStatus::Error;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Protocol::EncodeResponseCmdAR(const RequestMsg &msg, ResponseMsgParamCodes ar, uint8_t *txbuff) {
|
||||||
|
txbuff[0] = (uint8_t)msg.code;
|
||||||
|
txbuff[1] = msg.value + '0';
|
||||||
|
txbuff[2] = ' ';
|
||||||
|
txbuff[3] = (uint8_t)ar;
|
||||||
|
txbuff[4] = '\n';
|
||||||
|
return 5;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Protocol::EncodeResponseReadFINDA(const RequestMsg &msg, uint8_t findaValue, uint8_t *txbuff) {
|
||||||
|
txbuff[0] = (uint8_t)msg.code;
|
||||||
|
txbuff[1] = msg.value + '0';
|
||||||
|
txbuff[2] = ' ';
|
||||||
|
txbuff[3] = (uint8_t)ResponseMsgParamCodes::Accepted;
|
||||||
|
txbuff[4] = findaValue + '0';
|
||||||
|
txbuff[5] = '\n';
|
||||||
|
return 6;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Protocol::EncodeResponseVersion(const RequestMsg &msg, uint8_t value, uint8_t *txbuff) {
|
||||||
|
txbuff[0] = (uint8_t)msg.code;
|
||||||
|
txbuff[1] = msg.value + '0';
|
||||||
|
txbuff[2] = ' ';
|
||||||
|
txbuff[3] = (uint8_t)ResponseMsgParamCodes::Accepted;
|
||||||
|
uint8_t *dst = txbuff + 4;
|
||||||
|
if (value < 10) {
|
||||||
|
*dst++ = value + '0';
|
||||||
|
} else if (value < 100) {
|
||||||
|
*dst++ = value / 10 + '0';
|
||||||
|
*dst++ = value % 10 + '0';
|
||||||
|
} else {
|
||||||
|
*dst++ = value / 100 + '0';
|
||||||
|
*dst++ = (value / 10) % 10 + '0';
|
||||||
|
*dst++ = value % 10 + '0';
|
||||||
|
}
|
||||||
|
*dst = '\n';
|
||||||
|
return dst - txbuff + 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t Protocol::EncodeResponseQueryOperation(const RequestMsg &msg, ResponseMsgParamCodes code, uint8_t value, uint8_t *txbuff) {
|
||||||
|
txbuff[0] = (uint8_t)msg.code;
|
||||||
|
txbuff[1] = msg.value + '0';
|
||||||
|
txbuff[2] = ' ';
|
||||||
|
txbuff[3] = (uint8_t)code;
|
||||||
|
uint8_t *dst = txbuff + 4;
|
||||||
|
if (code != ResponseMsgParamCodes::Finished) {
|
||||||
|
if (value < 10) {
|
||||||
|
*dst++ = value + '0';
|
||||||
|
} else if (value < 100) {
|
||||||
|
*dst++ = value / 10 + '0';
|
||||||
|
*dst++ = value % 10 + '0';
|
||||||
|
} else {
|
||||||
|
*dst++ = value / 100 + '0';
|
||||||
|
*dst++ = (value / 10) % 10 + '0';
|
||||||
|
*dst++ = value % 10 + '0';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
*dst = '\n';
|
||||||
|
return dst - txbuff + 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace modules
|
||||||
|
|
@ -1,27 +1,143 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
/// MMU protocol implementation
|
/// MMU protocol implementation
|
||||||
/// See description of the new protocol in the MMU 2021 doc
|
/// See description of the new protocol in the MMU 2021 doc
|
||||||
/// @@TODO possibly add some checksum to verify the correctness of messages
|
/// @@TODO possibly add some checksum to verify the correctness of messages
|
||||||
|
|
||||||
namespace modules {
|
namespace modules {
|
||||||
|
|
||||||
/// @@TODO define/improve this simple message structure that fits our domain
|
enum class RequestMsgCodes : uint8_t {
|
||||||
struct Msg {
|
unknown = 0,
|
||||||
uint8_t code;
|
Query = 'Q',
|
||||||
|
Tool = 'T',
|
||||||
|
Load = 'L',
|
||||||
|
Mode = 'M',
|
||||||
|
Unload = 'U',
|
||||||
|
Reset = 'X',
|
||||||
|
Finda = 'P',
|
||||||
|
Version = 'S',
|
||||||
|
Button = 'B',
|
||||||
|
Eject = 'E',
|
||||||
|
Wait = 'W',
|
||||||
|
Cut = 'K'
|
||||||
|
};
|
||||||
|
|
||||||
|
enum class ResponseMsgParamCodes : uint8_t {
|
||||||
|
unknown = 0,
|
||||||
|
Processing = 'P',
|
||||||
|
Error = 'E',
|
||||||
|
Finished = 'F',
|
||||||
|
Accepted = 'A',
|
||||||
|
Rejected = 'R'
|
||||||
|
};
|
||||||
|
|
||||||
|
/// A request message
|
||||||
|
/// Requests are being sent by the printer into the MMU
|
||||||
|
/// It is the same structure as the generic Msg
|
||||||
|
struct RequestMsg {
|
||||||
|
RequestMsgCodes code;
|
||||||
uint8_t value;
|
uint8_t value;
|
||||||
|
inline RequestMsg(RequestMsgCodes code, uint8_t value)
|
||||||
|
: code(code)
|
||||||
|
, value(value) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
/// A response message
|
||||||
|
/// Responses are being sent from the MMU into the printer as a response to a request message
|
||||||
|
struct ResponseMsg {
|
||||||
|
RequestMsg request; ///< response is always preceeded by the request message
|
||||||
|
ResponseMsgParamCodes paramCode; ///< parameters of reply
|
||||||
|
uint8_t paramValue; ///< parameters of reply
|
||||||
|
inline ResponseMsg(RequestMsg request, ResponseMsgParamCodes paramCode, uint8_t paramValue)
|
||||||
|
: request(request)
|
||||||
|
, paramCode(paramCode)
|
||||||
|
, paramValue(paramValue) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Protocol class is responsible for creating/decoding messages in Rx/Tx buffer
|
/// Protocol class is responsible for creating/decoding messages in Rx/Tx buffer
|
||||||
|
/// Beware - in the decoding more, it is meant to be a statefull instance which works through public methods
|
||||||
|
/// processing one input byte per call
|
||||||
class Protocol {
|
class Protocol {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
/// Decodes message in rxbuff
|
/// Message decoding return value
|
||||||
/// @returns decoded message structure
|
enum class DecodeStatus : uint_fast8_t {
|
||||||
Msg Decode(const uint8_t *rxbuff);
|
MessageCompleted, ///< message completed and successfully lexed
|
||||||
/// Encodes message msg into txbuff memory
|
NeedMoreData, ///< message incomplete yet, waiting for another byte to come
|
||||||
|
Error, ///< input character broke message decoding
|
||||||
|
};
|
||||||
|
|
||||||
|
inline Protocol()
|
||||||
|
: rqState(RequestStates::Code)
|
||||||
|
, requestMsg(RequestMsgCodes::unknown, 0)
|
||||||
|
, rspState(ResponseStates::RequestCode)
|
||||||
|
, responseMsg(RequestMsg(RequestMsgCodes::unknown, 0), ResponseMsgParamCodes::unknown, 0) {
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Takes the input byte c and steps one step through the state machine
|
||||||
|
/// @returns state of the message being decoded
|
||||||
|
DecodeStatus DecodeRequest(uint8_t c);
|
||||||
|
|
||||||
|
/// Decodes response message in rxbuff
|
||||||
|
/// @returns decoded response message structure
|
||||||
|
DecodeStatus DecodeResponse(uint8_t c);
|
||||||
|
|
||||||
|
/// Encodes request message msg into txbuff memory
|
||||||
/// It is expected the txbuff is large enough to fit the message
|
/// It is expected the txbuff is large enough to fit the message
|
||||||
void Encode(uint8_t *txbuff, const Msg &msg);
|
/// @returns number of bytes written into txbuff
|
||||||
|
static uint8_t EncodeRequest(const RequestMsg &msg, uint8_t *txbuff);
|
||||||
|
|
||||||
|
/// Encode generic response Command Accepted or Rejected
|
||||||
|
/// @param msg source request message for this response
|
||||||
|
/// @returns number of bytes written into txbuff
|
||||||
|
static uint8_t EncodeResponseCmdAR(const RequestMsg &msg, ResponseMsgParamCodes ar, uint8_t *txbuff);
|
||||||
|
|
||||||
|
/// Encode response to Read FINDA query
|
||||||
|
/// @param msg source request message for this response
|
||||||
|
/// @param findaValue 1/0 (on/off) status of FINDA
|
||||||
|
/// @returns number of bytes written into txbuff
|
||||||
|
static uint8_t EncodeResponseReadFINDA(const RequestMsg &msg, uint8_t findaValue, uint8_t *txbuff);
|
||||||
|
|
||||||
|
/// Encode response to Version query
|
||||||
|
/// @param msg source request message for this response
|
||||||
|
/// @param value version number (0-255)
|
||||||
|
/// @returns number of bytes written into txbuff
|
||||||
|
static uint8_t EncodeResponseVersion(const RequestMsg &msg, uint8_t value, uint8_t *txbuff);
|
||||||
|
|
||||||
|
/// Encode response to Query operation status
|
||||||
|
/// @param msg source request message for this response
|
||||||
|
/// @param code status of operation (Processing, Error, Finished)
|
||||||
|
/// @param value related to status of operation(e.g. error code or progress)
|
||||||
|
/// @returns number of bytes written into txbuff
|
||||||
|
static uint8_t EncodeResponseQueryOperation(const RequestMsg &msg, ResponseMsgParamCodes code, uint8_t value, uint8_t *txbuff);
|
||||||
|
|
||||||
|
/// @returns the most recently lexed request message
|
||||||
|
inline const RequestMsg GetRequestMsg() const { return requestMsg; }
|
||||||
|
|
||||||
|
/// @returns the most recently lexed response message
|
||||||
|
inline const ResponseMsg GetResponseMsg() const { return responseMsg; }
|
||||||
|
|
||||||
|
private:
|
||||||
|
enum class RequestStates : uint8_t {
|
||||||
|
Code, ///< starting state - expects message code
|
||||||
|
Value, ///< expecting code value
|
||||||
|
Error ///< automaton in error state
|
||||||
|
};
|
||||||
|
|
||||||
|
RequestStates rqState;
|
||||||
|
RequestMsg requestMsg;
|
||||||
|
|
||||||
|
enum class ResponseStates : uint8_t {
|
||||||
|
RequestCode, ///< starting state - expects message code
|
||||||
|
RequestValue, ///< expecting code value
|
||||||
|
ParamCode, ///< expecting param code
|
||||||
|
ParamValue, ///< expecting param value
|
||||||
|
Error ///< automaton in error state
|
||||||
|
};
|
||||||
|
|
||||||
|
ResponseStates rspState;
|
||||||
|
ResponseMsg responseMsg;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace modules
|
} // namespace modules
|
||||||
|
|
|
||||||
|
|
@ -0,0 +1 @@
|
||||||
|
int main() {}
|
||||||
|
|
@ -1,5 +1,5 @@
|
||||||
# define the test executable
|
# define the test executable
|
||||||
add_executable(protocol_tests test_protocol.cpp)
|
add_executable(protocol_tests ../../../../src/modules/protocol.cpp test_protocol.cpp)
|
||||||
|
|
||||||
# define required search paths
|
# define required search paths
|
||||||
target_include_directories(protocol_tests PUBLIC ${CMAKE_SOURCE_DIR}/src/modules)
|
target_include_directories(protocol_tests PUBLIC ${CMAKE_SOURCE_DIR}/src/modules)
|
||||||
|
|
|
||||||
|
|
@ -3,6 +3,443 @@
|
||||||
|
|
||||||
using Catch::Matchers::Equals;
|
using Catch::Matchers::Equals;
|
||||||
|
|
||||||
TEST_CASE("protocol::1", "[protocol]") {
|
TEST_CASE("protocol::EncodeRequests", "[protocol]") {
|
||||||
CHECK(true);
|
using namespace modules;
|
||||||
|
|
||||||
|
RequestMsgCodes code;
|
||||||
|
uint8_t value;
|
||||||
|
std::tie(code, value) = GENERATE(
|
||||||
|
std::make_tuple(RequestMsgCodes::Button, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Button, 1),
|
||||||
|
std::make_tuple(RequestMsgCodes::Button, 2),
|
||||||
|
std::make_tuple(RequestMsgCodes::Cut, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Eject, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Finda, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Load, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Load, 1),
|
||||||
|
std::make_tuple(RequestMsgCodes::Load, 2),
|
||||||
|
std::make_tuple(RequestMsgCodes::Load, 3),
|
||||||
|
std::make_tuple(RequestMsgCodes::Load, 4),
|
||||||
|
std::make_tuple(RequestMsgCodes::Mode, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Mode, 1),
|
||||||
|
std::make_tuple(RequestMsgCodes::Query, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Reset, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Tool, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Tool, 1),
|
||||||
|
std::make_tuple(RequestMsgCodes::Tool, 2),
|
||||||
|
std::make_tuple(RequestMsgCodes::Tool, 3),
|
||||||
|
std::make_tuple(RequestMsgCodes::Tool, 4),
|
||||||
|
std::make_tuple(RequestMsgCodes::Unload, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Version, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::Version, 1),
|
||||||
|
std::make_tuple(RequestMsgCodes::Version, 2),
|
||||||
|
std::make_tuple(RequestMsgCodes::Wait, 0),
|
||||||
|
std::make_tuple(RequestMsgCodes::unknown, 0));
|
||||||
|
|
||||||
|
std::array<uint8_t, 3> txbuff;
|
||||||
|
|
||||||
|
CHECK(Protocol::EncodeRequest(RequestMsg(code, value), txbuff.data()) == 3);
|
||||||
|
CHECK(txbuff[0] == (uint8_t)code);
|
||||||
|
CHECK(txbuff[1] == value + '0');
|
||||||
|
CHECK(txbuff[2] == '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::EncodeResponseCmdAR", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
|
||||||
|
auto requestMsg = GENERATE(
|
||||||
|
RequestMsg(RequestMsgCodes::Button, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Button, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Button, 2),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Cut, 0),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Mode, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Mode, 1),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Unload, 0),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Wait, 0));
|
||||||
|
|
||||||
|
auto responseStatus = GENERATE(ResponseMsgParamCodes::Accepted, ResponseMsgParamCodes::Rejected);
|
||||||
|
|
||||||
|
std::array<uint8_t, 8> txbuff;
|
||||||
|
uint8_t msglen = Protocol::EncodeResponseCmdAR(requestMsg, responseStatus, txbuff.data());
|
||||||
|
|
||||||
|
CHECK(msglen == 5);
|
||||||
|
CHECK(txbuff[0] == (uint8_t)requestMsg.code);
|
||||||
|
CHECK(txbuff[1] == requestMsg.value + '0');
|
||||||
|
CHECK(txbuff[2] == ' ');
|
||||||
|
CHECK(txbuff[3] == (uint8_t)responseStatus);
|
||||||
|
CHECK(txbuff[4] == '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::EncodeResponseReadFINDA", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
auto requestMsg = RequestMsg(RequestMsgCodes::Finda, 0);
|
||||||
|
|
||||||
|
uint8_t findaStatus = GENERATE(0, 1);
|
||||||
|
|
||||||
|
std::array<uint8_t, 8> txbuff;
|
||||||
|
uint8_t msglen = Protocol::EncodeResponseReadFINDA(requestMsg, findaStatus, txbuff.data());
|
||||||
|
|
||||||
|
CHECK(msglen == 6);
|
||||||
|
CHECK(txbuff[0] == (uint8_t)requestMsg.code);
|
||||||
|
CHECK(txbuff[1] == requestMsg.value + '0');
|
||||||
|
CHECK(txbuff[2] == ' ');
|
||||||
|
CHECK(txbuff[3] == (uint8_t)ResponseMsgParamCodes::Accepted);
|
||||||
|
CHECK(txbuff[4] == findaStatus + '0');
|
||||||
|
CHECK(txbuff[5] == '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::EncodeResponseVersion", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
|
||||||
|
std::uint8_t versionQueryType = GENERATE(0, 1, 2, 3);
|
||||||
|
auto requestMsg = RequestMsg(RequestMsgCodes::Version, versionQueryType);
|
||||||
|
|
||||||
|
auto version = GENERATE(0, 1, 2, 3, 4, 10, 11, 12, 20, 99, 100, 101, 255);
|
||||||
|
|
||||||
|
std::array<uint8_t, 8> txbuff;
|
||||||
|
uint8_t msglen = Protocol::EncodeResponseVersion(requestMsg, version, txbuff.data());
|
||||||
|
|
||||||
|
CHECK(msglen <= 8);
|
||||||
|
CHECK(txbuff[0] == (uint8_t)requestMsg.code);
|
||||||
|
CHECK(txbuff[1] == requestMsg.value + '0');
|
||||||
|
CHECK(txbuff[2] == ' ');
|
||||||
|
CHECK(txbuff[3] == (uint8_t)ResponseMsgParamCodes::Accepted);
|
||||||
|
|
||||||
|
if (version < 10) {
|
||||||
|
CHECK(txbuff[4] == version + '0');
|
||||||
|
} else if (version < 100) {
|
||||||
|
CHECK(txbuff[4] == version / 10 + '0');
|
||||||
|
CHECK(txbuff[5] == version % 10 + '0');
|
||||||
|
} else {
|
||||||
|
CHECK(txbuff[4] == version / 100 + '0');
|
||||||
|
CHECK(txbuff[5] == (version / 10) % 10 + '0');
|
||||||
|
CHECK(txbuff[6] == version % 10 + '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
CHECK(txbuff[msglen - 1] == '\n');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::EncodeResponseQueryOperation", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
|
||||||
|
auto requestMsg = GENERATE(
|
||||||
|
RequestMsg(RequestMsgCodes::Cut, 0),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Eject, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Load, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 0),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 1),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 2),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 3),
|
||||||
|
RequestMsg(RequestMsgCodes::Tool, 4),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Unload, 0),
|
||||||
|
|
||||||
|
RequestMsg(RequestMsgCodes::Wait, 0));
|
||||||
|
|
||||||
|
auto responseStatus = GENERATE(ResponseMsgParamCodes::Processing, ResponseMsgParamCodes::Error, ResponseMsgParamCodes::Finished);
|
||||||
|
|
||||||
|
auto value = GENERATE(0, 1, 2, 3, 10, 11, 99, 100, 101, 102, 200, 255);
|
||||||
|
|
||||||
|
std::array<uint8_t, 8> txbuff;
|
||||||
|
uint8_t msglen = Protocol::EncodeResponseQueryOperation(requestMsg, responseStatus, value, txbuff.data());
|
||||||
|
|
||||||
|
CHECK(msglen <= 8);
|
||||||
|
CHECK(txbuff[0] == (uint8_t)requestMsg.code);
|
||||||
|
CHECK(txbuff[1] == requestMsg.value + '0');
|
||||||
|
CHECK(txbuff[2] == ' ');
|
||||||
|
CHECK(txbuff[3] == (uint8_t)responseStatus);
|
||||||
|
|
||||||
|
if (responseStatus == ResponseMsgParamCodes::Finished) {
|
||||||
|
CHECK(txbuff[4] == '\n');
|
||||||
|
CHECK(msglen == 5);
|
||||||
|
} else {
|
||||||
|
if (value < 10) {
|
||||||
|
CHECK(txbuff[4] == value + '0');
|
||||||
|
} else if (value < 100) {
|
||||||
|
CHECK(txbuff[4] == value / 10 + '0');
|
||||||
|
CHECK(txbuff[5] == value % 10 + '0');
|
||||||
|
} else {
|
||||||
|
CHECK(txbuff[4] == value / 100 + '0');
|
||||||
|
CHECK(txbuff[5] == (value / 10) % 10 + '0');
|
||||||
|
CHECK(txbuff[6] == value % 10 + '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
CHECK(txbuff[msglen - 1] == '\n');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::DecodeRequest", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
const char *rxbuff = GENERATE(
|
||||||
|
"B0\n", "B1\n", "B2\n",
|
||||||
|
"E0\n", "E1\n", "E2\n", "E3\n", "E4\n",
|
||||||
|
"K0\n",
|
||||||
|
"L0\n", "L1\n", "L2\n", "L3\n", "L4\n",
|
||||||
|
"M0\n", "M1\n",
|
||||||
|
"P0\n",
|
||||||
|
"Q0\n",
|
||||||
|
"S0\n", "S1\n", "S2\n", "S3\n",
|
||||||
|
"T0\n", "T1\n", "T2\n", "T3\n",
|
||||||
|
"U0\n",
|
||||||
|
"W0\n",
|
||||||
|
"X0\n");
|
||||||
|
|
||||||
|
const char *pc = rxbuff;
|
||||||
|
for (;;) {
|
||||||
|
uint8_t c = *pc++;
|
||||||
|
if (c == 0) {
|
||||||
|
// end of input test data
|
||||||
|
break;
|
||||||
|
} else if (c == '\n') {
|
||||||
|
// regular end of message line
|
||||||
|
CHECK(p.DecodeRequest(c) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
} else {
|
||||||
|
CHECK(p.DecodeRequest(c) == Protocol::DecodeStatus::NeedMoreData);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// check the message type
|
||||||
|
const RequestMsg &rq = p.GetRequestMsg();
|
||||||
|
CHECK((uint8_t)rq.code == rxbuff[0]);
|
||||||
|
CHECK(rq.value == rxbuff[1] - '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::DecodeResponseReadFinda", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
const char *rxbuff = GENERATE(
|
||||||
|
"P0 A0\n",
|
||||||
|
"P0 A1\n");
|
||||||
|
|
||||||
|
const char *pc = rxbuff;
|
||||||
|
for (;;) {
|
||||||
|
uint8_t c = *pc++;
|
||||||
|
if (c == 0) {
|
||||||
|
// end of input test data
|
||||||
|
break;
|
||||||
|
} else if (c == '\n') {
|
||||||
|
// regular end of message line
|
||||||
|
CHECK(p.DecodeResponse(c) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
} else {
|
||||||
|
CHECK(p.DecodeResponse(c) == Protocol::DecodeStatus::NeedMoreData);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// check the message type
|
||||||
|
const ResponseMsg &rsp = p.GetResponseMsg();
|
||||||
|
CHECK((uint8_t)rsp.request.code == rxbuff[0]);
|
||||||
|
CHECK(rsp.request.value == rxbuff[1] - '0');
|
||||||
|
CHECK((uint8_t)rsp.paramCode == rxbuff[3]);
|
||||||
|
CHECK((uint8_t)rsp.paramValue == rxbuff[4] - '0');
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::DecodeResponseQueryOperation", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
const char *cmdReference = GENERATE(
|
||||||
|
"E0", "E1", "E2", "E3", "E4",
|
||||||
|
"K0",
|
||||||
|
"L0", "L1", "L2", "L3", "L4",
|
||||||
|
"T0", "T1", "T2", "T3",
|
||||||
|
"U0",
|
||||||
|
"W0");
|
||||||
|
|
||||||
|
const char *status = GENERATE(
|
||||||
|
"P0", "P1", "E0", "E1", "E9", "F");
|
||||||
|
|
||||||
|
std::string rxbuff(cmdReference);
|
||||||
|
rxbuff += ' ';
|
||||||
|
rxbuff += status;
|
||||||
|
rxbuff += '\n';
|
||||||
|
|
||||||
|
const char *pc = rxbuff.c_str();
|
||||||
|
for (;;) {
|
||||||
|
uint8_t c = *pc++;
|
||||||
|
if (c == 0) {
|
||||||
|
// end of input test data
|
||||||
|
break;
|
||||||
|
} else if (c == '\n') {
|
||||||
|
// regular end of message line
|
||||||
|
CHECK(p.DecodeResponse(c) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
} else {
|
||||||
|
CHECK(p.DecodeResponse(c) == Protocol::DecodeStatus::NeedMoreData);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// check the message type
|
||||||
|
const ResponseMsg &rsp = p.GetResponseMsg();
|
||||||
|
CHECK((uint8_t)rsp.request.code == rxbuff[0]);
|
||||||
|
CHECK(rsp.request.value == rxbuff[1] - '0');
|
||||||
|
CHECK((uint8_t)rsp.paramCode == rxbuff[3]);
|
||||||
|
if ((uint8_t)rsp.paramCode != (uint8_t)ResponseMsgParamCodes::Finished) {
|
||||||
|
CHECK((uint8_t)rsp.paramValue == rxbuff[4] - '0');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::DecodeRequestErrors", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
const char b0[] = "b0";
|
||||||
|
CHECK(p.DecodeRequest(b0[0]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b0[1]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
|
||||||
|
// reset protokol decoder
|
||||||
|
CHECK(p.DecodeRequest('\n') == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
|
||||||
|
const char B1_[] = "B1 \n";
|
||||||
|
CHECK(p.DecodeRequest(B1_[0]) == Protocol::DecodeStatus::NeedMoreData);
|
||||||
|
CHECK(p.DecodeRequest(B1_[1]) == Protocol::DecodeStatus::NeedMoreData);
|
||||||
|
CHECK(p.DecodeRequest(B1_[2]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(B1_[3]) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
|
||||||
|
const char _B2[] = " B2\n";
|
||||||
|
CHECK(p.DecodeRequest(_B2[0]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B2[1]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B2[2]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B2[3]) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
|
||||||
|
const char _B0_[] = " B0 ";
|
||||||
|
CHECK(p.DecodeRequest(_B0_[0]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B0_[1]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B0_[2]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(_B0_[3]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest('\n') == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("protocol::DecodeResponseErrors", "[protocol]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
|
||||||
|
const char b0[] = "b0 A\n";
|
||||||
|
CHECK(p.DecodeRequest(b0[0]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b0[1]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b0[2]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b0[3]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b0[4]) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
|
||||||
|
const char b1[] = "b0A\n";
|
||||||
|
CHECK(p.DecodeRequest(b1[0]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b1[1]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b1[2]) == Protocol::DecodeStatus::Error);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
CHECK(p.DecodeRequest(b1[3]) == Protocol::DecodeStatus::MessageCompleted);
|
||||||
|
CHECK(p.GetRequestMsg().code == RequestMsgCodes::unknown);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Beware - this test makes 18M+ combinations, run only when changing the implementation of the codec
|
||||||
|
// Therefore it is disabled [.] by default
|
||||||
|
TEST_CASE("protocol::DecodeResponseErrorsCross", "[protocol][.]") {
|
||||||
|
using namespace modules;
|
||||||
|
Protocol p;
|
||||||
|
|
||||||
|
const char *validInitialSpaces = "";
|
||||||
|
const char *invalidInitialSpaces = GENERATE(" ", " ");
|
||||||
|
bool viInitialSpace = GENERATE(true, false);
|
||||||
|
|
||||||
|
const char *validReqCode = GENERATE("B", "E", "K", "L", "M", "P", "Q", "S", "T", "U", "W", "X");
|
||||||
|
const char *invalidReqCode = GENERATE("A", "R", "F");
|
||||||
|
bool viReqCode = GENERATE(true, false);
|
||||||
|
|
||||||
|
const char *validReqValue = GENERATE("0", "1", "2", "3", "4");
|
||||||
|
// these are silently accepted
|
||||||
|
// const char *invalidReqValue = GENERATE(/*"5", */"10", "100");
|
||||||
|
// bool viReqValue = GENERATE(true, false);
|
||||||
|
|
||||||
|
const char *validSpace = " ";
|
||||||
|
const char *invalidSpace = GENERATE("", " ");
|
||||||
|
bool viSpace = GENERATE(true, false);
|
||||||
|
|
||||||
|
const char *validRspCode = GENERATE("A", "R", "P", "E", "F");
|
||||||
|
const char *invalidRspCode = GENERATE("B", "K", "L", "M", "Q");
|
||||||
|
bool viRspCode = GENERATE(true, false);
|
||||||
|
|
||||||
|
const char *validRspValue = GENERATE("0", "1", "2", "3", "10", "11", "100", "255");
|
||||||
|
|
||||||
|
const char *validTerminatingSpaces = "";
|
||||||
|
const char *invalidTerminatingSpaces = GENERATE(" ", " ");
|
||||||
|
bool viTerminatingSpaces = GENERATE(true, false);
|
||||||
|
|
||||||
|
// skip valid combinations
|
||||||
|
std::string msg;
|
||||||
|
msg += viInitialSpace ? validInitialSpaces : invalidInitialSpaces;
|
||||||
|
msg += viReqCode ? validReqCode : invalidReqCode;
|
||||||
|
msg += validReqValue; //viReqValue ? validReqValue : invalidReqValue;
|
||||||
|
msg += viSpace ? validSpace : invalidSpace;
|
||||||
|
const char *rspCode = viRspCode ? validRspCode : invalidRspCode;
|
||||||
|
msg += rspCode;
|
||||||
|
if (rspCode[0] == 'F') {
|
||||||
|
// this one doesn't have any value behind
|
||||||
|
} else {
|
||||||
|
msg += validRspValue;
|
||||||
|
}
|
||||||
|
msg += viTerminatingSpaces ? validTerminatingSpaces : invalidTerminatingSpaces;
|
||||||
|
msg += '\n';
|
||||||
|
|
||||||
|
bool shouldPass = viInitialSpace && viReqCode && /*viReqValue && */ viSpace && viRspCode && viTerminatingSpaces;
|
||||||
|
bool failed = false;
|
||||||
|
std::for_each(msg.cbegin(), msg.cend(), [&](uint8_t c) {
|
||||||
|
if (p.DecodeResponse(c) == Protocol::DecodeStatus::Error) {
|
||||||
|
failed = true;
|
||||||
|
}
|
||||||
|
});
|
||||||
|
CHECK(failed != shouldPass); // it must have failed!
|
||||||
|
if (failed) {
|
||||||
|
CHECK(p.GetResponseMsg().paramCode == ResponseMsgParamCodes::unknown);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue