From 2daa7ca1090a48862483bdf6d65a83fb617f87b3 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Jonas=20Kieran=20R=C3=B6ger?=
 <jonas.kieran.roeger@iml.fraunhofer.de>
Date: Tue, 18 Feb 2025 13:02:54 +0000
Subject: [PATCH] feat: :sparkles: VDA5050 2.1.0 compatibility

* build: :arrow_up: use vda5050_message_structs 2.1.0.1

* chore: :bookmark: set version to 3.0.0

* docs(MapActionHandler): :memo: add MapActionHandler documentation (+example)

* docs(config): :memo: add new config table docs

* docs: :memo: update references to 2.1.0

* feat(ActionDeclarations): add map related action declarations

* feat(AgvDescription): :sparkles: make network configurable

* feat(AgvDescription): :sparkles: store user versions

* feat(MapActionHandler): :sparkles: add the MapActionHandler

* feat(MqttModule): use qos 0 except for connection (qos 1)

* feat(factsheet): :sparkles: gather information for new factsheet struct

* feat: :bookmark: set VDA5050 version to 2.1.0

* feat: :sparkles: fill vda5050::Error::errorHint fields

* fix(ActionTask): :bug: add guards for nullptr states

* fix(AgvDescription): :bug: remove localization parameters and update example

* test(MapActionHandler): :white_check_mark: add member function tests

* test: :bug: order test cases to fix instance init bug
---
 CMakeLists.txt                                |   6 +-
 README.md                                     |   7 +-
 cmake/ensure-deps.cmake                       |   2 +-
 docs/api.md                                   |  56 +++++-
 docs/configuration.md                         |  36 ++--
 docs/index.md                                 |  11 +-
 examples/example_config.toml                  |  34 ++--
 examples/src/full_config.cpp                  |   8 +-
 examples/src/handler_demo.cpp                 |  40 +++++
 .../private/vda5050++/core/factsheet/gather.h |  14 +-
 include/private/vda5050++/core/instance.h     |  10 ++
 .../vda5050++/core/messages/mqtt_module.h     |   3 -
 .../vda5050++/core/state/map_manager.h        |  90 ++++++++++
 .../core/state/state_event_handler.h          |  27 +++
 .../vda5050++/core/status_event_manager.h     |  24 +++
 .../agv_description/agv_description.h         |   7 +-
 .../config/agv_description_subconfig.h        |   6 +-
 .../public/vda5050++/events/status_event.h    |  28 +++
 .../vda5050++/handler/map_action_handler.h    | 120 +++++++++++++
 .../vda5050++/misc/action_declarations.h      |  88 +++++++++
 src/CMakeLists.txt                            |   2 +
 .../config/agv_description_subconfig.cpp      |  57 ++++--
 .../core/agv_handler/query_event_handler.cpp  |   8 +
 src/vda5050++/core/checks/action.cpp          |  21 +++
 src/vda5050++/core/checks/header.cpp          |   3 +
 src/vda5050++/core/checks/order.cpp           |  16 ++
 src/vda5050++/core/common/conversion.cpp      |   2 +
 .../factsheet/factsheet_event_handler.cpp     |   2 +-
 src/vda5050++/core/factsheet/gather.cpp       |  24 ++-
 src/vda5050++/core/instance.cpp               |   4 +-
 src/vda5050++/core/messages/mqtt_module.cpp   |  19 +-
 src/vda5050++/core/order/action_task.cpp      |  24 ++-
 src/vda5050++/core/state/map_manager.cpp      |  57 ++++++
 .../core/state/state_event_handler.cpp        |  37 ++++
 src/vda5050++/core/status_event_manager.cpp   |  24 +++
 src/vda5050++/handler/map_action_handler.cpp  |  85 +++++++++
 src/vda5050++/version.cpp                     |   2 +-
 test/CMakeLists.txt                           |   2 +
 test/vda5050++/core/factsheet/gather.cpp      |  25 ++-
 test/vda5050++/core/state/map_manager.cpp     | 104 +++++++++++
 test/vda5050++/handler/map_action_handler.cpp | 167 ++++++++++++++++++
 test/vda5050++/observer/message_observer.cpp  |   2 +-
 test/vda5050++/observer/order_observer.cpp    |   6 +-
 43 files changed, 1219 insertions(+), 91 deletions(-)
 create mode 100644 include/private/vda5050++/core/state/map_manager.h
 create mode 100644 include/public/vda5050++/handler/map_action_handler.h
 create mode 100644 src/vda5050++/core/state/map_manager.cpp
 create mode 100644 src/vda5050++/handler/map_action_handler.cpp
 create mode 100644 test/vda5050++/core/state/map_manager.cpp
 create mode 100644 test/vda5050++/handler/map_action_handler.cpp

diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6e9b922..39752cd 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -22,7 +22,7 @@ if(CMAKE_GENERATOR MATCHES "Ninja")
 endif()
 
 project(libvda5050++
-    VERSION 2.10.0
+    VERSION 3.0.0
     DESCRIPTION "Helper library for building VDA 5050 compliant software"
     LANGUAGES CXX)
 
@@ -150,7 +150,9 @@ if(CODE_COVERAGE AND BUILD_TESTING AND CMAKE_CXX_COMPILER_ID STREQUAL "Clang")
     target_code_coverage(vda5050++)
     target_code_coverage(vda5050++_test
         ARGS
-        --reporter junit --out vda5050++_test.xml
+        --reporter junit --out vda5050++_test.xml # report for for gitlab ci
+        --order lex # this is a rather ugly workaround, that prevents static initialization
+                    # bugs of the instance in the test-cases
     )
 endif()
 
