diff --git a/.gitignore b/.gitignore index ea9338f..0af9c12 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ .idea .vscode +.claude .venv _*/ cmake-build-debug/ \ No newline at end of file diff --git a/CMLibStorage.cmake b/CMLibStorage.cmake index 7e7142d..36796ba 100644 --- a/CMLibStorage.cmake +++ b/CMLibStorage.cmake @@ -1,3 +1,7 @@ +FIND_PACKAGE(CMLIB REQUIRED COMPONENTS CMCONF) + +CMCONF_INIT_SYSTEM(FLEET_PROTOCOL) + SET(STORAGE_LIST DEP) SET(STORAGE_LIST_DEP "https://github.com/bacpack-system/package-tracker.git") diff --git a/CMakeLists.txt b/CMakeLists.txt index 022ba78..2b9e609 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -55,17 +55,17 @@ IF (NOT BRINGAUTO_SYSTEM_DEP) ENDIF () FIND_PACKAGE(nlohmann_json 3.10.5 REQUIRED) -FIND_PACKAGE(Protobuf 3.21.12 REQUIRED) FIND_PACKAGE(fleet-protocol-interface 2.0.0 REQUIRED) FIND_PACKAGE(fleet-protocol-cxx-helpers-static 1.1.1 REQUIRED) +FIND_PACKAGE(async-function-execution-shared 1.0.0 REQUIRED) +FIND_PACKAGE(aeron 1.48.6 REQUIRED) IF (FLEET_PROTOCOL_BUILD_EXTERNAL_SERVER) - FIND_PACKAGE(fleet-http-client-shared 2.0.0 REQUIRED) + FIND_PACKAGE(fleet-http-client-shared 2.0.1 REQUIRED) ### fleet-http-client dependencies FIND_PACKAGE(Boost CONFIG REQUIRED) FIND_PACKAGE(ZLIB REQUIRED) FIND_PACKAGE(cpprestsdk REQUIRED) - FIND_PACKAGE(libbringauto_logger 1.2.0 REQUIRED) ENDIF () CMDEF_ADD_LIBRARY( @@ -74,18 +74,11 @@ CMDEF_ADD_LIBRARY( VERSION ${MISSION_MODULE_VERSION} ) -# Protobuf, JSON mission payload -SET(Protobuf_USE_STATIC_LIBS ON) -FILE(GLOB_RECURSE protobuf_mission_cpp_files "lib/protobuf-mission-module/*") -ADD_LIBRARY(message_handler_lib STATIC ${protobuf_mission_cpp_files}) -TARGET_INCLUDE_DIRECTORIES(message_handler_lib PUBLIC "lib/protobuf-mission-module/") -TARGET_LINK_LIBRARIES(message_handler_lib PUBLIC protobuf::libprotobuf nlohmann_json::nlohmann_json) - FILE(GLOB_RECURSE HEADERS "include/*") ADD_LIBRARY(mission_module_hpp INTERFACE ${HEADERS}) TARGET_INCLUDE_DIRECTORIES(mission_module_hpp INTERFACE "include/") -TARGET_LINK_LIBRARIES(mission_module_hpp INTERFACE message_handler_lib) +TARGET_LINK_LIBRARIES(mission_module_hpp INTERFACE nlohmann_json::nlohmann_json) FILE(GLOB_RECURSE SOURCES "source/bringauto/*") @@ -95,7 +88,6 @@ TARGET_LINK_LIBRARIES(mission_module_sources PUBLIC mission_module_hpp fleet-protocol-interface::common-headers-interface fleet-protocol-cxx-helpers-static::fleet-protocol-cxx-helpers-static - message_handler_lib ) IF (FLEET_PROTOCOL_BUILD_MODULE_GATEWAY) diff --git a/cmake/Dependencies.cmake b/cmake/Dependencies.cmake index 49bc780..ca31c83 100644 --- a/cmake/Dependencies.cmake +++ b/cmake/Dependencies.cmake @@ -1,14 +1,14 @@ SET(CMAKE_FIND_USE_CMAKE_SYSTEM_PATH FALSE) BA_PACKAGE_LIBRARY(fleet-protocol-interface v2.0.0 NO_DEBUG ON) -BA_PACKAGE_LIBRARY(fleet-protocol-cxx-helpers-static v1.1.1) +BA_PACKAGE_LIBRARY(fleet-protocol-cpp v1.2.0) +BA_PACKAGE_LIBRARY(async-function-execution v1.0.0) +BA_PACKAGE_LIBRARY(aeron v1.48.6) BA_PACKAGE_LIBRARY(zlib v1.2.11) BA_PACKAGE_LIBRARY(nlohmann-json v3.10.5 NO_DEBUG ON) -BA_PACKAGE_LIBRARY(protobuf v4.21.12) IF (FLEET_PROTOCOL_BUILD_EXTERNAL_SERVER) - BA_PACKAGE_LIBRARY(fleet-http-client-shared v2.0.0) + BA_PACKAGE_LIBRARY(fleet-http-client-shared v2.0.1) BA_PACKAGE_LIBRARY(boost v1.86.0) BA_PACKAGE_LIBRARY(cpprestsdk v2.10.20) - BA_PACKAGE_LIBRARY(ba-logger v1.2.0) ENDIF () diff --git a/docs/mission_module.md b/docs/mission_module.md index 2a788a2..b4ce508 100644 --- a/docs/mission_module.md +++ b/docs/mission_module.md @@ -38,7 +38,7 @@ flowchart TD ## Structure -Below, the data passed in the messages used in the External Protocol are described. The data structure can also be found in the [.proto](../lib/protobuf-mission-module/) file. +Below, the data passed in the messages used in the External Protocol are described. ## Status payload data @@ -166,8 +166,8 @@ Example of command payload when there is no mission defined for the car: ## Validation -The validation of each of the messages is done against the message structure described above (and in the [.proto](../lib/protobuf-mission-module/) file). The functions for validation: +The validation of each of the messages is done against the message structure described above. The functions for validation are in `JsonValidator`: -- `parseAutonomyStatus` for status, -- `parseAutonomyError` for status error, -- `parseAutonomyCommand` for command. +- `JsonValidator::validateAutonomyStatus` for status, +- `JsonValidator::validateAutonomyError` for status error, +- `JsonValidator::validateAutonomyCommand` for command. diff --git a/include/bringauto/JsonHelper.hpp b/include/bringauto/JsonHelper.hpp new file mode 100644 index 0000000..6563b86 --- /dev/null +++ b/include/bringauto/JsonHelper.hpp @@ -0,0 +1,81 @@ +#pragma once + +#include +#include +#include + +#include + + +namespace bringauto { + +/** + * @brief Utility class for converting between buffers, JSON objects, and mission module enums + * + * Represents a collection of static conversion and validation utilities tied to the + * mission module's JSON message format. Its purpose is to centralise all JSON serialisation, + * deserialisation, and structural validation so that the rest of the module does not + * depend directly on the nlohmann::json API. + */ +class JsonHelper { +public: + /** + * @brief Parses a buffer into a JSON object + * @param json Output JSON object + * @param buffer Input buffer containing a JSON string + * @return OK on success, NOT_OK if parsing fails + */ + static int bufferToJson(nlohmann::ordered_json& json, const buffer& buffer); + + /** + * @brief Serializes a JSON object into a buffer + * @param buffer Output buffer + * @param json Input JSON object + * @return OK on success, NOT_OK if allocation fails + */ + static int jsonToBuffer(buffer* buffer, const nlohmann::ordered_json& json); + + /** + * @brief Converts a string representation of autonomy state to the corresponding enum value + * @param state String state value (e.g. "DRIVE", "IN_STOP") + * @return Corresponding AutonomyState enum value, ERROR if unrecognized + */ + static modules::mission_module::AutonomyState stringToAutonomyState(std::string_view state); + + /** + * @brief Converts an AutonomyState enum value to its string representation + * @param state AutonomyState enum value + * @return String representation (e.g. "DRIVE", "IN_STOP") + */ + static std::string autonomyStateToString(modules::mission_module::AutonomyState state); + + /** + * @brief Converts an AutonomyAction enum value to its string representation + * @param action AutonomyAction enum value + * @return String representation (e.g. "START", "STOP", "NO_ACTION") + */ + static std::string autonomyActionToString(modules::mission_module::AutonomyAction action); + + /** + * @brief Checks whether a JSON object contains all required fields for an AutonomyStatus message + * @param status JSON object to validate + * @return true if all required fields are present + */ + static bool isValidAutonomyStatus(const nlohmann::ordered_json& status); + + /** + * @brief Checks whether a JSON object contains all required fields for an AutonomyCommand message + * @param command JSON object to validate + * @return true if all required fields are present + */ + static bool isValidAutonomyCommand(const nlohmann::ordered_json& command); + + /** + * @brief Checks whether a JSON object contains all required fields for an AutonomyError message + * @param errorMessage JSON object to validate + * @return true if all required fields are present + */ + static bool isValidAutonomyError(const nlohmann::ordered_json& errorMessage); +}; + +} diff --git a/include/bringauto/JsonValidator.hpp b/include/bringauto/JsonValidator.hpp new file mode 100644 index 0000000..8a4886d --- /dev/null +++ b/include/bringauto/JsonValidator.hpp @@ -0,0 +1,35 @@ +#pragma once + +#include + + +namespace bringauto { + +/** + * @brief Validates JSON messages against the expected mission module message schemas + */ +class JsonValidator { +public: + /** + * @brief Validates that a JSON string contains the required fields for an AutonomyStatus message + * @param status JSON string to validate + * @return OK if valid, NOT_OK otherwise + */ + static int validateAutonomyStatus(const std::string &status); + + /** + * @brief Validates that a JSON string contains the required fields for an AutonomyCommand message + * @param command JSON string to validate + * @return OK if valid, NOT_OK otherwise + */ + static int validateAutonomyCommand(const std::string &command); + + /** + * @brief Validates that a JSON string contains the required fields for an AutonomyError message + * @param errorMessage JSON string to validate + * @return OK if valid, NOT_OK otherwise + */ + static int validateAutonomyError(const std::string &errorMessage); +}; + +} \ No newline at end of file diff --git a/include/bringauto/ba_json/JsonHelper.hpp b/include/bringauto/ba_json/JsonHelper.hpp deleted file mode 100644 index 408ea67..0000000 --- a/include/bringauto/ba_json/JsonHelper.hpp +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once - -#include - -#include - -#include - -namespace bringauto::ba_json { - -using json = nlohmann::ordered_json; - -class JsonHelper { -public: - static int bufferToJson(json& json, const buffer& buffer); - - static int jsonToBuffer(buffer* buffer, const json& json); - - static MissionModule::AutonomyStatus_State stringToAutonomyState(const std::string_view &state); - - static std::string autonomyStateToString(MissionModule::AutonomyStatus_State state); - - static std::string autonomyActionToString(MissionModule::AutonomyCommand_Action action); - -}; -} diff --git a/include/bringauto/modules/mission_module/AutonomyAction.hpp b/include/bringauto/modules/mission_module/AutonomyAction.hpp new file mode 100644 index 0000000..2e13ded --- /dev/null +++ b/include/bringauto/modules/mission_module/AutonomyAction.hpp @@ -0,0 +1,15 @@ +#pragma once + + +namespace bringauto::modules::mission_module { + +/** + * @brief Represents the action to be performed by the autonomy device + */ +enum class AutonomyAction { + NO_ACTION, + STOP, + START +}; + +} \ No newline at end of file diff --git a/include/bringauto/modules/mission_module/AutonomyState.hpp b/include/bringauto/modules/mission_module/AutonomyState.hpp new file mode 100644 index 0000000..51128c3 --- /dev/null +++ b/include/bringauto/modules/mission_module/AutonomyState.hpp @@ -0,0 +1,17 @@ +#pragma once + + +namespace bringauto::modules::mission_module { + +/** + * @brief Represents the driving state of the autonomy device + */ +enum class AutonomyState { + IDLE, + DRIVE, + IN_STOP, + OBSTACLE, + ERROR +}; + +} \ No newline at end of file diff --git a/include/bringauto/protobuf/ProtobufHelper.hpp b/include/bringauto/protobuf/ProtobufHelper.hpp deleted file mode 100644 index 4fca370..0000000 --- a/include/bringauto/protobuf/ProtobufHelper.hpp +++ /dev/null @@ -1,19 +0,0 @@ -#pragma once - -#include -#include - -namespace bringauto::protobuf { -class ProtobufHelper { -public: - static int serializeProtobufMessageToBuffer(struct buffer* message, const google::protobuf::Message &protobufMessage); - - static int validateAutonomyStatus(const std::string &status); - - static int validateAutonomyCommand(const std::string &command); - - static int validateAutonomyError(const std::string &errorMessage); - - -}; -} diff --git a/source/bringauto/JsonHelper.cpp b/source/bringauto/JsonHelper.cpp new file mode 100644 index 0000000..e1b5f6a --- /dev/null +++ b/source/bringauto/JsonHelper.cpp @@ -0,0 +1,68 @@ +#include + +#include + + +namespace bringauto { + +using json = nlohmann::ordered_json; +using namespace bringauto::modules::mission_module; + +int JsonHelper::bufferToJson(json& json, const buffer& buffer) { + const auto buffer_data = static_cast (buffer.data); + try { + json = json::parse(buffer_data, buffer_data + buffer.size_in_bytes); + } catch (json::parse_error &) { + return NOT_OK; + } + return OK; +} + +int JsonHelper::jsonToBuffer(buffer *buffer, const json& json) { + const std::string tmp = nlohmann::to_string(json); + if (allocate(buffer, tmp.size()) == NOT_OK) { + return NOT_OK; + } + std::memcpy(buffer->data, tmp.c_str(), tmp.size()); + return OK; +} + +AutonomyState JsonHelper::stringToAutonomyState(const std::string_view state) { + if (state == "IDLE") return AutonomyState::IDLE; + if (state == "DRIVE") return AutonomyState::DRIVE; + if (state == "IN_STOP") return AutonomyState::IN_STOP; + if (state == "OBSTACLE") return AutonomyState::OBSTACLE; + return AutonomyState::ERROR; +} + +std::string JsonHelper::autonomyStateToString(const AutonomyState state) { + switch (state) { + case AutonomyState::IDLE: return "IDLE"; + case AutonomyState::DRIVE: return "DRIVE"; + case AutonomyState::IN_STOP: return "IN_STOP"; + case AutonomyState::OBSTACLE: return "OBSTACLE"; + default: return "ERROR"; + } +} + +std::string JsonHelper::autonomyActionToString(const AutonomyAction action) { + switch (action) { + case AutonomyAction::STOP: return "STOP"; + case AutonomyAction::START: return "START"; + default: return "NO_ACTION"; + } +} + +bool JsonHelper::isValidAutonomyStatus(const json& status) { + return status.contains("state") && status.contains("telemetry") && status.contains("nextStop"); +} + +bool JsonHelper::isValidAutonomyCommand(const json& command) { + return command.contains("action") && command.contains("stops") && command.contains("route"); +} + +bool JsonHelper::isValidAutonomyError(const json& errorMessage) { + return errorMessage.contains("finishedStops"); +} + +} \ No newline at end of file diff --git a/source/bringauto/JsonValidator.cpp b/source/bringauto/JsonValidator.cpp new file mode 100644 index 0000000..a75f38a --- /dev/null +++ b/source/bringauto/JsonValidator.cpp @@ -0,0 +1,45 @@ +#include + +#include +#include + + +namespace bringauto { + +int JsonValidator::validateAutonomyStatus(const std::string &status) { + try { + const auto json = nlohmann::json::parse(status); + if (!json.contains("state") || !json.contains("telemetry") || !json.contains("nextStop")) { + return NOT_OK; + } + } catch (...) { + return NOT_OK; + } + return OK; +} + +int JsonValidator::validateAutonomyCommand(const std::string &command) { + try { + const auto json = nlohmann::json::parse(command); + if (!json.contains("action") || !json.contains("stops") || !json.contains("route")) { + return NOT_OK; + } + } catch (...) { + return NOT_OK; + } + return OK; +} + +int JsonValidator::validateAutonomyError(const std::string &errorMessage) { + try { + const auto json = nlohmann::json::parse(errorMessage); + if (!json.contains("finishedStops")) { + return NOT_OK; + } + } catch (...) { + return NOT_OK; + } + return OK; +} + +} \ No newline at end of file diff --git a/source/bringauto/ba_json/JsonHelper.cpp b/source/bringauto/ba_json/JsonHelper.cpp deleted file mode 100644 index aa6d8ad..0000000 --- a/source/bringauto/ba_json/JsonHelper.cpp +++ /dev/null @@ -1,70 +0,0 @@ -#include - -#include - - -namespace bringauto::ba_json { - -using json = nlohmann::ordered_json; - -int JsonHelper::bufferToJson(json& json, const buffer& buffer) { - const auto buffer_data = static_cast (buffer.data); - try { - json = json::parse(buffer_data, buffer_data + buffer.size_in_bytes); - } catch (json::parse_error &) { - return NOT_OK; - } - return OK; -} - -int JsonHelper::jsonToBuffer(buffer *buffer, const json& json) { - const std::string tmp = nlohmann::to_string(json); - if (allocate(buffer, tmp.size()) == NOT_OK) { - return NOT_OK; - } - std::memcpy(buffer->data, tmp.c_str(), tmp.size()); - return OK; -} - -MissionModule::AutonomyStatus_State JsonHelper::stringToAutonomyState(const std::string_view &state) { - if (state == "IDLE") { - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_IDLE; - } else if (state == "DRIVE") { - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_DRIVE; - } else if (state == "IN_STOP") { - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_IN_STOP; - } else if (state == "OBSTACLE") { - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_OBSTACLE; - } else if (state == "ERROR") { - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_ERROR; - } - return MissionModule::AutonomyStatus_State::AutonomyStatus_State_ERROR; -} - -std::string JsonHelper::autonomyStateToString(const MissionModule::AutonomyStatus_State state) { - switch (state) { - case MissionModule::AutonomyStatus_State::AutonomyStatus_State_IDLE: - return "IDLE"; - case MissionModule::AutonomyStatus_State::AutonomyStatus_State_DRIVE: - return "DRIVE"; - case MissionModule::AutonomyStatus_State::AutonomyStatus_State_IN_STOP: - return "IN_STOP"; - case MissionModule::AutonomyStatus_State::AutonomyStatus_State_OBSTACLE: - return "OBSTACLE"; - default: - return "ERROR"; - } -} - -std::string JsonHelper::autonomyActionToString(const MissionModule::AutonomyCommand_Action action) { - switch (action) { - case MissionModule::AutonomyCommand_Action::AutonomyCommand_Action_STOP: - return "STOP"; - case MissionModule::AutonomyCommand_Action::AutonomyCommand_Action_START: - return "DRIVE"; - default: - return "NO_ACTION"; - } -} - -} diff --git a/source/bringauto/modules/mission_module/devices/AutonomyDevice.cpp b/source/bringauto/modules/mission_module/devices/AutonomyDevice.cpp index 58d6535..8aad02c 100644 --- a/source/bringauto/modules/mission_module/devices/AutonomyDevice.cpp +++ b/source/bringauto/modules/mission_module/devices/AutonomyDevice.cpp @@ -1,5 +1,4 @@ -#include -#include +#include #include #include @@ -18,8 +17,8 @@ std::map AutonomyDevice::last_sent_stat int AutonomyDevice::send_status_condition(const struct buffer current_status, const struct buffer new_status, unsigned int device_type) { json current_status_json {}; json new_status_json {}; - if (ba_json::JsonHelper::bufferToJson(current_status_json, current_status) != OK || - ba_json::JsonHelper::bufferToJson(new_status_json, new_status) != OK) { + if (JsonHelper::bufferToJson(current_status_json, current_status) != OK || + JsonHelper::bufferToJson(new_status_json, new_status) != OK) { return NOT_OK; } @@ -44,20 +43,21 @@ int AutonomyDevice::generate_command(struct buffer *generated_command, const str json current_status_json {}; json new_status_json {}; json current_command_json {}; - if (ba_json::JsonHelper::bufferToJson(current_status_json, current_status) != OK || - ba_json::JsonHelper::bufferToJson(new_status_json, new_status) != OK || - ba_json::JsonHelper::bufferToJson(current_command_json, current_command) != OK) { + if (JsonHelper::bufferToJson(current_status_json, current_status) != OK || + JsonHelper::bufferToJson(new_status_json, new_status) != OK || + JsonHelper::bufferToJson(current_command_json, current_command) != OK) { return NOT_OK; } - if (ba_json::JsonHelper::stringToAutonomyState(std::string(current_status_json.at("state"))) == - MissionModule::AutonomyStatus_State_DRIVE && - ba_json::JsonHelper::stringToAutonomyState(std::string(new_status_json.at("state"))) == - MissionModule::AutonomyStatus_State_IN_STOP && - !current_command_json.at("stops").empty()) { + if (!current_command_json.at("stops").empty() && + JsonHelper::stringToAutonomyState(std::string(new_status_json.at("state"))) == + AutonomyState::IN_STOP && + (JsonHelper::stringToAutonomyState(std::string(current_status_json.at("state"))) == + AutonomyState::DRIVE || + new_status_json.at("nextStop") == current_command_json.at("stops")[0])) { current_command_json.at("stops").erase(current_command_json.at("stops").begin()); } - return ba_json::JsonHelper::jsonToBuffer(generated_command, current_command_json); + return JsonHelper::jsonToBuffer(generated_command, current_command_json); } int AutonomyDevice::aggregate_status(struct buffer *aggregated_status, const struct buffer current_status, @@ -73,12 +73,12 @@ int AutonomyDevice::aggregate_error(struct buffer *error_message, const struct b const struct buffer status) { json status_json {}; json error_json {}; - if (ba_json::JsonHelper::bufferToJson(status_json, status) != OK || - ba_json::JsonHelper::bufferToJson(error_json, current_error_message) != OK) { + if (JsonHelper::bufferToJson(status_json, status) != OK || + JsonHelper::bufferToJson(error_json, current_error_message) != OK) { return NOT_OK; } - if (status_json.at("state") == ba_json::JsonHelper::autonomyStateToString(MissionModule::AutonomyStatus_State_IN_STOP)) { + if (status_json.at("state") == JsonHelper::autonomyStateToString(AutonomyState::IN_STOP)) { if (!error_json.at("finishedStops").empty()) { if (error_json.at("finishedStops")[error_json.at("finishedStops").size() - 1] != status_json.at("nextStop")) { error_json.at("finishedStops").push_back(status_json.at("nextStop")); @@ -88,15 +88,15 @@ int AutonomyDevice::aggregate_error(struct buffer *error_message, const struct b } } - return ba_json::JsonHelper::jsonToBuffer(error_message, error_json); + return JsonHelper::jsonToBuffer(error_message, error_json); } int AutonomyDevice::generate_first_command(struct buffer *default_command) { json command {}; - command["action"] = ba_json::JsonHelper::autonomyActionToString(MissionModule::AutonomyCommand_Action_NO_ACTION); + command["action"] = JsonHelper::autonomyActionToString(AutonomyAction::NO_ACTION); command["route"] = ""; command["stops"] = json::array(); - if (ba_json::JsonHelper::jsonToBuffer(default_command, command) != OK) { + if (JsonHelper::jsonToBuffer(default_command, command) != OK) { return NOT_OK; } return OK; @@ -104,24 +104,18 @@ int AutonomyDevice::generate_first_command(struct buffer *default_command) { int AutonomyDevice::status_data_valid(const struct buffer status) { json status_json {}; - if (ba_json::JsonHelper::bufferToJson(status_json, status) != OK) { + if (JsonHelper::bufferToJson(status_json, status) != OK) { return NOT_OK; } - if (protobuf::ProtobufHelper::validateAutonomyStatus(nlohmann::to_string(status_json)) != OK) { - return NOT_OK; - } - return OK; + return JsonHelper::isValidAutonomyStatus(status_json) ? OK : NOT_OK; } int AutonomyDevice::command_data_valid(const struct buffer command) { json command_json {}; - if (ba_json::JsonHelper::bufferToJson(command_json, command) != OK) { + if (JsonHelper::bufferToJson(command_json, command) != OK) { return NOT_OK; } - if (protobuf::ProtobufHelper::validateAutonomyCommand(nlohmann::to_string(command_json)) != OK) { - return NOT_OK; - } - return OK; + return JsonHelper::isValidAutonomyCommand(command_json) ? OK : NOT_OK; } } diff --git a/source/bringauto/protobuf/ProtobufHelper.cpp b/source/bringauto/protobuf/ProtobufHelper.cpp deleted file mode 100644 index 52ac535..0000000 --- a/source/bringauto/protobuf/ProtobufHelper.cpp +++ /dev/null @@ -1,48 +0,0 @@ -#include - -#include - -#include - -namespace bringauto::protobuf { -int ProtobufHelper::serializeProtobufMessageToBuffer(struct buffer* message, const google::protobuf::Message &protobufMessage) { - if (allocate(message, protobufMessage.ByteSizeLong()) == OK) { - protobufMessage.SerializeToArray(message->data, static_cast(message->size_in_bytes)); - return OK; - } - return NOT_OK; -} - -int ProtobufHelper::validateAutonomyStatus(const std::string &status) { - MissionModule::AutonomyStatus autonomyStatus {}; - const auto parse_status = google::protobuf::util::JsonStringToMessage( - status, &autonomyStatus - ); - if(!parse_status.ok()) { - return NOT_OK; - } - return OK; -} - -int ProtobufHelper::validateAutonomyCommand(const std::string &command) { - MissionModule::AutonomyCommand autonomyCommand {}; - const auto parse_status = google::protobuf::util::JsonStringToMessage( - command, &autonomyCommand - ); - if(!parse_status.ok()) { - return NOT_OK; - } - return OK; -} - -int ProtobufHelper::validateAutonomyError(const std::string &errorMessage) { - MissionModule::AutonomyError autonomyError {}; - const auto parse_status = google::protobuf::util::JsonStringToMessage( - errorMessage, &autonomyError - ); - if(!parse_status.ok()) { - return NOT_OK; - } - return OK; -} -} diff --git a/source/external_server_api.cpp b/source/external_server_api.cpp index a94163a..eed1a22 100644 --- a/source/external_server_api.cpp +++ b/source/external_server_api.cpp @@ -2,21 +2,36 @@ #include #include #include -#include +#include #include #include #include #include #include +#include #include #include +#include +#include +#include namespace bamm = bringauto::modules::mission_module; +using Validator = std::function; +struct StringConfigEntry { std::string* target; Validator validate; }; + +std::optional parseNonNegativeInt(const std::string& data) { + int value {}; + auto result = std::from_chars(data.data(), data.data() + data.size(), value); + if (result.ec != std::errc() || value < 0) { + return std::nullopt; + } + return value; +} + void *init(const config config_data) { - auto *context = new bamm::Context {}; const bringauto::fleet_protocol::cxx::KeyValueConfig config(config_data); std::string api_url {}; std::string api_key {}; @@ -27,62 +42,37 @@ void *init(const config config_data) { int delay_after_threshold_reached_ms {}; int retry_requests_delay_ms {}; - for (auto i = config.cbegin(); i != config.cend(); ++i) { - if (i->first == "api_url") { - if (!std::regex_match(i->second, std::regex(R"(^(http|https)://([\w-]+\.)?+[\w-]+(:[0-9]+)?(/[\w-]*)?+$)"))) { - delete context; - return nullptr; - } - api_url = i->second; - } - else if (i->first == "api_key") { - if (i->second.empty()) { - delete context; - return nullptr; - } - api_key = i->second; - } - else if (i->first == "company_name") { - if (!std::regex_match(i->second, std::regex("^[a-z0-9_]*$")) || i->second.empty()) { - delete context; - return nullptr; - } - company_name = i->second; - } - else if (i->first == "car_name") { - if (!std::regex_match(i->second, std::regex("^[a-z0-9_]*$")) || i->second.empty()) { - delete context; - return nullptr; - } - car_name = i->second; - } - else if (i->first == "max_requests_threshold_count") { - auto result = std::from_chars(i->second.data(), i->second.data() + i->second.size(), max_requests_threshold_count); - if (result.ec != std::errc() || max_requests_threshold_count < 0 || i->second.empty()) { - delete context; - return nullptr; - } - } - else if (i->first == "max_requests_threshold_period_ms") { - auto result = std::from_chars(i->second.data(), i->second.data() + i->second.size(), max_requests_threshold_period_ms); - if (result.ec != std::errc() || max_requests_threshold_period_ms < 0 || i->second.empty()) { - delete context; - return nullptr; - } - } - else if (i->first == "delay_after_threshold_reached_ms") { - auto result = std::from_chars(i->second.data(), i->second.data() + i->second.size(), delay_after_threshold_reached_ms); - if (result.ec != std::errc() || delay_after_threshold_reached_ms < 0 || i->second.empty()) { - delete context; + const std::regex alphanumeric_regex("^[a-z0-9_]*$"); + const std::regex url_regex(R"(^(http|https)://([\w-]+\.)?+[\w-]+(:[0-9]+)?(/[\w-]*)?+$)"); + + const std::map> string_config_keys { + { "api_url", { &api_url, [&url_regex](const std::string& v) { return std::regex_match(v, url_regex); } } }, + { "api_key", { &api_key, [](const std::string& v) { return !v.empty(); } } }, + { "company_name", { &company_name, [&alphanumeric_regex](const std::string& v) { return !v.empty() && std::regex_match(v, alphanumeric_regex); } } }, + { "car_name", { &car_name, [&alphanumeric_regex](const std::string& v) { return !v.empty() && std::regex_match(v, alphanumeric_regex); } } }, + }; + + const std::map> int_config_keys { + { "max_requests_threshold_count", &max_requests_threshold_count }, + { "max_requests_threshold_period_ms", &max_requests_threshold_period_ms }, + { "delay_after_threshold_reached_ms", &delay_after_threshold_reached_ms }, + { "retry_requests_delay_ms", &retry_requests_delay_ms } + }; + + for (auto entry = config.cbegin(); entry != config.cend(); ++entry) { + if (auto string_key = string_config_keys.find(entry->first); string_key != string_config_keys.end()) { + const auto& [target, validate] = string_key->second; + if (!validate(entry->second)) { return nullptr; } + *target = entry->second; } - else if (i->first == "retry_requests_delay_ms") { - auto result = std::from_chars(i->second.data(), i->second.data() + i->second.size(), retry_requests_delay_ms); - if (result.ec != std::errc() || retry_requests_delay_ms < 0 || i->second.empty()) { - delete context; + else if (auto int_key = int_config_keys.find(entry->first); int_key != int_config_keys.end()) { + auto value = parseNonNegativeInt(entry->second); + if (!value) { return nullptr; } + *int_key->second = *value; } } @@ -100,6 +90,7 @@ void *init(const config config_data) { .retryRequestsDelayMs = std::chrono::milliseconds(retry_requests_delay_ms) }; + auto *context = new bamm::Context {}; context->fleet_api_client = std::make_shared( fleet_api_config, request_frequency_guard_config ); @@ -129,7 +120,7 @@ int forward_status(const buffer device_status, const device_identification devic if(device.device_type == bamm::AUTONOMY_DEVICE_TYPE) { const bringauto::fleet_protocol::cxx::BufferAsString device_status_bas(&device_status); const auto device_status_str = std::string(device_status_bas.getStringView()); - if (bringauto::protobuf::ProtobufHelper::validateAutonomyStatus(device_status_str) != OK) { + if (bringauto::JsonValidator::validateAutonomyStatus(device_status_str) != OK) { return NOT_OK; } @@ -166,7 +157,7 @@ int forward_error_message(const buffer error_msg, const device_identification de if(device.device_type == bamm::AUTONOMY_DEVICE_TYPE) { const bringauto::fleet_protocol::cxx::BufferAsString error_msg_bas(&error_msg); const auto error_msg_str = std::string(error_msg_bas.getStringView()); - if (bringauto::protobuf::ProtobufHelper::validateAutonomyError(error_msg_str) != OK) { + if (bringauto::JsonValidator::validateAutonomyError(error_msg_str) != OK) { return NOT_OK; } @@ -279,7 +270,7 @@ int wait_for_command(int timeout_time_in_ms, void *context) { if(parse_commands) { std::string command_str = command->getPayload()->getData()->getJson().serialize(); - if (bringauto::protobuf::ProtobufHelper::validateAutonomyCommand(command_str) != OK) { + if (bringauto::JsonValidator::validateAutonomyCommand(command_str) != OK) { return NOT_OK; }