diff --git a/README.md b/README.md
index aeda572..bcc65ed 100644
--- a/README.md
+++ b/README.md
@@ -14,7 +14,12 @@
 
 _The current documentation can be viewed [online](http://silicon-economy.pages.fraunhofer.de/services/odyn/vda5050/libvda5050pp)._
 
-libVDA5050++ is a complete and open source implementation of the standard VDA5050 version 2.0.0 ([VDA5050 Github Repo](https://github.com/VDA5050/VDA5050) / [VDA5050 standard v2.0.0](https://github.com/VDA5050/VDA5050/tree/2.0.0)). The aim of the VDA5050 standard is to standardize the interface for communication of automated guided vehicles (AGVs) between the control system and the AGVs. Today's systems are mainly isolated solutions, which means that the control of AGVs is proprietary and therefore manufacturer-specific. This means that AGVs from different manufacturers cannot be controlled by a control system of a specific manufacturer. The VDA5050 standard, which was developed by the German Association of the Automotive Industry (Verband der Automobilindustrie e. V. (VDA)) VDA and Mechanical Engineering Industry Association (Verband Deutscher Maschinen- und Anlagenbau (VDMA)), is intended to overcome this situation. 
+> [!WARNING]
+> This is an early version of the libVDA5050++ supporting VDA5050 2.1.0.
+> The map server interface is currently supported, however the user is responsible for implementing
+> the download.
+
+libVDA5050++ is a complete and open source implementation of the standard VDA5050 version 2.1.0 ([VDA5050 Github Repo](https://github.com/VDA5050/VDA5050) / [VDA5050 standard v2.1.0](https://github.com/VDA5050/VDA5050/tree/2.1.0)). The aim of the VDA5050 standard is to standardize the interface for communication of automated guided vehicles (AGVs) between the control system and the AGVs. Today's systems are mainly isolated solutions, which means that the control of AGVs is proprietary and therefore manufacturer-specific. This means that AGVs from different manufacturers cannot be controlled by a control system of a specific manufacturer. The VDA5050 standard, which was developed by the German Association of the Automotive Industry (Verband der Automobilindustrie e. V. (VDA)) VDA and Mechanical Engineering Industry Association (Verband Deutscher Maschinen- und Anlagenbau (VDMA)), is intended to overcome this situation. 
 
 ![Structure of the libVDA5050++ implementation](docs/resources/libVDA5050++_solution.drawio.svg)
 
diff --git a/cmake/ensure-deps.cmake b/cmake/ensure-deps.cmake
index 3990eb7..3a7c85e 100644
--- a/cmake/ensure-deps.cmake
+++ b/cmake/ensure-deps.cmake
@@ -8,7 +8,7 @@
 find_package(Threads REQUIRED)
 
 # include vda5050_message_structs ##################################################################
-set(LIBVDA5050PP_VDA5050_MESSAGE_STRUCTS_VERSION "2.0.0.9" CACHE STRING "Overwrite vda5050_message_structs version")
+set(LIBVDA5050PP_VDA5050_MESSAGE_STRUCTS_VERSION "2.1.0.1" CACHE STRING "Overwrite vda5050_message_structs version")
 
 if(NOT LIBVDA5050PP_VDA5050_MESSAGE_STRUCTS_DEP_LOCAL)
   find_package(vda5050_message_structs ${LIBVDA5050PP_VDA5050_MESSAGE_STRUCTS_VERSION} QUIET)
diff --git a/docs/api.md b/docs/api.md
index 61549cd..b49bf3f 100644
--- a/docs/api.md
+++ b/docs/api.md
@@ -2,7 +2,7 @@
 
 The [`vda5050pp::agv_description` namespace](doxygen/html/namespacevda5050pp_1_1agv__description.html)
 contains data structures to describe the AGV. The main purpose is to provide information
-for the [Factsheet](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#-616-topic-factsheet) generation and [Topic](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#-63-mqtt-topic-levels)
+for the [Factsheet](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#615-topic-factsheet) generation and [Topic](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#63-mqtt-topic-levels)
 selection. Information in the factsheet will be partially filled by
 the library, the remaining information must be provided by the user (with the AGV description).
 You can set the AGV description in the [`vda5050pp::Config`](doxygen/html/classvda5050pp_1_1Config.html)
@@ -351,6 +351,60 @@ public:
 };
 ```
 
+## MapActionHandler
+
+Then [`vda5050pp::handler::MapActionHandler`](doxygen/html/classvda5050pp_1_1handler_1_1MapActionHandler.html) is a pre-defined handler to cover all map ([VDA5050 6.7.1](https://github.com/VDA5050/VDA5050/blob/main/VDA5050_EN.md#671-map-distribution)) related actions, i.e. `enableMap`,
+`deleteMap` and `downloadMap` (see [VDA5050 6.8.1](https://github.com/VDA5050/VDA5050/blob/main/VDA5050_EN.md#681-definition-parameters-effects-and-scope-of-predefined-actions)).
+
+This handler is meant to be a thin wrapper around those actions. Incoming actions are automatically validated and
+parameters are parsed/forwarded to the pure virtual functions `enableMap`, `deleteMap` and `downloadMap`.
+The user has to enable, delete and download the maps according to their implementation environment.
+Any changes to the maps managed by the user shall be reflected by calls to `stateEnableMap`, `stateDeleteMap` and `stateAddMap`
+respectively. _(This can be done anytime without the MC requesting this)_
+
+Example implementation:
+
+```c++
+class MapHandler : public vda5050pp::handler::MapActionHandler {
+public:
+  std::list<vda5050::Error> enableMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    // Enable the map in the user-code. This means, that any NodePosition containing this map_id
+    // can be understood by the AGV.
+
+    // Also enable the map in the internal state if no error occurred
+    this->stateEnableMap(map_id, map_version);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+
+  std::list<vda5050::Error> deleteMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    // Delete the map in the user-code
+
+    // Also delete the map in the internal state if no error occurred
+    this->stateDeleteMap(map_id, map_version);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+
+  std::list<vda5050::Error> downloadMap(std::string_view map_id, std::string_view map_version,
+                                        std::string_view map_download_link,
+                                        std::optional<std::string_view> map_hash) override {
+    // Download the map in the user-code
+    vda5050::Map info_of_downloaded_map;
+
+    // Add the downloaded map info to the internal state if no error occurred
+    this->stateAddMap(info_of_downloaded_map);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+};
+```
+
 ## SimpleActionHandler
 
 The [`vda5050pp::handler::SimpleActionHandler`](doxygen/html/classvda5050pp_1_1handler_1_1SimpleActionHandler.html)
diff --git a/docs/configuration.md b/docs/configuration.md
index 54bb466..9fde95e 100644
--- a/docs/configuration.md
+++ b/docs/configuration.md
@@ -71,7 +71,7 @@ will be serialized in the `[agv_description]` table.
 
 ### `[agv_description.type_specification]` subtable
 
-Contains JSON serialized [`factsheet.typeSpecification`](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#typespecification).
+Contains JSON serialized [`factsheet.typeSpecification`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#typespecification).
 
 | key                 | description                                                                                 |
 | ------------------- | ------------------------------------------------------------------------------------------- |
@@ -81,7 +81,7 @@ Contains JSON serialized [`factsheet.typeSpecification`](https://github.com/VDA5
 
 ### `[agv_description.physical_parameters]` subtable
 
-Contains JSON serialized [`factsheet.physicalParameters`](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#physicalparameters).
+Contains JSON serialized [`factsheet.physicalParameters`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#physicalparameters).
 
 | key                 | description                                                                                  |
 | ------------------- | -------------------------------------------------------------------------------------------- |
@@ -91,7 +91,7 @@ Contains JSON serialized [`factsheet.physicalParameters`](https://github.com/VDA
 
 ### `[agv_description.agv_geometry]` subtable
 
-Contains JSON serialized [`factsheet.agvGeometry`](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#agvgeometry).
+Contains JSON serialized [`factsheet.agvGeometry`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#agvgeometry).
 
 | key                 | description                                                                           |
 | ------------------- | ------------------------------------------------------------------------------------- |
@@ -101,7 +101,7 @@ Contains JSON serialized [`factsheet.agvGeometry`](https://github.com/VDA5050/VD
 
 ### `[agv_description.load_specification]` subtable
 
-Contains JSON serialized [`factsheet.loadSpecification`](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#loadspecification).
+Contains JSON serialized [`factsheet.loadSpecification`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#loadspecification).
 
 | key                 | description                                                                                 |
 | ------------------- | ------------------------------------------------------------------------------------------- |
@@ -109,21 +109,20 @@ Contains JSON serialized [`factsheet.loadSpecification`](https://github.com/VDA5
 | json_file           | The path of a file containing the JSON serialized load specification. Alternative of `json` |
 | json_file_overwrite | Allow the `vda5050pp::Config::save` to overwrite the file.                                  |
 
-### `[agv_description.localization_parameters]` subtable
+### `[agv_description.network]` subtable
 
-Contains JSON serialized `factsheet.localizationParameters`, since it was not defined in the original document,
-we expect a `{ "type": "", "description": "" }` like object.
+Contains JSON serialized [`factsheet.vehicleConfig.network`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#vehicleconfig).
 
-| key                 | description                                                                                      |
-| ------------------- | ------------------------------------------------------------------------------------------------ |
-| json                | A JSON serialized string of the localization parameters. Alternative of `json_file`              |
-| json_file           | The path of a file containing the JSON serialized localization parameters. Alternative of `json` |
-| json_file_overwrite | Allow the `vda5050pp::Config::save` to overwrite the file.                                       |
 
+| key                 | description                                                                             |
+| ------------------- | --------------------------------------------------------------------------------------- |
+| json                | A JSON serialized string of the network config. Alternative of `json_file`              |
+| json_file           | The path of a file containing the JSON serialized network config. Alternative of `json` |
+| json_file_overwrite | Allow the `vda5050pp::Config::save` to overwrite the file.                              |
 
 ### `[agv_description.simple_protocol_limits]` subtable
 
-It contains a simple form of the [factsheet.protocolLimits](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#protocollimits)
+It contains a simple form of the [factsheet.protocolLimits](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#protocollimits)
 defined in the VDA5050, that is only the parameters, which won't be set by the library itself.
 
 
@@ -134,6 +133,17 @@ defined in the VDA5050, that is only the parameters, which won't be set by the l
 | max_load_id_len   | Maximum length of load IDs                 | yes      |
 | max_loads         | Maximum number of loads in the array       | yes      |
 
+### `[agv_description.user_versions]` subtable
+
+Contains key value pairs, which will end up in [`factsheet.vehicleConfig.versions`](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#vehicleconfig). Static version numbers can be defined here. If your application has runtime information
+on versions, consider specifying them programmatically.
+
+| key              | value              |
+| ---------------- | ------------------ |
+| `<version_key1>` | `<version_value1>` |
+| `<version_key2>` | `<version_value2>` |
+| `...`            | `...`              |
+
 # Module Configuration
 
 Several of the libVDA5050++'s internal modules can be configured.
diff --git a/docs/index.md b/docs/index.md
index a0f0ebb..173b58a 100644
--- a/docs/index.md
+++ b/docs/index.md
@@ -2,7 +2,12 @@
 
 _The current documentation can be viewed [online](http://silicon-economy.pages.fraunhofer.de/services/odyn/vda5050/libvda5050pp)._
 
-libVDA5050++ is a complete and open source implementation of the standard VDA5050 version 2.0.0 ([VDA5050 Github Repo](https://github.com/VDA5050/VDA5050) / [VDA5050 standard v2.0.0](https://github.com/VDA5050/VDA5050/tree/2.0.0)). The aim of the VDA5050 standard is to standardize the interface for communication of automated guided vehicles (AGVs) between the control system and the AGVs. Today's systems are mainly isolated solutions, which means that the control of AGVs is proprietary and therefore manufacturer-specific. This means that AGVs from different manufacturers cannot be controlled by a control system of a specific manufacturer. The VDA5050 standard, which was developed by the German Association of the Automotive Industry (Verband der Automobilindustrie e. V. (VDA)) VDA and Mechanical Engineering Industry Association (Verband Deutscher Maschinen- und Anlagenbau (VDMA)), is intended to overcome this situation. 
+> [!WARNING]
+> This is an early version of the libVDA5050++ supporting VDA5050 2.1.0.
+> The map server interface is currently supported, however the user is responsible for implementing
+> the download.
+
+libVDA5050++ is a complete and open source implementation of the standard VDA5050 version 2.1.0 ([VDA5050 Github Repo](https://github.com/VDA5050/VDA5050) / [VDA5050 standard v2.1.0](https://github.com/VDA5050/VDA5050/tree/2.1.0)). The aim of the VDA5050 standard is to standardize the interface for communication of automated guided vehicles (AGVs) between the control system and the AGVs. Today's systems are mainly isolated solutions, which means that the control of AGVs is proprietary and therefore manufacturer-specific. This means that AGVs from different manufacturers cannot be controlled by a control system of a specific manufacturer. The VDA5050 standard, which was developed by the German Association of the Automotive Industry (Verband der Automobilindustrie e. V. (VDA)) VDA and Mechanical Engineering Industry Association (Verband Deutscher Maschinen- und Anlagenbau (VDMA)), is intended to overcome this situation. 
 
 ![Structure of the libVDA5050++ implementation](resources/libVDA5050++_solution.drawio.svg)
 
@@ -17,8 +22,8 @@ List of the most important functionalities of the libVDA5050++:
 - Supervise AGV navigation (goals, pausing, resuming, stopping)
 - Notify AGV about pending actions of the order based on it's position
 - Implements a Scheduler for VDA5050 compliant execution of
-  actions and navigation goals ([6.2.10](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#-6102-traversal-of-nodes-and-enteringleaving-edges-triggering-of-actions),
-  [6.11](https://github.com/VDA5050/VDA5050/blob/2.0.0/VDA5050_EN_V1.md#-611-actionstates))
+  actions and navigation goals ([6.10.2](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#6102-traversal-of-nodes-and-enteringleaving-edges-triggering-of-actions),
+  [6.11](https://github.com/VDA5050/VDA5050/blob/release/2.1.0/VDA5050_EN.md#611-action-states))
 - Notify AGV / Master Control about certain state changes
 - Provide an easy access to the current state
 - Process the AGV's position and state
diff --git a/examples/example_config.toml b/examples/example_config.toml
index 36e14fd..dcb98b5 100644
--- a/examples/example_config.toml
+++ b/examples/example_config.toml
@@ -18,7 +18,7 @@ serial_number = 'my_serial_number' # The serial number of the AGV, used in the M
 
 [agv_description.agv_geometry]
 # The AGV's geometry, used in the factsheet. (Format as in VDA5050)
-# alternatlively json_file with a path to the json file can be set.
+# alternatively json_file with a path to the json file can be set.
 json = '''{
   "envelopes2d": [
     {
@@ -96,7 +96,7 @@ max_voltage = 24.0 # Maximum Voltage [V]
 
 [agv_description.load_specification]
 # The AGV's load specification, used in the factsheet. (Format as in VDA5050)
-# alternatlively json_file with a path to the json file can be set.
+# alternatively json_file with a path to the json file can be set.
 json = '''{
   "loadPositions": [
     "LEFT",
@@ -120,17 +120,25 @@ json = '''{
   ]
 }'''
 
-[agv_description.localization_parameters]
-# The AGV's localizaion parameters, used in the factsheet. (Format as in VDA5050)
-# alternatlively json_file with a path to the json file can be set.
+[agv_description.network]
+# The AGV's network config, used in the factsheet. (Format as in VDA5050)
+# alternatively json_file with a path to the json file can be set.
 json = '''{
-  "description": "These are my localization parameters",
-  "type": "The type of my localization parameters"
+  "defaultGateway": "192.168.0.1",
+  "dnsServers": [
+    "dns1",
+    "dns2"
+  ],
+  "localIpAddress": "192.168.0.10",
+  "netmask": "255.255.0.0",
+  "ntpServers": [
+    "ntp1"
+  ]
 }'''
 
 [agv_description.physical_parameters]
-# The AGV's physica parameters, used in the factsheet. (Format as in VDA5050)
-# alternatlively json_file with a path to the json file can be set.
+# The AGV's physical parameters, used in the factsheet. (Format as in VDA5050)
+# alternatively json_file with a path to the json file can be set.
 json = '''{
   "accelerationMax": 1.0,
   "decelerationMax": 2.5,
@@ -149,7 +157,7 @@ max_load_id_len = 12 # Maximum length of load ids
 
 [agv_description.type_specification]
 # The AGV's type specification, used in the factsheet. (Format as in VDA5050)
-# alternatlively json_file with a path to the json file can be set.
+# alternatively json_file with a path to the json file can be set.
 json = '''{
   "agvClass": "CARRIER",
   "agvKinematic": "OMNI",
@@ -166,6 +174,12 @@ json = '''{
   "seriesName": "TEST_SERIES_1"
 }'''
 
+# You can put custom version information for the factsheet in here.
+# However it is probably better to set this programmatically, with runtime version info.
+[agv_description.user_versions]
+Ubuntu = '22.04'
+my_library = 'v1.0'
+
 [global]
 log_level = 'debug' # The global log-level used as a fallback by each module
 log_file_name = 'vda5050.log' # The name of the log file (modules will inherit this file)
diff --git a/examples/src/full_config.cpp b/examples/src/full_config.cpp
index 1960d7f..7d0b14d 100644
--- a/examples/src/full_config.cpp
+++ b/examples/src/full_config.cpp
@@ -41,7 +41,7 @@ int main() {
   cfg.refAgvDescription().type_specification.seriesDescription = "My AGV series description";
   cfg.refAgvDescription().type_specification.seriesName = "TEST_SERIES_1";
 
-  cfg.refAgvDescription().localization_parameters = {{"param1", "value1"}, {"param2", "value2"}};
+  cfg.refAgvDescription().user_versions = {{"my_library", "v1.0"}, {"Ubuntu", "22.04"}};
 
   cfg.refAgvDescription().load_specification.loadPositions = {"LEFT", "RIGHT"};
   cfg.refAgvDescription().load_specification.loadSets = {
@@ -90,6 +90,12 @@ int main() {
                                                             std::nullopt,
                                                             std::nullopt}};
 
+  cfg.refAgvDescription().network.dnsServers = {{"dns1", "dns2"}};
+  cfg.refAgvDescription().network.ntpServers = {{"ntp1"}};
+  cfg.refAgvDescription().network.localIpAddress = "192.168.0.10";
+  cfg.refAgvDescription().network.netmask = "255.255.0.0";
+  cfg.refAgvDescription().network.defaultGateway = "192.168.0.1";
+
   cfg.refGlobalConfig().setLogLevel(vda5050pp::config::LogLevel::k_debug);
   cfg.refGlobalConfig().useBlackList();
   cfg.refGlobalConfig().bwListModule("NodeReachedHandler");
diff --git a/examples/src/handler_demo.cpp b/examples/src/handler_demo.cpp
index c2fa3c7..6b838e3 100644
--- a/examples/src/handler_demo.cpp
+++ b/examples/src/handler_demo.cpp
@@ -8,6 +8,7 @@
 #include <vda5050++/handle.h>
 #include <vda5050++/handler/base_navigation_handler.h>
 #include <vda5050++/handler/base_query_handler.h>
+#include <vda5050++/handler/map_action_handler.h>
 #include <vda5050++/handler/simple_multi_action_handler.h>
 #include <vda5050++/misc/action_declarations.h>
 
@@ -128,6 +129,45 @@ public:
   }
 };
 
+class MapHandler : public vda5050pp::handler::MapActionHandler {
+public:
+  std::list<vda5050::Error> enableMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    // Enable the map in the user-code. This means, that any NodePosition containing this map_id
+    // can be understood by the AGV.
+
+    // Also enable the map in the internal state if no error occurred
+    this->stateEnableMap(map_id, map_version);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+
+  std::list<vda5050::Error> deleteMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    // Delete the map in the user-code
+
+    // Also delete the map in the internal state if no error occurred
+    this->stateDeleteMap(map_id, map_version);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+
+  std::list<vda5050::Error> downloadMap(std::string_view map_id, std::string_view map_version,
+                                        std::string_view map_download_link,
+                                        std::optional<std::string_view> map_hash) override {
+    // Download the map in the user-code
+    vda5050::Map info_of_downloaded_map;
+
+    // Add the downloaded map info to the internal state if no error occurred
+    this->stateAddMap(info_of_downloaded_map);  // This can be called anytime for other maps, too
+
+    // Return errors (empty iff successful)
+    return {};
+  }
+};
+
 class NavigationHandler : public vda5050pp::handler::BaseNavigationHandler {
 public:
   void horizonUpdated(
diff --git a/include/private/vda5050++/core/factsheet/gather.h b/include/private/vda5050++/core/factsheet/gather.h
index fbdb928..8b07018 100644
--- a/include/private/vda5050++/core/factsheet/gather.h
+++ b/include/private/vda5050++/core/factsheet/gather.h
@@ -29,13 +29,6 @@ vda5050::AgvGeometry gatherGeometry();
 ///
 vda5050::LoadSpecification gatherLoadSpecification();
 
-///
-///\brief Gather localization parameters from the AGVDescription
-///
-///\return vda5050::json the localization parameters
-///
-vda5050::json gatherLocalizationParameters();
-
 ///
 ///\brief Gather physical parameters from the AGVDescription
 ///
@@ -71,6 +64,13 @@ vda5050::ProtocolLimits gatherProtocolLimits();
 ///
 vda5050::TypeSpecification gatherTypeSpecification();
 
+///
+///\brief Gather the vehicle configuration of the AGV
+///
+///\return vda5050::VehicleConfig the vehicle config
+///
+vda5050::VehicleConfig gatherVehicleConfig();
+
 }  // namespace vda5050pp::core::factsheet
 
 #endif  // VDA5050_2B_2B_CORE_FACTSHEET_GATHER_H_
diff --git a/include/private/vda5050++/core/instance.h b/include/private/vda5050++/core/instance.h
index f392cbc..2c14c30 100644
--- a/include/private/vda5050++/core/instance.h
+++ b/include/private/vda5050++/core/instance.h
@@ -30,6 +30,7 @@
 #include "vda5050++/core/navigation_status_manager.h"
 #include "vda5050++/core/order_event_manager.h"
 #include "vda5050++/core/query_event_manager.h"
+#include "vda5050++/core/state/map_manager.h"
 #include "vda5050++/core/state/order_manager.h"
 #include "vda5050++/core/state/status_manager.h"
 #include "vda5050++/core/status_event_manager.h"
@@ -121,6 +122,8 @@ private:
   vda5050pp::core::state::OrderManager order_manager_;
   ///\brief the status manager, holding status data of the vda5050::State
   vda5050pp::core::state::StatusManager status_manager_;
+  ///\brief the map manager, holding map data of the vda5050::State
+  vda5050pp::core::state::MapManager map_manager_;
 
 protected:
   ///
@@ -403,6 +406,13 @@ public:
   ///\return vda5050pp::core::state::StatusManager&
   ///
   vda5050pp::core::state::StatusManager &getStatusManager();
+
+  ///
+  ///\brief Get a rw reference to the map manager
+  ///
+  ///\return vda5050pp::core::state::MapManager&
+  ///
+  vda5050pp::core::state::MapManager &getMapManager();
 };
 
 }  // namespace vda5050pp::core
diff --git a/include/private/vda5050++/core/messages/mqtt_module.h b/include/private/vda5050++/core/messages/mqtt_module.h
index 3ce7f7d..be18761 100644
--- a/include/private/vda5050++/core/messages/mqtt_module.h
+++ b/include/private/vda5050++/core/messages/mqtt_module.h
@@ -91,9 +91,6 @@ private:
   ///\brief the serial number, used in each header and each topic path
   std::string serial_number_;
 
-  ///\brief the mqtt quality of service level
-  const int k_qos = 0;
-
   ///
   ///\brief Fill in a header with information for the connection topic
   ///
diff --git a/include/private/vda5050++/core/state/map_manager.h b/include/private/vda5050++/core/state/map_manager.h
new file mode 100644
index 0000000..6155b75
--- /dev/null
+++ b/include/private/vda5050++/core/state/map_manager.h
@@ -0,0 +1,90 @@
+// Copyright Open Logistics Foundation
+//
+// Licensed under the Open Logistics Foundation License 1.3.
+// For details on the licensing terms, see the LICENSE file.
+// SPDX-License-Identifier: OLFL-1.3
+//
+
+#ifndef VDA5050_2B_2B_CORE_STATE_MAP_MANAGER_H_
+#define VDA5050_2B_2B_CORE_STATE_MAP_MANAGER_H_
+
+#include <optional>
+#include <string>
+#include <vector>
+
+#include "vda5050/Map.h"
+#include "vda5050/MapStatus.h"
+#include "vda5050/State.h"
+
+namespace vda5050pp::core::state {
+
+///
+///\brief A manager for all maps.
+///
+/// This currently keeps track of all map objects for the vda5050 state.
+/// It makes sure, that only one map per id is enabled at a time.
+///
+class MapManager {
+private:
+  std::vector<vda5050::Map> maps_;
+
+public:
+  ///
+  ///\brief Enable a map. (Disable all other maps with the same id)
+  ///
+  ///\param map_id the map id
+  ///\param map_version the map version
+  ///
+  void enableMap(std::string_view map_id, std::string_view map_version);
+
+  ///
+  ///\brief Delete a map.
+  ///
+  ///\param map_id the map id
+  ///\param map_version the map version
+  ///
+  void deleteMap(std::string_view map_id, std::string_view map_version);
+
+  ///
+  ///\brief Add a map.
+  ///
+  ///\param map The map to add. It should be disabled, otherwise there may be two enabled maps.
+  ///
+  void addMap(const vda5050::Map &map);
+
+  ///
+  ///\brief Check if a map is available.
+  ///
+  ///\param map_id the map id to check
+  ///\return is this map available?
+  ///
+  bool hasMap(std::string_view map_id) const;
+
+  ///
+  ///\brief Check if a map is available.
+  ///
+  ///\param map_id the map id to check
+  ///\param map_version the map version
+  ///\return is this map available?
+  ///
+  bool hasMap(std::string_view map_id, std::string_view map_version) const;
+
+  ///
+  ///\brief Get an enabled map by it's id.
+  ///
+  ///\param map_id The id of the map to get.
+  ///\return std::optional<vda5050::Map> The map if it is enabled, otherwise std::nullopt.
+  ///
+  std::optional<vda5050::Map> getMap(std::string_view map_id) const;
+
+  ///
+  ///\brief Write all maps to the state.
+  ///
+  ///\param state the state to write to
+  ///
+  void dumpTo(vda5050::State &state) const;
+};
+
+}  // namespace vda5050pp::core::state
+
+#endif  // VDA5050_2B_2B_CORE_STATE_MAP_MANAGER_H_
diff --git a/include/private/vda5050++/core/state/state_event_handler.h b/include/private/vda5050++/core/state/state_event_handler.h
index d3f7e54..ac122ba 100644
--- a/include/private/vda5050++/core/state/state_event_handler.h
+++ b/include/private/vda5050++/core/state/state_event_handler.h
@@ -350,6 +350,33 @@ private:
   ///
   void handleInfosAlter(std::shared_ptr<vda5050pp::events::InfosAlter> data) const noexcept(false);
 
+  ///
+  ///\brief Handle an AddMap event
+  ///
+  ///\param data the event data
+  ///
+  ///\throws VDA5050PPNullPointer if data is nullptr
+  ///
+  void handleAddMap(std::shared_ptr<vda5050pp::events::AddMap> data) const noexcept(false);
+
+  ///
+  ///\brief Handle an EnableMap event
+  ///
+  ///\param data the event data
+  ///
+  ///\throws VDA5050PPNullPointer if data is nullptr
+  ///
+  void handleEnableMap(std::shared_ptr<vda5050pp::events::EnableMap> data) const noexcept(false);
+
+  ///
+  ///\brief Handle an DeleteMap event
+  ///
+  ///\param data the event data
+  ///
+  ///\throws VDA5050PPNullPointer if data is nullptr
+  ///
+  void handleDeleteMap(std::shared_ptr<vda5050pp::events::DeleteMap> data) const noexcept(false);
+
 public:
   ///
   ///\brief Setup all subscribers.
diff --git a/include/private/vda5050++/core/status_event_manager.h b/include/private/vda5050++/core/status_event_manager.h
index 9564a03..0b4cc6e 100644
--- a/include/private/vda5050++/core/status_event_manager.h
+++ b/include/private/vda5050++/core/status_event_manager.h
@@ -180,6 +180,30 @@ public:
   ///
   void subscribe(std::function<void(std::shared_ptr<vda5050pp::events::InfosAlter>)>
                      &&callback) noexcept(true);
+
+  ///
+  ///\brief Subscribe to AddMap events.
+  ///
+  ///\param callback the callback to call
+  ///
+  void subscribe(
+      std::function<void(std::shared_ptr<vda5050pp::events::AddMap>)> &&callback) noexcept(true);
+
+  ///
+  ///\brief Subscribe to DeleteMap events.
+  ///
+  ///\param callback the callback to call
+  ///
+  void subscribe(
+      std::function<void(std::shared_ptr<vda5050pp::events::DeleteMap>)> &&callback) noexcept(true);
+
+  ///
+  ///\brief Subscribe to EnableMap events.
+  ///
+  ///\param callback the callback to call
+  ///
+  void subscribe(
+      std::function<void(std::shared_ptr<vda5050pp::events::EnableMap>)> &&callback) noexcept(true);
 };
 
 ///
diff --git a/include/public/vda5050++/agv_description/agv_description.h b/include/public/vda5050++/agv_description/agv_description.h
index 1176851..55183ee 100644
--- a/include/public/vda5050++/agv_description/agv_description.h
+++ b/include/public/vda5050++/agv_description/agv_description.h
@@ -10,13 +10,16 @@
 
 #include <vda5050/AgvGeometry.h>
 #include <vda5050/LoadSpecification.h>
+#include <vda5050/Network.h>
 #include <vda5050/PhysicalParameters.h>
 #include <vda5050/TypeSpecification.h>
+#include <vda5050/VersionInfo.h>
 
 #include <cstdint>
 #include <optional>
 #include <set>
 #include <string>
+#include <vector>
 
 #include "vda5050++/agv_description/action_declaration.h"
 #include "vda5050++/agv_description/battery.h"
@@ -49,9 +52,11 @@ struct AGVDescription {
 
   vda5050::LoadSpecification load_specification;
 
-  vda5050::json localization_parameters;
+  vda5050::Network network;
 
   SimpleProtocolLimits simple_protocol_limits;
+
+  std::vector<vda5050::VersionInfo> user_versions;
 };
 
 }  // namespace vda5050pp::agv_description
diff --git a/include/public/vda5050++/config/agv_description_subconfig.h b/include/public/vda5050++/config/agv_description_subconfig.h
index 3096ee6..f5253db 100644
--- a/include/public/vda5050++/config/agv_description_subconfig.h
+++ b/include/public/vda5050++/config/agv_description_subconfig.h
@@ -31,7 +31,7 @@ private:
   std::optional<JSONFile> physical_parameters_mode_;
   std::optional<JSONFile> agv_geometry_mode_;
   std::optional<JSONFile> load_specifications_mode_;
-  std::optional<JSONFile> localization_parameters_mode_;
+  std::optional<JSONFile> network_mode_;
 
 protected:
   ///\brief Restore this object from a ConstConfigNode
@@ -91,14 +91,14 @@ public:
   void setLoadSpecificationsJSONMode(const std::optional<JSONFile> &mode);
 
   ///
-  ///\brief Set the LocalizationParameters JSON Serialization mode
+  ///\brief Set the Network JSON Serialization mode
   ///
   /// std::nullopt means serialize to string
   /// JSONFile means serialize to file and store filename
   ///
   ///\param mode the serialization mode
   ///
-  void setLocalizationParametersJSONMode(const std::optional<JSONFile> &mode);
+  void setNetworkJSONMode(const std::optional<JSONFile> &mode);
 
   ///
   ///\brief Get the current AGVDescription.
diff --git a/include/public/vda5050++/events/status_event.h b/include/public/vda5050++/events/status_event.h
index e80998a..798d84a 100644
--- a/include/public/vda5050++/events/status_event.h
+++ b/include/public/vda5050++/events/status_event.h
@@ -16,6 +16,7 @@
 #include "vda5050/Error.h"
 #include "vda5050/Info.h"
 #include "vda5050/Load.h"
+#include "vda5050/Map.h"
 #include "vda5050/OperatingMode.h"
 #include "vda5050/SafetyState.h"
 
@@ -44,6 +45,9 @@ enum class StatusEventType {
   k_errors_alter,
   k_info_add,
   k_infos_alter,
+  k_add_map,
+  k_enable_map,
+  k_delete_map,
 };
 
 ///
@@ -199,6 +203,30 @@ struct InfosAlter : public StatusEventId<StatusEventType::k_infos_alter> {
   std::function<void(std::vector<vda5050::Info> &)> alter_function;
 };
 
+///
+///\brief This event can be dispatched by the user to add a map to the state.
+///
+struct AddMap : public StatusEventId<StatusEventType::k_add_map> {
+  vda5050::Map map;
+};
+
+///
+///\brief This event can be dispatched by the user to enable a map in the state.
+/// Other maps with the same map_id will be disabled
+///
+struct EnableMap : public StatusEventId<StatusEventType::k_enable_map> {
+  std::string map_id;
+  std::string map_version;
+};
+
+///
+///\brief This event can be dispatched by the user to delete a map from the state.
+///
+struct DeleteMap : public StatusEventId<StatusEventType::k_delete_map> {
+  std::string map_id;
+  std::string map_version;
+};
+
 }  // namespace vda5050pp::events
 
 #endif  // PUBLIC_VDA5050_2B_2B_EVENTS_STATUS_EVENT_H_
diff --git a/include/public/vda5050++/handler/map_action_handler.h b/include/public/vda5050++/handler/map_action_handler.h
new file mode 100644
index 0000000..37fe69b
--- /dev/null
+++ b/include/public/vda5050++/handler/map_action_handler.h
@@ -0,0 +1,120 @@
+//  Copyright Open Logistics Foundation
+//
+//  Licensed under the Open Logistics Foundation License 1.3.
+//  For details on the licensing terms, see the LICENSE file.
+//  SPDX-License-Identifier: OLFL-1.3
+//
+
+#ifndef PUBLIC_VDA5050_2B_2B_HANDLER_MAP_ACTION_HANDLER_H_
+#define PUBLIC_VDA5050_2B_2B_HANDLER_MAP_ACTION_HANDLER_H_
+
+#include <vda5050/Map.h>
+
+#include <future>
+
+#include "vda5050++/handler/simple_multi_action_handler.h"
+
+namespace vda5050pp::handler {
+
+///
+///\brief A pre implemented BaseActionHandler for map related actions.
+///
+/// Covers:
+/// - enableMap
+/// - downloadMap
+/// - deleteMap
+///
+/// NOTE: The library will call the member functions of this class with one dedicated thread.
+/// The user has to make sure to return from the functions in order to receive the next function
+/// call.
+///
+class MapActionHandler : public vda5050pp::handler::SimpleMultiActionHandler {
+private:
+  ///
+  ///\brief This function is called to prepare a valid action.
+  /// This will be mainly used to organize possible things in the user-code and set callbacks
+  /// for the concerning action.
+  ///
+  ///\param action_state the ActionState (may not be used here)
+  ///\param parameters the parsed parameters of the validate() call
+  ///\return ActionCallbacks the callbacks used for the Action associated with action_state.
+  ///
+  vda5050pp::handler::ActionCallbacks prepare(
+      std::shared_ptr<vda5050pp::handler::ActionState> action_state,
+      std::shared_ptr<ParametersMap> parameters) noexcept(false) override;
+
+protected:
+  ///\brief Default reset implementation does nothing here.
+  void reset() override;
+
+public:
+  MapActionHandler();
+  ~MapActionHandler() override = default;
+
+  ///
+  ///\brief Add a map to the internal (VDA5050) state.
+  ///
+  ///\param map The map to add
+  ///
+  void stateAddMap(const vda5050::Map &map) const;
+
+  ///
+  ///\brief Enable a map in the internal (VDA5050) state.
+  ///
+  ///\param map_id the map id of the map to enable
+  ///\param map_version the map version of the map to enable
+  ///
+  void stateEnableMap(std::string_view map_id, std::string_view map_version) const;
+
+  ///
+  ///\brief Delete a map from the internal (VDA5050) state.
+  ///
+  ///\param map_id the map id of the map to delete
+  ///\param map_version the map version of the map to delete
+  ///
+  void stateDeleteMap(std::string_view map_id, std::string_view map_version) const;
+
+  ///
+  ///\brief Enable a map. This function is triggered by the MC via the enableMap action.
+  ///
+  /// The user has to make sure to call stateEnableMap to enable the map in the internal state.
+  ///
+  ///\param map_id the map id of the map to enable.
+  ///\param map_version the map version of the map to enable
+  ///\return std::list<vda5050::Error> a list of error. empty iff. success
+  ///
+  virtual std::list<vda5050::Error> enableMap(std::string_view map_id,
+                                              std::string_view map_version) = 0;
+
+  ///
+  ///\brief Delete a map. This function is triggered by the MC via the deleteMap action.
+  ///
+  /// The user has to make sure to call stateDeleteMap to delete the map in the internal state.
+  ///
+  ///\param map_id the map id of the map to delete.
+  ///\param map_version the map version of the map to delete
+  ///\return std::list<vda5050::Error> a list of error. empty iff. success
+  ///
+  virtual std::list<vda5050::Error> deleteMap(std::string_view map_id,
+                                              std::string_view map_version) = 0;
+
+  ///
+  ///\brief Download a new map. This function is triggered by the MC via the downloadMap action.
+  ///
+  /// The user has to make sure to call stateAddMap to add the map to the internal state.
+  ///
+  ///\param map_id the map id of the map to download.
+  ///\param map_version the map version of the map to download
+  ///\param map_download_link the download link of the map
+  ///\param map_hash the hash of the map (optional)
+  ///\return std::list<vda5050::Error> a list of error. empty iff. success
+  ///
+  virtual std::list<vda5050::Error> downloadMap(std::string_view map_id,
+                                                std::string_view map_version,
+                                                std::string_view map_download_link,
+                                                std::optional<std::string_view> map_hash) = 0;
+};
+
+}  // namespace vda5050pp::handler
+
+#endif  // PUBLIC_VDA5050_2B_2B_HANDLER_MAP_ACTION_HANDLER_H_
diff --git a/include/public/vda5050++/misc/action_declarations.h b/include/public/vda5050++/misc/action_declarations.h
index 4b72141..c83846d 100644
--- a/include/public/vda5050++/misc/action_declarations.h
+++ b/include/public/vda5050++/misc/action_declarations.h
@@ -150,6 +150,33 @@ const vda5050pp::agv_description::ParameterRange k_map_id{
     std::nullopt,                                              // Allowed Value Set
 };
 
+const vda5050pp::agv_description::ParameterRange k_map_version{
+    "mapVersion",                                              // key
+    vda5050pp::agv_description::ParameterValueType::k_string,  // type
+    "The version of the map",                                  // Description
+    std::nullopt,                                              // Ordinal Min
+    std::nullopt,                                              // Ordinal Max
+    std::nullopt,                                              // Allowed Value Set
+};
+
+const vda5050pp::agv_description::ParameterRange k_map_download_link{
+    "mapDownloadLink",                                         // key
+    vda5050pp::agv_description::ParameterValueType::k_string,  // type
+    "The URL, from which the AGV can download the map",        // Description
+    std::nullopt,                                              // Ordinal Min
+    std::nullopt,                                              // Ordinal Max
+    std::nullopt,                                              // Allowed Value Set
+};
+
+const vda5050pp::agv_description::ParameterRange k_map_hash{
+    "mapHash",                                                                // key
+    vda5050pp::agv_description::ParameterValueType::k_string,                 // type
+    "The hash value of the downloaded map (application specific algorithm)",  // Description
+    std::nullopt,                                                             // Ordinal Min
+    std::nullopt,                                                             // Ordinal Max
+    std::nullopt,                                                             // Allowed Value Set
+};
+
 const vda5050pp::agv_description::ParameterRange k_last_node_id{
     "lastNodeId",                                              // key
     vda5050pp::agv_description::ParameterValueType::k_string,  // type
@@ -303,6 +330,67 @@ const vda5050pp::agv_description::ActionDeclaration k_init_position{
     false,                          // Can be on Edge
 };
 
+const vda5050pp::agv_description::ActionDeclaration k_enable_map{
+    "enableMap",  // Type
+    "Enable a previously downloaded map explicitly to be used in orders without initializing a new "
+    "position.",   // Description
+    std::nullopt,  // Result Description
+    {
+        action_parameter::k_map_id,
+        action_parameter::k_map_version,
+    },   // Parameter
+    {},  // Optional Parameter
+    {
+        vda5050::BlockingType::HARD,
+        vda5050::BlockingType::SOFT,
+        vda5050::BlockingType::NONE,
+    },      // Allowed BlockingTypes
+    true,   // Can be instant
+    true,   // Can be on Node
+    false,  // Can be on Edge
+};
+
+const vda5050pp::agv_description::ActionDeclaration k_download_map{
+    "downloadMap",  // Type
+    "Trigger the download of a new map. Active during the download. Errors reported in vehicle "
+    "state. Finished after verifying the successful download, preparing the map for use and "
+    "setting the map in the state.",  // Description
+    std::nullopt,                     // Result Description
+    {
+        action_parameter::k_map_id,
+        action_parameter::k_map_version,
+        action_parameter::k_map_download_link,
+    },                               // Parameter
+    {action_parameter::k_map_hash},  // Optional Parameter
+    {
+        vda5050::BlockingType::HARD,
+        vda5050::BlockingType::SOFT,
+        vda5050::BlockingType::NONE,
+    },      // Allowed BlockingTypes
+    true,   // Can be instant
+    false,  // Can be on Node
+    false,  // Can be on Edge
+};
+
+const vda5050pp::agv_description::ActionDeclaration k_delete_map{
+    "deleteMap",                                              // Type
+    "Trigger the removal of a map from the vehicle memory.",  // Description
+    std::nullopt,                                             // Result Description
+    {
+        action_parameter::k_map_id,
+        action_parameter::k_map_version,
+    },   // Parameter
+    {},  // Optional Parameter
+    {
+        vda5050::BlockingType::HARD,
+        vda5050::BlockingType::SOFT,
+        vda5050::BlockingType::NONE,
+    },      // Allowed BlockingTypes
+    true,   // Can be instant
+    false,  // Can be on Node
+    false,  // Can be on Edge
+};
+
 }  // namespace vda5050pp::misc::action_declarations
 
 #endif  // PUBLIC_VDA5050_2B_2B_MISC_ACTION_DECLARATIONS_H_
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 18c90c8..1623f20 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -57,6 +57,7 @@ set(LIBVDA5050PP_SOURCES
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/order_event_manager.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/query_event_manager.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/state/graph.cpp
+  ${PROJECT_SOURCE_DIR}/src/vda5050++/core/state/map_manager.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/state/order_manager.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/state/state_event_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/core/state/state_update_timer.cpp
@@ -73,6 +74,7 @@ set(LIBVDA5050PP_SOURCES
   ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/base_navigation_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/base_query_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/init_position_handler.cpp
+  ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/map_action_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/simple_action_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/handler/simple_multi_action_handler.cpp
   ${PROJECT_SOURCE_DIR}/src/vda5050++/misc/action_parameter_view.cpp
diff --git a/src/vda5050++/config/agv_description_subconfig.cpp b/src/vda5050++/config/agv_description_subconfig.cpp
index 0f41f19..e7c5a89 100644
--- a/src/vda5050++/config/agv_description_subconfig.cpp
+++ b/src/vda5050++/config/agv_description_subconfig.cpp
@@ -161,15 +161,14 @@ static toml::table toLoadSpecificationTable(
   return toJSONTable<vda5050::LoadSpecification>(load_spec, file, "LoadSpecification");
 }
 
-static vda5050::json fromLocalizationParametersTable(
-    toml::node_view<const toml::node> node,
-    std::optional<AGVDescriptionSubConfig::JSONFile> &file) {
-  return fromJSONTable<vda5050::json>(node, file, "LocalizationParameters");
+static vda5050::Network fromNetworkTable(toml::node_view<const toml::node> node,
+                                         std::optional<AGVDescriptionSubConfig::JSONFile> &file) {
+  return fromJSONTable<vda5050::Network>(node, file, "Network");
 }
 
-static toml::table toLocalizationParametersTable(
-    const vda5050::json &loc_par, const std::optional<AGVDescriptionSubConfig::JSONFile> &file) {
-  return toJSONTable<vda5050::json>(loc_par, file, "LocalizationParameters");
+static toml::table toNetworkTable(const vda5050::Network &network,
+                                  const std::optional<AGVDescriptionSubConfig::JSONFile> &file) {
+  return toJSONTable<vda5050::Network>(network, file, "Network");
 }
 
 static vda5050pp::agv_description::SimpleProtocolLimits fromSimpleProtocolLimitsTable(
@@ -212,6 +211,30 @@ static toml::table toSimpleProtocolLimitsTable(
   return table;
 }
 
+static std::vector<vda5050::VersionInfo> fromUserVersionsTable(
+    toml::node_view<const toml::node> node) {
+  std::vector<vda5050::VersionInfo> user_versions;
+
+  auto &table = *node.as_table();
+
+  for (const auto &[key, value] : table) {
+    user_versions.push_back(vda5050::VersionInfo{std::string(key.str()),
+                                                 value.value_or<std::string>("<not a string>")});
+  }
+
+  return user_versions;
+}
+
+static toml::table toUserVersionsTable(const std::vector<vda5050::VersionInfo> &user_versions) {
+  toml::table table;
+
+  for (const auto &version : user_versions) {
+    table.insert(version.key, version.value);
+  }
+
+  return table;
+}
+
 void AGVDescriptionSubConfig::getFrom(const ConstConfigNode &node) {
   auto node_view = core::config::ConstConfigNode::upcast(node).get();
 
@@ -239,13 +262,15 @@ void AGVDescriptionSubConfig::getFrom(const ConstConfigNode &node) {
     this->agv_description_.load_specification =
         fromLoadSpecificationTable(ls, this->load_specifications_mode_);
   }
-  if (auto lp = node_view["localization_parameters"]; lp) {
-    this->agv_description_.localization_parameters =
-        fromLocalizationParametersTable(lp, this->localization_parameters_mode_);
-  }
   if (auto sp = node_view["simple_protocol_limits"]; sp) {
     this->agv_description_.simple_protocol_limits = fromSimpleProtocolLimitsTable(sp);
   }
+  if (auto n = node_view["network"]; n) {
+    this->agv_description_.network = fromNetworkTable(n, this->network_mode_);
+  }
+  if (auto uv = node_view["user_versions"]; uv) {
+    this->agv_description_.user_versions = fromUserVersionsTable(uv);
+  }
 }
 
 void AGVDescriptionSubConfig::putTo(ConfigNode &node) const {
@@ -271,11 +296,10 @@ void AGVDescriptionSubConfig::putTo(ConfigNode &node) const {
   table.insert("load_specification",
                toLoadSpecificationTable(this->agv_description_.load_specification,
                                         this->load_specifications_mode_));
-  table.insert("localization_parameters",
-               toLocalizationParametersTable(this->agv_description_.localization_parameters,
-                                             this->localization_parameters_mode_));
   table.insert("simple_protocol_limits",
                toSimpleProtocolLimitsTable(this->agv_description_.simple_protocol_limits));
+  table.insert("network", toNetworkTable(this->agv_description_.network, this->network_mode_));
+  table.insert("user_versions", toUserVersionsTable(this->agv_description_.user_versions));
 }
 
 void AGVDescriptionSubConfig::setTypeSpecificationJSONMode(const std::optional<JSONFile> &mode) {
@@ -294,11 +318,6 @@ void AGVDescriptionSubConfig::setLoadSpecificationsJSONMode(const std::optional<
   this->load_specifications_mode_ = mode;
 }
 
-void AGVDescriptionSubConfig::setLocalizationParametersJSONMode(
-    const std::optional<JSONFile> &mode) {
-  this->localization_parameters_mode_ = mode;
-}
-
 void AGVDescriptionSubConfig::setAGVDescription(
     const vda5050pp::agv_description::AGVDescription &new_description) {
   this->agv_description_ = new_description;
diff --git a/src/vda5050++/core/agv_handler/query_event_handler.cpp b/src/vda5050++/core/agv_handler/query_event_handler.cpp
index 6d04e2a..ef7cd63 100644
--- a/src/vda5050++/core/agv_handler/query_event_handler.cpp
+++ b/src/vda5050++/core/agv_handler/query_event_handler.cpp
@@ -219,6 +219,8 @@ void QueryEventHandler::handleQueryNodeTriviallyReachable(
           fmt::format(
               "Node {} is not the last node of the AGV (accepting nodes by deviation is disabled)",
               data->node->nodeId),
+          fmt::format("Either allow deviation based checks or start the order at node {}",
+                      agv_node),
           vda5050::ErrorLevel::WARNING,
       }};
     } else if (data->node->nodePosition.has_value()) {
@@ -249,6 +251,9 @@ void QueryEventHandler::handleQueryNodeTriviallyReachable(
               {"order.nodes[0].nodeId", data->node->nodeId}}},
             fmt::format("The AGV is not in the deviation radius of node {} (last node: {})",
                         data->node->nodeId, agv_node),
+            fmt::format("Either increase the deviation radius of the temporary node or start the "
+                        "order at node {}",
+                        agv_node),
             vda5050::ErrorLevel::WARNING,
         }};
       }
@@ -260,6 +265,9 @@ void QueryEventHandler::handleQueryNodeTriviallyReachable(
           fmt::format("Node {} is not the last node of the AGV (no position data available for "
                       "deviation check)",
                       data->node->nodeId),
+          fmt::format(
+              "Either attach position information to node {} or let the order start at node {}",
+              data->node->nodeId, agv_node),
           vda5050::ErrorLevel::WARNING,
       }};
     }
diff --git a/src/vda5050++/core/checks/action.cpp b/src/vda5050++/core/checks/action.cpp
index 4c1828b..39d7335 100644
--- a/src/vda5050++/core/checks/action.cpp
+++ b/src/vda5050++/core/checks/action.cpp
@@ -37,6 +37,7 @@ inline std::variant<T, vda5050::Error> ensureParameterConstraints(
     vda5050::Error err;
     err.errorType = k_malformed_error;
     err.errorDescription = e.what();
+    err.errorHint = "Ensure the value is of the correct type";
     err.errorLevel = vda5050::ErrorLevel::WARNING;
     return err;
   }
@@ -50,6 +51,7 @@ inline std::variant<T, vda5050::Error> ensureParameterConstraints(
                                                                            : k_semantic_error;
       err.errorDescription =
           fmt::format("Expected a value not smaller then {}, got {}", min_value, t_value);
+      err.errorHint = fmt::format("Ensure the value is within the allowed range (>={})", min_value);
       err.errorLevel = vda5050::ErrorLevel::WARNING;
       return err;
     }
@@ -65,6 +67,7 @@ inline std::variant<T, vda5050::Error> ensureParameterConstraints(
       err.errorDescription =
           fmt::format("Expected a value not greater then {}, got {}", max_value, t_value);
       err.errorLevel = vda5050::ErrorLevel::WARNING;
+      err.errorHint = fmt::format("Ensure the value is within the allowed range (<={})", max_value);
       return err;
     }
   }
@@ -75,6 +78,7 @@ inline std::variant<T, vda5050::Error> ensureParameterConstraints(
     err.errorType = context == vda5050pp::misc::ActionContext::k_instant ? k_ia_semantic_error
                                                                          : k_semantic_error;
     err.errorDescription = fmt::format("Expected a value of {}, not {}", *p.value_set, t_value);
+    err.errorHint = fmt::format("Ensure the value is within the allowed set {}", *p.value_set);
     err.errorLevel = vda5050::ErrorLevel::WARNING;
     return err;
   }
@@ -94,6 +98,7 @@ inline std::variant<bool, vda5050::Error> ensureParameterConstraints<bool>(
     err.errorType = k_malformed_error;
     err.errorDescription = e.what();
     err.errorLevel = vda5050::ErrorLevel::WARNING;
+    err.errorHint = "Ensure the value is a boolean";
     return err;
   }
 
@@ -103,6 +108,7 @@ inline std::variant<bool, vda5050::Error> ensureParameterConstraints<bool>(
     err.errorType = context == vda5050pp::misc::ActionContext::k_instant ? k_ia_semantic_error
                                                                          : k_semantic_error;
     err.errorDescription = fmt::format("Expected a value of {}, not {}", *p.value_set, t_value);
+    err.errorHint = fmt::format("Ensure the value is within the allowed set {}", *p.value_set);
     err.errorLevel = vda5050::ErrorLevel::WARNING;
     return err;
   }
@@ -175,6 +181,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::contextCheck(
   err.errorReferences->push_back({"action.actionType", action.actionType});
   err.errorReferences->push_back({"action.context", where});
   err.errorReferences->push_back({"action.allowedContext", fmt::format("{}", allowed)});
+  err.errorHint =
+      fmt::format("Make sure to use this action in the following contexts: {}", allowed);
 
   return {err};
 }
@@ -197,6 +205,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::validateActionWithDeclaration
     err.errorLevel = vda5050::ErrorLevel::WARNING;
     err.errorReferences = {{"action.actionType", action.actionType},
                            {"requiredActionType", action_declaration.action_type}};
+    err.errorHint = std::nullopt;
     errors.push_back(err);
   }
 
@@ -214,6 +223,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::validateActionWithDeclaration
     err.errorLevel = vda5050::ErrorLevel::WARNING;
     err.errorReferences = {{"action.blockingType", fmt::format("{}", action.blockingType)},
                            {"allowedBlockingTypes", expected_types}};
+    err.errorHint =
+        fmt::format("Use the correct blocking type for this action ({})", expected_types);
 
     errors.emplace_back(std::move(err));
   }
@@ -242,6 +253,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::validateActionWithDeclaration
       err.errorReferences = {{"action.actionType", action.actionType},
                              {"action.actionId", action.actionId},
                              {"action.parameter.key", p.key}};
+      err.errorHint = "Check the required/allowed parameters for this action";
       errors.emplace_back(std::move(err));
       continue;
     }
@@ -290,6 +302,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::validateActionWithDeclaration
     err.errorDescription = fmt::format("Missing action parameters: {}", missing);
     err.errorReferences = {{"action.actionId", action.actionId},
                            {"action.actionType", action.actionType}};
+    err.errorHint = "Check the required/allowed parameters for this action";
+    errors.emplace_back(std::move(err));
     errors.emplace_back(std::move(err));
   }
 
@@ -308,6 +322,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::uniqueActionId(
         {"order.action.actionId", action.actionId},
         {"order.action.actionType", action.actionType},
     };
+    error.errorHint = "Make sure your action has a unique id";
     error.errorLevel = vda5050::ErrorLevel::WARNING;
 
     return {error};
@@ -328,6 +343,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::uniqueActionId(
         {"order.action.actionId", action.actionId},
         {"order.action.actionType", action.actionType},
     };
+    error.errorHint = "Make sure your action has a unique id";
     error.errorLevel = vda5050::ErrorLevel::WARNING;
 
     return {error};
@@ -365,6 +381,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::controlActionFeasible(
     error.errorReferences = {{"action.actionId", action.actionId},
                              {"action.actionType", action.actionType},
                              {"internal.orderStatus", fmt::format("{}", order_status)}};
+    error.errorHint =
+        "Make sure to only pause the AGV, when it is not already paused or being paused";
     return {error};
   } else if (action.actionType == "stopPause" && !isResumable(order_status)) {
     vda5050::Error error;
@@ -374,6 +392,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::controlActionFeasible(
     error.errorReferences = {{"action.actionId", action.actionId},
                              {"action.actionType", action.actionType},
                              {"internal.orderStatus", fmt::format("{}", order_status)}};
+    error.errorHint = "Make sure to only resume the AGV, when it is paused";
     return {error};
   } else if (action.actionType == "cancelOrder" && !isCancelable(order_status)) {
     vda5050::Error error;
@@ -383,6 +402,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::controlActionFeasible(
     error.errorReferences = {{"action.actionId", action.actionId},
                              {"action.actionType", action.actionType},
                              {"internal.orderStatus", fmt::format("{}", order_status)}};
+    error.errorHint = "Make sure to only cancel the current Order, when it is not already canceled "
+                      "or transitioning between paused and resumed";
     return {error};
   } else {
     return {};
diff --git a/src/vda5050++/core/checks/header.cpp b/src/vda5050++/core/checks/header.cpp
index 9254c9e..29e86be 100644
--- a/src/vda5050++/core/checks/header.cpp
+++ b/src/vda5050++/core/checks/header.cpp
@@ -28,6 +28,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkHeader(
     err.errorReferences = {{{"header.headerId", std::to_string(header.headerId)},
                             {"header.manufacturer", header.manufacturer}}};
     err.errorLevel = vda5050::ErrorLevel::WARNING;
+    err.errorHint = "Make sure the manufacturer is correctly configured";
     errors.push_back(std::move(err));
   }
 
@@ -39,6 +40,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkHeader(
     err.errorReferences = {{{"header.headerId", std::to_string(header.headerId)},
                             {"header.serialNumber", header.serialNumber}}};
     err.errorLevel = vda5050::ErrorLevel::WARNING;
+    err.errorHint = "Make sure the serial number is correctly configured";
     errors.push_back(std::move(err));
   }
 
@@ -50,6 +52,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkHeader(
     err.errorReferences = {
         {{"header.headerId", std::to_string(header.headerId)}, {"header.version", header.version}}};
     err.errorLevel = vda5050::ErrorLevel::WARNING;
+    err.errorHint = "Make sure to use a compatible version of the VDA5050 protocol";
     errors.push_back(std::move(err));
   }
 
diff --git a/src/vda5050++/core/checks/order.cpp b/src/vda5050++/core/checks/order.cpp
index fec127a..7fead7c 100644
--- a/src/vda5050++/core/checks/order.cpp
+++ b/src/vda5050++/core/checks/order.cpp
@@ -23,6 +23,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
              {{{"order.orderId", order.orderId},
                {"order.orderUpdateId", std::to_string(order.orderUpdateId)}}},
              "This order does not contain any nodes",
+             "Do not send empty orders, if you intend to cancel this order, please use the "
+             "cancelOrder instant action",
              vda5050::ErrorLevel::WARNING}};
   }
 
@@ -35,6 +37,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
                  {"node.nodeId", node.nodeId},
                  {"node.sequenceId", std::to_string(node.sequenceId)}}},
                "The order contains a node with an odd sequence id",
+               "Make sure all Nodes have even sequence ids and all Edges have odd sequence ids",
                vda5050::ErrorLevel::WARNING}};
     }
     if (found_base.find(node.sequenceId) != found_base.end() ||
@@ -45,6 +48,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
                  {"node.nodeId", node.nodeId},
                  {"node.sequenceId", std::to_string(node.sequenceId)}}},
                "The order contains duplicate sequence ids",
+               "Make sure all Nodes have unique sequence ids",
                vda5050::ErrorLevel::WARNING}};
     }
     if (node.released) {
@@ -63,6 +67,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
                  {"edge.edgeId", edge.edgeId},
                  {"edge.sequenceId", std::to_string(edge.sequenceId)}}},
                "The order contains a edge with an even sequence id",
+               "Make sure all Nodes have even sequence ids and all Edges have odd sequence ids",
                vda5050::ErrorLevel::WARNING}};
     }
     if (found_base.find(edge.sequenceId) != found_base.end() ||
@@ -73,6 +78,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
                  {"edge.edgeId", edge.edgeId},
                  {"edge.sequenceId", std::to_string(edge.sequenceId)}}},
                "The order contains duplicate sequence ids",
+               "Make sure all Edges have unique sequence ids",
                vda5050::ErrorLevel::WARNING}};
     }
     if (edge.released) {
@@ -102,6 +108,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
              {{{"order.orderId", order.orderId},
                {"order.orderUpdateId", std::to_string(order.orderUpdateId)}}},
              "The order skips sequence ids",
+             "Make sure your order contains a continuous sequence of ids",
              vda5050::ErrorLevel::WARNING}};
   }
 
@@ -114,6 +121,7 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderGraphConsistency(
                {{{"order.orderId", order.orderId},
                  {"order.orderUpdateId", std::to_string(order.orderUpdateId)}}},
                "The order contains a horizon sequence id smaller then a base sequence id",
+               "Make sure your order contains a clear separation between base and horizon",
                vda5050::ErrorLevel::WARNING}};
     }
   }
@@ -130,6 +138,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderId(const vda5050::O
     error.errorType = "orderUpdateError";
     error.errorDescription = "6.6.4.3 - Cannot accept decreasing orderUpdateId";
     error.errorLevel = vda5050::ErrorLevel::WARNING;
+    error.errorHint =
+        "Make sure your orderUpdateIds do not increase. Otherwise use another orderId";
     error.errorReferences = {
         {"state.orderId", id},
         {"state.orderUpdateId", std::to_string(update_id)},
@@ -161,6 +171,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderAppend(const vda505
     return {{"orderUpdateError",
              {{{"order.orderId", order.orderId}, {"state.orderId", id}}},
              "Order ID does not match the current (unfinished) one",
+             "Your order replaces the current one, but the current order is not finished yet. Try "
+             "to send an order update instead or cancel the current order.",
              vda5050::ErrorLevel::WARNING}};
   }
 
@@ -190,6 +202,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderAppend(const vda505
                {"order.node.sequenceId", std::to_string(order_first_node_it->sequenceId)},
                {"state.baseSequenceId", base_last ? std::to_string(*base_last) : "<none>"}}},
              "Could not stitch order due to invalid sequence ids",
+             "When appending an order, the first node must have a sequence id equal to the last "
+             "base node's sequence id",
              vda5050::ErrorLevel::WARNING}};
   }
 
@@ -202,6 +216,8 @@ std::list<vda5050::Error> vda5050pp::core::checks::checkOrderAppend(const vda505
                {{{"order.nodes[0]", vda5050::json(*order_first_node_it).dump(2)},
                  {"state.baseNodes[-1]", vda5050::json(*last_base_node.getNode()).dump(2)}}},
                "The first node of the order does not equal the last base node",
+               "Make sure your appending order has exactly the same first node as the last node of "
+               "the base.",
                vda5050::ErrorLevel::WARNING}};
     }
   }
diff --git a/src/vda5050++/core/common/conversion.cpp b/src/vda5050++/core/common/conversion.cpp
index 128ab8c..f024faa 100644
--- a/src/vda5050++/core/common/conversion.cpp
+++ b/src/vda5050++/core/common/conversion.cpp
@@ -95,5 +95,7 @@ vda5050::AgvAction vda5050pp::core::common::fromActionDeclaration(
     agv_action.actionScopes.push_back(vda5050::ActionScope::INSTANT);
   }
 
+  agv_action.blockingTypes = std::vector(decl.blocking_types.begin(), decl.blocking_types.end());
+
   return agv_action;
 }
\ No newline at end of file
diff --git a/src/vda5050++/core/factsheet/factsheet_event_handler.cpp b/src/vda5050++/core/factsheet/factsheet_event_handler.cpp
index 9d5736b..4f3b33a 100644
--- a/src/vda5050++/core/factsheet/factsheet_event_handler.cpp
+++ b/src/vda5050++/core/factsheet/factsheet_event_handler.cpp
@@ -38,11 +38,11 @@ void FactsheetEventHandler::handleFactsheetGatherEvent(
     vda5050::AgvFactsheet factsheet;
     factsheet.agvGeometry = gatherGeometry();
     factsheet.loadSpecification = gatherLoadSpecification();
-    factsheet.localizationParameters = gatherLocalizationParameters();
     factsheet.physicalParameters = gatherPhysicalParameters();
     factsheet.protocolFeatures = gatherProtocolFeatures();
     factsheet.protocolLimits = gatherProtocolLimits();
     factsheet.typeSpecification = gatherTypeSpecification();
+    factsheet.vehicleConfig = gatherVehicleConfig();
 
     result.setValue(std::move(factsheet));
   } catch (const vda5050pp::VDA5050PPError &e) {
diff --git a/src/vda5050++/core/factsheet/gather.cpp b/src/vda5050++/core/factsheet/gather.cpp
index 134388b..50b8665 100644
--- a/src/vda5050++/core/factsheet/gather.cpp
+++ b/src/vda5050++/core/factsheet/gather.cpp
@@ -15,6 +15,7 @@
 #include "vda5050++/config/visualization_timer_subconfig.h"
 #include "vda5050++/core/instance.h"
 #include "vda5050++/core/logger.h"
+#include "vda5050++/version.h"
 
 using namespace std::chrono_literals;
 
@@ -31,10 +32,6 @@ vda5050::LoadSpecification vda5050pp::core::factsheet::gatherLoadSpecification()
   return Instance::ref().getConfig().getAgvDescription().load_specification;
 }
 
-vda5050::json vda5050pp::core::factsheet::gatherLocalizationParameters() {
-  return Instance::ref().getConfig().getAgvDescription().localization_parameters;
-}
-
 vda5050::PhysicalParameters vda5050pp::core::factsheet::gatherPhysicalParameters() {
   return Instance::ref().getConfig().getAgvDescription().physical_parameters;
 }
@@ -111,4 +108,23 @@ vda5050::ProtocolLimits vda5050pp::core::factsheet::gatherProtocolLimits() {
 
 vda5050::TypeSpecification vda5050pp::core::factsheet::gatherTypeSpecification() {
   return Instance::ref().getConfig().getAgvDescription().type_specification;
+}
+
+vda5050::VehicleConfig vda5050pp::core::factsheet::gatherVehicleConfig() {
+  vda5050::VehicleConfig vehicle_config;
+
+  // Write the versions related to libVDA5050++
+  vehicle_config.versions = std::vector<vda5050::VersionInfo>{
+      vda5050::VersionInfo{"libVDA5050++", std::string(vda5050pp::version::getLibraryVersion())},
+      vda5050::VersionInfo{"VDA5050", std::string(vda5050pp::version::getCurrentVersion())},
+  };
+
+  // Write the user versions
+  for (const auto &vi : Instance::ref().getConfig().getAgvDescription().user_versions) {
+    vehicle_config.versions->push_back(vi);
+  }
+
+  vehicle_config.network = Instance::ref().getConfig().getAgvDescription().network;
+
+  return vehicle_config;
 }
\ No newline at end of file
diff --git a/src/vda5050++/core/instance.cpp b/src/vda5050++/core/instance.cpp
index 0bc731f..de4c57f 100644
--- a/src/vda5050++/core/instance.cpp
+++ b/src/vda5050++/core/instance.cpp
@@ -436,4 +436,6 @@ vda5050pp::core::state::OrderManager &Instance::getOrderManager() { return this-
 
 vda5050pp::core::state::StatusManager &Instance::getStatusManager() {
   return this->status_manager_;
-}
\ No newline at end of file
+}
+
+vda5050pp::core::state::MapManager &Instance::getMapManager() { return this->map_manager_; }
\ No newline at end of file
diff --git a/src/vda5050++/core/messages/mqtt_module.cpp b/src/vda5050++/core/messages/mqtt_module.cpp
index a9f2502..f6aaddb 100644
--- a/src/vda5050++/core/messages/mqtt_module.cpp
+++ b/src/vda5050++/core/messages/mqtt_module.cpp
@@ -18,6 +18,11 @@
 #include "vda5050++/core/logger.h"
 #include "vda5050++/version.h"
 
+/// QOS-Level for communication (order, instantActions, state, visualization, factsheet)
+constexpr int comm_qos = 0;
+/// QOS-Level for the connection topic (at least 1)
+constexpr int conn_qos = 1;
+
 using namespace vda5050pp::core::messages;
 using namespace std::chrono_literals;
 
@@ -60,7 +65,7 @@ mqtt::will_options MqttModule::getWill() {
   mqtt::will_options will;
   will.set_topic(this->connection_topic_);
   will.set_retained(true);
-  will.set_qos(this->k_qos);
+  will.set_qos(conn_qos);
   will.set_payload(j.dump());
 
   return will;
@@ -122,8 +127,8 @@ void MqttModule::on_success(const mqtt::token &) {
 }
 
 void MqttModule::connected(const std::string & /*cause*/) {
-  this->mqtt_client_->subscribe(this->order_topic_, this->k_qos);
-  this->mqtt_client_->subscribe(this->instant_actions_topic_, this->k_qos);
+  this->mqtt_client_->subscribe(this->order_topic_, comm_qos);
+  this->mqtt_client_->subscribe(this->instant_actions_topic_, comm_qos);
 
   getMqttLogger()->info("MqttModule: online");
   this->state_ = State::k_online;
@@ -243,7 +248,7 @@ void MqttModule::sendState(const vda5050::State &state) const {
   auto msg = std::make_shared<mqtt::message>();
   msg->set_topic(this->state_topic_);
   msg->set_payload(j.dump());
-  msg->set_qos(this->k_qos);
+  msg->set_qos(comm_qos);
   this->mqtt_client_->publish(msg);
 }
 void MqttModule::sendVisualization(const vda5050::Visualization &visualization) const {
@@ -258,7 +263,7 @@ void MqttModule::sendVisualization(const vda5050::Visualization &visualization)
   auto msg = std::make_shared<mqtt::message>();
   msg->set_topic(this->visualization_topic_);
   msg->set_payload(j.dump());
-  msg->set_qos(this->k_qos);
+  msg->set_qos(comm_qos);
   this->mqtt_client_->publish(msg);
 }
 
@@ -274,7 +279,7 @@ void MqttModule::sendConnection(const vda5050::Connection &connection) const {
   auto msg = std::make_shared<mqtt::message>();
   msg->set_topic(this->connection_topic_);
   msg->set_payload(j.dump());
-  msg->set_qos(this->k_qos);
+  msg->set_qos(conn_qos);
   msg->set_retained(true);
   this->mqtt_client_->publish(msg);
 }
@@ -291,7 +296,7 @@ void MqttModule::sendFactsheet(const vda5050::AgvFactsheet &factsheet) const {
   auto msg = std::make_shared<mqtt::message>();
   msg->set_topic(this->factsheet_topic_);
   msg->set_payload(j.dump());
-  msg->set_qos(this->k_qos);
+  msg->set_qos(comm_qos);
   msg->set_retained(true);
   this->mqtt_client_->publish(msg);
 }
diff --git a/src/vda5050++/core/order/action_task.cpp b/src/vda5050++/core/order/action_task.cpp
index aa6abbf..3f06371 100644
--- a/src/vda5050++/core/order/action_task.cpp
+++ b/src/vda5050++/core/order/action_task.cpp
@@ -305,19 +305,39 @@ const vda5050::Action &ActionTask::getAction() const {
 }
 
 void ActionTask::transition(const ActionTransition &transition) {
+  if (this->state_ == nullptr) {
+    throw vda5050pp::VDA5050PPNullPointer(MK_EX_CONTEXT("this->state_ is nullptr"));
+  }
   getOrderLogger()->debug("ActionTask(id={})::transition pre_state_={}", this->action_->actionId,
                           this->state_->describe());
   this->state_ = this->state_->transition(transition);
+  if (this->state_ == nullptr) {
+    throw vda5050pp::VDA5050PPNullPointer(
+        MK_EX_CONTEXT("this->state_->transition() returned nullptr"));
+  }
   getOrderLogger()->debug("ActionTask(id={})::transition post_state_={}", this->action_->actionId,
                           this->state_->describe());
   this->state_->effect();
 }
 
-bool ActionTask::isTerminal() const { return this->state_->isTerminal(); }
+bool ActionTask::isTerminal() const {
+  if (this->state_ == nullptr) {
+    throw vda5050pp::VDA5050PPNullPointer(MK_EX_CONTEXT("this->state_ is nullptr"));
+  }
+  return this->state_->isTerminal();
+}
 
-bool ActionTask::isPaused() const { return this->state_->isPaused(); }
+bool ActionTask::isPaused() const {
+  if (this->state_ == nullptr) {
+    throw vda5050pp::VDA5050PPNullPointer(MK_EX_CONTEXT("this->state_ is nullptr"));
+  }
+  return this->state_->isPaused();
+}
 
 std::string ActionTask::describe() const {
+  if (this->state_ == nullptr) {
+    throw vda5050pp::VDA5050PPNullPointer(MK_EX_CONTEXT("this->state_ is nullptr"));
+  }
   return fmt::format("ActionTask(id={}) state: {}", this->action_->actionId,
                      this->state_->describe());
 }
\ No newline at end of file
diff --git a/src/vda5050++/core/state/map_manager.cpp b/src/vda5050++/core/state/map_manager.cpp
new file mode 100644
index 0000000..8f3fedd
--- /dev/null
+++ b/src/vda5050++/core/state/map_manager.cpp
@@ -0,0 +1,57 @@
+// Copyright Open Logistics Foundation
+//
+// Licensed under the Open Logistics Foundation License 1.3.
+// For details on the licensing terms, see the LICENSE file.
+// SPDX-License-Identifier: OLFL-1.3
+//
+#include "vda5050++/core/state/map_manager.h"
+
+using namespace vda5050pp::core::state;
+
+void MapManager::enableMap(std::string_view map_id, std::string_view map_version) {
+  for (auto &map : this->maps_) {
+    if (map.mapId == map_id) {
+      if (map.mapVersion == map_version) {
+        map.mapStatus = vda5050::MapStatus::ENABLED;
+        return;
+      } else {
+        map.mapStatus = vda5050::MapStatus::DISABLED;
+      }
+    }
+  }
+}
+
+void MapManager::deleteMap(std::string_view map_id, std::string_view map_version) {
+  auto it = std::remove_if(this->maps_.begin(), this->maps_.end(), [&](const vda5050::Map &map) {
+    return map.mapId == map_id && map.mapVersion == map_version;
+  });
+
+  this->maps_.erase(it, this->maps_.end());
+}
+
+void MapManager::addMap(const vda5050::Map &map) { this->maps_.push_back(map); }
+
+bool MapManager::hasMap(std::string_view map_id) const {
+  return std::any_of(this->maps_.begin(), this->maps_.end(),
+                     [&](const vda5050::Map &map) { return map.mapId == map_id; });
+}
+
+bool MapManager::hasMap(std::string_view map_id, std::string_view map_version) const {
+  return std::any_of(this->maps_.begin(), this->maps_.end(), [&](const vda5050::Map &map) {
+    return map.mapId == map_id && map.mapVersion == map_version;
+  });
+}
+
+std::optional<vda5050::Map> MapManager::getMap(std::string_view map_id) const {
+  auto it = std::find_if(this->maps_.begin(), this->maps_.end(), [&](const vda5050::Map &map) {
+    return map.mapId == map_id && map.mapStatus == vda5050::MapStatus::ENABLED;
+  });
+
+  if (it == this->maps_.end()) {
+    return std::nullopt;
+  }
+
+  return *it;
+}
+
+void MapManager::dumpTo(vda5050::State &state) const { state.maps = this->maps_; }
\ No newline at end of file
diff --git a/src/vda5050++/core/state/state_event_handler.cpp b/src/vda5050++/core/state/state_event_handler.cpp
index 5b4a0da..b8eaa8d 100644
--- a/src/vda5050++/core/state/state_event_handler.cpp
+++ b/src/vda5050++/core/state/state_event_handler.cpp
@@ -567,6 +567,36 @@ void StateEventHandler::handleInfosAlter(std::shared_ptr<vda5050pp::events::Info
   Instance::ref().getStateEventManager().dispatch(update);
 }
 
+void StateEventHandler::handleAddMap(std::shared_ptr<vda5050pp::events::AddMap> data) const
+    noexcept(false) {
+  if (data == nullptr) {
+    throw vda5050pp::VDA5050PPInvalidEventData(MK_EX_CONTEXT("AddMap Event is empty"));
+  }
+
+  getStateLogger()->info("Adding map: {} (version={})", data->map.mapId, data->map.mapVersion);
+  Instance::ref().getMapManager().addMap(data->map);
+}
+
+void StateEventHandler::handleEnableMap(std::shared_ptr<vda5050pp::events::EnableMap> data) const
+    noexcept(false) {
+  if (data == nullptr) {
+    throw vda5050pp::VDA5050PPInvalidEventData(MK_EX_CONTEXT("EnableMap Event is empty"));
+  }
+
+  getStateLogger()->info("Enabling map: {} (version={})", data->map_id, data->map_version);
+  Instance::ref().getMapManager().enableMap(data->map_id, data->map_version);
+}
+
+void StateEventHandler::handleDeleteMap(std::shared_ptr<vda5050pp::events::DeleteMap> data) const
+    noexcept(false) {
+  if (data == nullptr) {
+    throw vda5050pp::VDA5050PPInvalidEventData(MK_EX_CONTEXT("DeleteMap Event is empty"));
+  }
+
+  getStateLogger()->info("Delete map: {} (version={})", data->map_id, data->map_version);
+  Instance::ref().getMapManager().deleteMap(data->map_id, data->map_version);
+}
+
 void StateEventHandler::initialize(vda5050pp::core::Instance &instance) {
   this->interpreter_subscriber_ = instance.getInterpreterEventManager().getScopedSubscriber();
 
@@ -665,6 +695,13 @@ void StateEventHandler::initialize(vda5050pp::core::Instance &instance) {
 
   this->status_subscriber_->subscribe(
       std::bind(std::mem_fn(&StateEventHandler::handleInfosAlter), this, std::placeholders::_1));
+
+  this->status_subscriber_->subscribe(
+      std::bind(std::mem_fn(&StateEventHandler::handleAddMap), this, std::placeholders::_1));
+  this->status_subscriber_->subscribe(
+      std::bind(std::mem_fn(&StateEventHandler::handleDeleteMap), this, std::placeholders::_1));
+  this->status_subscriber_->subscribe(
+      std::bind(std::mem_fn(&StateEventHandler::handleEnableMap), this, std::placeholders::_1));
 }
 
 void StateEventHandler::deinitialize(vda5050pp::core::Instance &) {
diff --git a/src/vda5050++/core/status_event_manager.cpp b/src/vda5050++/core/status_event_manager.cpp
index e36c95b..f2e4a63 100644
--- a/src/vda5050++/core/status_event_manager.cpp
+++ b/src/vda5050++/core/status_event_manager.cpp
@@ -159,6 +159,30 @@ void ScopedStatusEventSubscriber::subscribe(
           std::move(callback)));
 }
 
+void ScopedStatusEventSubscriber::subscribe(
+    std::function<void(std::shared_ptr<vda5050pp::events::AddMap>)> &&callback) noexcept(true) {
+  this->remover_.appendListener(
+      vda5050pp::events::StatusEventType::k_add_map,
+      eventpp::argumentAdapter<void(std::shared_ptr<vda5050pp::events::AddMap>)>(
+          std::move(callback)));
+}
+
+void ScopedStatusEventSubscriber::subscribe(
+    std::function<void(std::shared_ptr<vda5050pp::events::DeleteMap>)> &&callback) noexcept(true) {
+  this->remover_.appendListener(
+      vda5050pp::events::StatusEventType::k_delete_map,
+      eventpp::argumentAdapter<void(std::shared_ptr<vda5050pp::events::DeleteMap>)>(
+          std::move(callback)));
+}
+
+void ScopedStatusEventSubscriber::subscribe(
+    std::function<void(std::shared_ptr<vda5050pp::events::EnableMap>)> &&callback) noexcept(true) {
+  this->remover_.appendListener(
+      vda5050pp::events::StatusEventType::k_enable_map,
+      eventpp::argumentAdapter<void(std::shared_ptr<vda5050pp::events::EnableMap>)>(
+          std::move(callback)));
+}
+
 void StatusEventManager::threadTask(vda5050pp::core::common::StopToken tkn) noexcept(true) {
   if (this->opts_.synchronous_event_dispatch) {
     // This processing loop is not needed
diff --git a/src/vda5050++/handler/map_action_handler.cpp b/src/vda5050++/handler/map_action_handler.cpp
new file mode 100644
index 0000000..9ee3916
--- /dev/null
+++ b/src/vda5050++/handler/map_action_handler.cpp
@@ -0,0 +1,85 @@
+// Copyright Open Logistics Foundation
+//
+// Licensed under the Open Logistics Foundation License 1.3.
+// For details on the licensing terms, see the LICENSE file.
+// SPDX-License-Identifier: OLFL-1.3
+//
+#include "vda5050++/handler/map_action_handler.h"
+
+#include "vda5050++/core/common/exception.h"
+#include "vda5050++/core/instance.h"
+#include "vda5050++/misc/action_declarations.h"
+
+vda5050pp::handler::MapActionHandler::MapActionHandler()
+    : SimpleMultiActionHandler({
+          vda5050pp::misc::action_declarations::k_enable_map,
+          vda5050pp::misc::action_declarations::k_download_map,
+          vda5050pp::misc::action_declarations::k_delete_map,
+      }) {}
+
+void vda5050pp::handler::MapActionHandler::stateAddMap(const vda5050::Map &map) const {
+  auto evt = std::make_shared<vda5050pp::events::AddMap>();
+  evt->map = map;
+
+  vda5050pp::core::Instance::ref().getStatusEventManager().dispatch(evt);
+}
+
+void vda5050pp::handler::MapActionHandler::stateEnableMap(std::string_view map_id,
+                                                          std::string_view map_version) const {
+  auto evt = std::make_shared<vda5050pp::events::EnableMap>();
+  evt->map_id = map_id;
+  evt->map_version = map_version;
+
+  vda5050pp::core::Instance::ref().getStatusEventManager().dispatch(evt);
+}
+void vda5050pp::handler::MapActionHandler::stateDeleteMap(std::string_view map_id,
+                                                          std::string_view map_version) const {
+  auto evt = std::make_shared<vda5050pp::events::DeleteMap>();
+  evt->map_id = map_id;
+  evt->map_version = map_version;
+
+  vda5050pp::core::Instance::ref().getStatusEventManager().dispatch(evt);
+}
+
+vda5050pp::handler::ActionCallbacks vda5050pp::handler::MapActionHandler::prepare(
+    std::shared_ptr<vda5050pp::handler::ActionState>,
+    std::shared_ptr<ParametersMap> parameters) noexcept(false) {
+  vda5050pp::handler::ActionCallbacks callbacks;
+
+  callbacks.on_cancel = [](auto &) { /* NOP */ };
+  callbacks.on_pause = [](auto &) { /* NOP */ };
+  callbacks.on_resume = [](auto &) { /* NOP */ };
+  callbacks.on_start = [parameters, this](ActionState &action_state) {
+    std::list<vda5050::Error> result;
+
+    if (action_state.getAction().actionType == "enableMap") {
+      result = this->enableMap(std::get<std::string>(parameters->at("mapId")),
+                               std::get<std::string>(parameters->at("mapVersion")));
+    } else if (action_state.getAction().actionType == "downloadMap") {
+      result = this->downloadMap(
+          std::get<std::string>(parameters->at("mapId")),
+          std::get<std::string>(parameters->at("mapVersion")),
+          std::get<std::string>(parameters->at("mapDownloadLink")),
+          parameters->find("mapHash") != parameters->end()
+              ? std::make_optional(std::get<std::string>(parameters->at("mapHash")))
+              : std::nullopt);
+    } else if (action_state.getAction().actionType == "deleteMap") {
+      result = this->deleteMap(std::get<std::string>(parameters->at("mapId")),
+                               std::get<std::string>(parameters->at("mapVersion")));
+    } else {
+      throw vda5050pp::VDA5050PPInvalidArgument(MK_EX_CONTEXT("Unknown action state"));
+    }
+
+    if (result.empty()) {
+      action_state.setFinished();
+    } else {
+      action_state.setFailed(result);
+    }
+  };
+
+  return callbacks;
+}
+
+void vda5050pp::handler::MapActionHandler::reset() {
+  /* NOP, because nothing meaningful can be reset here */
+}
\ No newline at end of file
diff --git a/src/vda5050++/version.cpp b/src/vda5050++/version.cpp
index 9c52536..1abc73d 100644
--- a/src/vda5050++/version.cpp
+++ b/src/vda5050++/version.cpp
@@ -12,7 +12,7 @@
 
 static const std::string_view k_library_version = STRING_LITERAL(LIBVDA5050PP_VERSION);
 
-static const std::string_view k_current = "2.0.0";
+static const std::string_view k_current = "2.1.0";
 
 static const std::set<std::string_view, std::less<>> k_compatible = {k_current};
 
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 9868924..d8f0018 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -68,6 +68,7 @@ add_executable(vda5050++_test
   ${PROJECT_SOURCE_DIR}/test/vda5050++/core/order/navigation_task.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/core/order/scheduler.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/core/state/graph.cpp
+  ${PROJECT_SOURCE_DIR}/test/vda5050++/core/state/map_manager.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/core/state/state_event_handler.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/core/validation/validation_event_handler.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/event_behaviour/combined.cpp
@@ -77,6 +78,7 @@ add_executable(vda5050++_test
   ${PROJECT_SOURCE_DIR}/test/vda5050++/events/synchronized_event.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/handle.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/handler/base_navigation_handler.cpp
+  ${PROJECT_SOURCE_DIR}/test/vda5050++/handler/map_action_handler.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/high_level_behaviour/cancel_order.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/misc/action_parameter_view.cpp
   ${PROJECT_SOURCE_DIR}/test/vda5050++/observer/message_observer.cpp
diff --git a/test/vda5050++/core/factsheet/gather.cpp b/test/vda5050++/core/factsheet/gather.cpp
index 6e3cad5..935c7a7 100644
--- a/test/vda5050++/core/factsheet/gather.cpp
+++ b/test/vda5050++/core/factsheet/gather.cpp
@@ -24,12 +24,18 @@ TEST_CASE("core::factsheet::gather", "[core][factsheet]") {
   cfg.refAgvDescription().agv_geometry.wheelDefinitions = std::vector<vda5050::WheelDefinition>();
   cfg.refAgvDescription().load_specification.loadPositions = {"a", "b", "c"};
   cfg.refAgvDescription().load_specification.loadSets = std::vector<vda5050::LoadSet>();
-  cfg.refAgvDescription().localization_parameters =
-      vda5050::json::parse(R"({ "a": 1, "b": null  })");
   cfg.refAgvDescription().physical_parameters.accelerationMax = 1.0;
   cfg.refAgvDescription().physical_parameters.heightMax = 100.0;
   cfg.refAgvDescription().type_specification.agvClass = "class";
   cfg.refAgvDescription().type_specification.seriesName = "series_name";
+  cfg.refAgvDescription().user_versions = {
+      vda5050::VersionInfo{
+          .key = "a",
+          .value = "1",
+      },
+  };
+  cfg.refAgvDescription().network.defaultGateway = "gateway";
+  cfg.refAgvDescription().network.dnsServers = {{"dns1", "dns2"}};
 
   vda5050pp::core::Instance::reset();
   auto instance = vda5050pp::core::Instance::init(cfg).lock();
@@ -43,11 +49,6 @@ TEST_CASE("core::factsheet::gather", "[core][factsheet]") {
             vda5050pp::core::factsheet::gatherLoadSpecification());
   }
 
-  SECTION("The LocalizationParameters from the cfg is used") {
-    REQUIRE(cfg.getAgvDescription().localization_parameters ==
-            vda5050pp::core::factsheet::gatherLocalizationParameters());
-  }
-
   SECTION("The PhysicalParameters from the cfg is used") {
     REQUIRE(cfg.getAgvDescription().physical_parameters ==
             vda5050pp::core::factsheet::gatherPhysicalParameters());
@@ -76,4 +77,14 @@ TEST_CASE("core::factsheet::gather", "[core][factsheet]") {
     REQUIRE(cfg.getAgvDescription().type_specification ==
             vda5050pp::core::factsheet::gatherTypeSpecification());
   }
+
+  SECTION("The Vehicle config from the cfg is used") {
+    REQUIRE(cfg.getAgvDescription().network ==
+            vda5050pp::core::factsheet::gatherVehicleConfig().network);
+    auto versions = vda5050pp::core::factsheet::gatherVehicleConfig().versions;
+    auto it = std::find_if(versions->begin(), versions->end(), [](const vda5050::VersionInfo &vi) {
+      return vi.key == "a" && vi.value == "1";
+    });
+    REQUIRE(it != versions->end());
+  }
 }
diff --git a/test/vda5050++/core/state/map_manager.cpp b/test/vda5050++/core/state/map_manager.cpp
new file mode 100644
index 0000000..cd88361
--- /dev/null
+++ b/test/vda5050++/core/state/map_manager.cpp
@@ -0,0 +1,104 @@
+// Copyright Open Logistics Foundation
+//
+// Licensed under the Open Logistics Foundation License 1.3.
+// For details on the licensing terms, see the LICENSE file.
+// SPDX-License-Identifier: OLFL-1.3
+//
+
+#include "vda5050++/core/state/map_manager.h"
+
+#include <catch2/catch_all.hpp>
+
+static vda5050::State getDump(const vda5050pp::core::state::MapManager &map_manager) {
+  vda5050::State state;
+  map_manager.dumpTo(state);
+  return state;
+}
+
+TEST_CASE("core::state::MapManager - behavior", "[core][state]") {
+  vda5050pp::core::state::MapManager map_manager;
+
+  vda5050::Map map11{
+      .mapId = "map1",
+      .mapVersion = "1",
+      .mapDescription = "Map 11",
+      .mapStatus = vda5050::MapStatus::DISABLED,
+  };
+
+  vda5050::Map map12{
+      .mapId = "map1",
+      .mapVersion = "2",
+      .mapDescription = "Map 12",
+      .mapStatus = vda5050::MapStatus::DISABLED,
+  };
+
+  vda5050::Map map21{
+      .mapId = "map2",
+      .mapVersion = "1",
+      .mapDescription = "Map 21",
+      .mapStatus = vda5050::MapStatus::DISABLED,
+  };
+
+  vda5050::Map map22{
+      .mapId = "map2",
+      .mapVersion = "2",
+      .mapDescription = "Map 22",
+      .mapStatus = vda5050::MapStatus::DISABLED,
+  };
+
+  WHEN("The map manager is empty") {
+    THEN("Delete map does not throw") { REQUIRE_NOTHROW(map_manager.deleteMap("map1", "1.0.0")); }
+    THEN("Get map returns nullopt") { REQUIRE(map_manager.getMap("map1") == std::nullopt); }
+    THEN("Has map returns false") { REQUIRE_FALSE(map_manager.hasMap("map1", "1.0.0")); }
+    THEN("Enable map does not throw") { REQUIRE_NOTHROW(map_manager.enableMap("map1", "1.0.0")); }
+    THEN("The dumped state map field is empty") { REQUIRE(getDump(map_manager).maps.empty()); }
+  }
+
+  WHEN("Adding maps") {
+    map_manager.addMap(map11);
+    map_manager.addMap(map12);
+    map_manager.addMap(map21);
+    map_manager.addMap(map22);
+
+    WHEN("No map is enabled") {
+      THEN("Getting maps returns nullopt") {
+        REQUIRE(map_manager.getMap("map1") == std::nullopt);
+        REQUIRE(map_manager.getMap("map2") == std::nullopt);
+      }
+      THEN("Has map returns true") {
+        REQUIRE(map_manager.hasMap("map1"));
+        REQUIRE(map_manager.hasMap("map2"));
+        REQUIRE(map_manager.hasMap("map1", "1"));
+        REQUIRE(map_manager.hasMap("map2", "2"));
+      }
+    }
+    WHEN("A version of a map is enabled") {
+      map_manager.enableMap("map1", "2");
+      map_manager.enableMap("map2", "1");
+
+      THEN("Getting maps returns the correct map") {
+        REQUIRE(map_manager.getMap("map1") != std::nullopt);
+        REQUIRE(map_manager.getMap("map2") != std::nullopt);
+        REQUIRE(map_manager.getMap("map1")->mapDescription == "Map 12");
+        REQUIRE(map_manager.getMap("map2")->mapDescription == "Map 21");
+      }
+      WHEN("Deleting an enabled map") {
+        map_manager.deleteMap("map1", "2");
+
+        THEN("Getting maps returns the correct map") {
+          REQUIRE(map_manager.getMap("map1") == std::nullopt);
+          REQUIRE(map_manager.getMap("map2") != std::nullopt);
+          REQUIRE(map_manager.getMap("map2")->mapDescription == "Map 21");
+        }
+      }
+      THEN("Dumping the state contains the maps") {
+        auto state = getDump(map_manager);
+        REQUIRE(state.maps.size() == 4);
+        REQUIRE(state.maps[0].mapDescription == "Map 11");
+        REQUIRE(state.maps[1].mapDescription == "Map 12");
+        REQUIRE(state.maps[2].mapDescription == "Map 21");
+        REQUIRE(state.maps[3].mapDescription == "Map 22");
+      }
+    }
+  }
+}
\ No newline at end of file
diff --git a/test/vda5050++/handler/map_action_handler.cpp b/test/vda5050++/handler/map_action_handler.cpp
new file mode 100644
index 0000000..b36aec4
--- /dev/null
+++ b/test/vda5050++/handler/map_action_handler.cpp
@@ -0,0 +1,167 @@
+// Copyright Open Logistics Foundation
+//
+// Licensed under the Open Logistics Foundation License 1.3.
+// For details on the licensing terms, see the LICENSE file.
+// SPDX-License-Identifier: OLFL-1.3
+//
+
+#include "vda5050++/handler/map_action_handler.h"
+
+#include <catch2/catch_all.hpp>
+
+#include "vda5050++/core/instance.h"
+
+using namespace std::chrono_literals;
+
+class TestMapHandler : public vda5050pp::handler::MapActionHandler {
+private:
+  std::promise<std::pair<std::string, std::string>> enable_promise_;
+  std::promise<std::pair<std::string, std::string>> delete_promise_;
+  std::promise<std::tuple<std::string, std::string, std::string>> download_promise_;
+
+public:
+  void resetPromise() {
+    enable_promise_ = std::promise<std::pair<std::string, std::string>>();
+    delete_promise_ = std::promise<std::pair<std::string, std::string>>();
+    download_promise_ = std::promise<std::tuple<std::string, std::string, std::string>>();
+  }
+
+  std::future<std::pair<std::string, std::string>> getEnableFuture() {
+    return enable_promise_.get_future();
+  }
+  std::future<std::pair<std::string, std::string>> getDeleteFuture() {
+    return delete_promise_.get_future();
+  }
+  std::future<std::tuple<std::string, std::string, std::string>> getDownloadFuture() {
+    return download_promise_.get_future();
+  }
+
+protected:
+  std::list<vda5050::Error> enableMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    enable_promise_.set_value({std::string(map_id), std::string(map_version)});
+    return {};
+  }
+
+  std::list<vda5050::Error> deleteMap(std::string_view map_id,
+                                      std::string_view map_version) override {
+    delete_promise_.set_value({std::string(map_id), std::string(map_version)});
+    return {};
+  }
+
+  std::list<vda5050::Error> downloadMap(std::string_view map_id, std::string_view map_version,
+                                        std::string_view map_download_link,
+                                        std::optional<std::string_view> map_hash) override {
+    download_promise_.set_value(
+        {std::string(map_id), std::string(map_version), std::string(map_download_link)});
+    return {};
+  }
+};
+
+TEST_CASE("handler::MapActionHandler", "[handler]") {
+  vda5050pp::core::events::EventManagerOptions evt_opts;
+  evt_opts.synchronous_event_dispatch = false;  // TODO: make this succeed with true
+  vda5050pp::Config cfg;
+  cfg.refGlobalConfig().useWhiteList();
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_action_event_handler_key);
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_interpreter_event_handler_key);
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_order_event_handler_key);
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_message_event_handler_key);
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_state_event_handler_key);
+  cfg.refGlobalConfig().bwListModule(vda5050pp::core::module_keys::k_validation_event_handler_key);
+  cfg.refGlobalConfig().setLogLevel(vda5050pp::config::LogLevel::k_debug);
+  vda5050pp::core::Instance::reset();
+  auto instance = vda5050pp::core::Instance::init(cfg, evt_opts).lock();
+
+  auto handler = std::make_shared<TestMapHandler>();
+  instance->addActionHandler(handler);
+
+  WHEN("An enable map instant action received") {
+    auto ia = std::make_shared<vda5050pp::core::events::ReceiveInstantActionMessageEvent>();
+    ia->instant_actions = std::make_shared<vda5050::InstantActions>();
+    ia->instant_actions->actions.push_back(
+        vda5050::Action{.actionType = "enableMap",
+                        .actionId = "1",
+                        .blockingType = vda5050::BlockingType::NONE,
+                        .actionParameters = {{{"mapId", "Map1"}, {"mapVersion", "V1"}}}});
+
+    instance->getMessageEventManager().synchronousDispatch(ia);
+    auto future = handler->getEnableFuture();
+
+    THEN("The enable map function is called") {
+      REQUIRE(future.wait_for(100ms) == std::future_status::ready);
+      REQUIRE(future.get() == std::pair<std::string, std::string>{"Map1", "V1"});
+    }
+  }
+
+  WHEN("An delete map instant action received") {
+    auto ia = std::make_shared<vda5050pp::core::events::ReceiveInstantActionMessageEvent>();
+    ia->instant_actions = std::make_shared<vda5050::InstantActions>();
+    ia->instant_actions->actions.push_back(
+        vda5050::Action{.actionType = "deleteMap",
+                        .actionId = "2",
+                        .blockingType = vda5050::BlockingType::NONE,
+                        .actionParameters = {{{"mapId", "Map2"}, {"mapVersion", "V2"}}}});
+
+    instance->getMessageEventManager().synchronousDispatch(ia);
+    auto future = handler->getDeleteFuture();
+
+    THEN("The delete map function is called") {
+      REQUIRE(future.wait_for(100ms) == std::future_status::ready);
+      REQUIRE(future.get() == std::pair<std::string, std::string>{"Map2", "V2"});
+    }
+  }
+
+  WHEN("An download map instant action is received") {
+    auto ia = std::make_shared<vda5050pp::core::events::ReceiveInstantActionMessageEvent>();
+    ia->instant_actions = std::make_shared<vda5050::InstantActions>();
+    ia->instant_actions->actions.push_back(vda5050::Action{
+        .actionType = "downloadMap",
+        .actionId = "3",
+        .blockingType = vda5050::BlockingType::NONE,
+        .actionParameters = {
+            {{"mapId", "Map2"}, {"mapVersion", "V2"}, {"mapDownloadLink", "http://example.com"}}}});
+
+    instance->getMessageEventManager().synchronousDispatch(ia);
+    auto future = handler->getDownloadFuture();
+
+    THEN("The download map function is called") {
+      REQUIRE(future.wait_for(100ms) == std::future_status::ready);
+      REQUIRE(future.get() == std::tuple<std::string, std::string, std::string>{
+                                  "Map2", "V2", "http://example.com"});
+    }
+  }
+
+  // Use sync dispatch
+  instance.reset();  // reset instance ptr before resetting the instance
+  vda5050pp::core::Instance::reset();
+  evt_opts.synchronous_event_dispatch = true;
+  instance = vda5050pp::core::Instance::init(cfg, evt_opts).lock();
+
+  WHEN("stateAddMap is called") {
+    vda5050::Map map{
+        .mapId = "id",
+        .mapVersion = "version",
+        .mapStatus = vda5050::MapStatus::DISABLED,
+    };
+
+    handler->stateAddMap(map);
+
+    THEN("It is in the state") { REQUIRE(instance->getMapManager().hasMap("id")); }
+
+    WHEN("stateEnableMap is called") {
+      handler->stateEnableMap("id", "version");
+
+      THEN("It is in the state") {
+        REQUIRE(instance->getMapManager().getMap("id") != std::nullopt);
+        REQUIRE(instance->getMapManager().getMap("id")->mapVersion == "version");
+      }
+
+      WHEN("stateDeleteMap is called") {
+        handler->stateDeleteMap("id", "version");
+
+        THEN("It is not in the state") { REQUIRE_FALSE(instance->getMapManager().hasMap("id")); }
+      }
+    }
+  }
+}
\ No newline at end of file
diff --git a/test/vda5050++/observer/message_observer.cpp b/test/vda5050++/observer/message_observer.cpp
index 72b3640..f4779a6 100644
--- a/test/vda5050++/observer/message_observer.cpp
+++ b/test/vda5050++/observer/message_observer.cpp
@@ -12,11 +12,11 @@
 #include "vda5050++/core/instance.h"
 
 TEST_CASE("observer::MessageObserver - event handling", "[observer]") {
+  vda5050pp::core::Instance::reset();
   vda5050pp::core::events::EventManagerOptions evt_opts;
   evt_opts.synchronous_event_dispatch = true;
   vda5050pp::Config cfg;
   cfg.refGlobalConfig().useWhiteList();
-  vda5050pp::core::Instance::reset();
   auto instance = vda5050pp::core::Instance::init(cfg, evt_opts).lock();
 
   vda5050pp::observer::MessageObserver observer;
diff --git a/test/vda5050++/observer/order_observer.cpp b/test/vda5050++/observer/order_observer.cpp
index 6bf6321..b2d20ee 100644
--- a/test/vda5050++/observer/order_observer.cpp
+++ b/test/vda5050++/observer/order_observer.cpp
@@ -223,8 +223,10 @@ TEST_CASE("observer::OrderObserver - event handling", "[observer]") {
   WHEN("Receiving a ErrorsChanged Event") {
     auto evt = std::make_shared<vda5050pp::events::OrderErrorsChanged>();
     evt->errors = {
-        vda5050::Error{"e1", std::nullopt, std::nullopt, vda5050::ErrorLevel::WARNING},
-        vda5050::Error{"e2", std::nullopt, std::nullopt, vda5050::ErrorLevel::WARNING},
+        vda5050::Error{"e1", std::nullopt, std::nullopt, std::nullopt,
+                       vda5050::ErrorLevel::WARNING},
+        vda5050::Error{"e2", std::nullopt, std::nullopt, std::nullopt,
+                       vda5050::ErrorLevel::WARNING},
     };
 
     std::promise<std::vector<vda5050::Error>> promise;
-- 
GitLab