diff --git a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp index 72e5b8f33073f716e9d3a299ea26dda288dc6066..70b399165ad3c229d96289676e0da6f2280e91a4 100644 --- a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp +++ b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.cpp @@ -49,8 +49,8 @@ namespace armarx::articulated_object { ArticulatedObjectLocalizerExample::ArticulatedObjectLocalizerExample() : - articulatedObjectWriter(new ::armarx::armem::articulated_object::ArticulatedObjectWriter(memoryNameSystem)), - articulatedObjectReader(new ::armarx::armem::articulated_object::ArticulatedObjectReader(memoryNameSystem)) + articulatedObjectWriter(new ::armarx::armem::articulated_object::ArticulatedObjectWriter(memoryNameSystem())), + articulatedObjectReader(new ::armarx::armem::articulated_object::ArticulatedObjectReader(memoryNameSystem())) { } @@ -90,7 +90,8 @@ namespace armarx::articulated_object start = armem::Time::now(); task = new PeriodicTask<ArticulatedObjectLocalizerExample>( - this, &ArticulatedObjectLocalizerExample::run, 1000.f / p.updateFrequency); + this, &ArticulatedObjectLocalizerExample::run, + static_cast<int>(1000.f / p.updateFrequency)); task->start(); } diff --git a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h index b4cab3fc71e6d6b1dd92e3128fd3a90a8c191109..e3747fb3f23fb4429ab7a9d028d85efd3f2befaa 100644 --- a/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h +++ b/source/RobotAPI/components/ArticulatedObjectLocalizerExample/ArticulatedObjectLocalizerExample.h @@ -13,7 +13,7 @@ #include "RobotAPI/libraries/armem/core/Time.h" #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> #include <RobotAPI/interface/armem/server/MemoryInterface.h> -#include <RobotAPI/libraries/armem/client/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/client/plugins.h> #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> #include <RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectReader.h> #include <RobotAPI/libraries/armem_objects/client/articulated_object/ArticulatedObjectWriter.h> diff --git a/source/RobotAPI/components/armem/MemoryNameSystem/CMakeLists.txt b/source/RobotAPI/components/armem/MemoryNameSystem/CMakeLists.txt index 75a50c54304d11e5452f1e4d1f8287a65fd0e9f6..fa06c3e77bf057e9ca37e790f908e981db1147af 100644 --- a/source/RobotAPI/components/armem/MemoryNameSystem/CMakeLists.txt +++ b/source/RobotAPI/components/armem/MemoryNameSystem/CMakeLists.txt @@ -19,4 +19,6 @@ set(HEADERS armarx_add_component("${SOURCES}" "${HEADERS}") #generate the application -armarx_generate_and_add_component_executable() +armarx_generate_and_add_component_executable( + COMPONENT_NAMESPACE "armarx::armem" +) diff --git a/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.cpp b/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.cpp index 47131a79a44f25dabc1e3364fcc7d3d044b3e506..0ebd0eac1dad18f7c53374c4a4fcc5ba173bbf14 100644 --- a/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.cpp +++ b/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.cpp @@ -29,16 +29,12 @@ #include <RobotAPI/libraries/armem/core/error.h> -namespace armarx +namespace armarx::armem { - MemoryNameSystemPropertyDefinitions::MemoryNameSystemPropertyDefinitions(std::string prefix) : - armarx::ComponentPropertyDefinitions(prefix) - { - } armarx::PropertyDefinitionsPtr MemoryNameSystem::createPropertyDefinitions() { - armarx::PropertyDefinitionsPtr defs = new MemoryNameSystemPropertyDefinitions(getConfigIdentifier()); + armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier()); return defs; } @@ -58,7 +54,7 @@ namespace armarx void MemoryNameSystem::onConnectComponent() { - RemoteGui__createTab(); + createRemoteGuiTab(); RemoteGui_startRunningTask(); } @@ -73,19 +69,19 @@ namespace armarx } - armem::data::RegisterMemoryResult MemoryNameSystem::registerMemory( - const armem::data::RegisterMemoryInput& input, const Ice::Current& c) + mns::dto::RegisterServerResult MemoryNameSystem::registerServer( + const mns::dto::RegisterServerInput& input, const Ice::Current& c) { - armem::data::RegisterMemoryResult result = Plugin::registerMemory(input, c); + mns::dto::RegisterServerResult result = PluginUser::registerServer(input, c); tab.rebuild = true; return result; } - armem::data::RemoveMemoryResult MemoryNameSystem::removeMemory( - const armem::data::RemoveMemoryInput& input, const Ice::Current& c) + mns::dto::RemoveServerResult MemoryNameSystem::removeServer( + const mns::dto::RemoveServerInput& input, const Ice::Current& c) { - armem::data::RemoveMemoryResult result = Plugin::removeMemory(input, c); + mns::dto::RemoveServerResult result = PluginUser::removeServer(input, c); tab.rebuild = true; return result; } @@ -94,12 +90,12 @@ namespace armarx // REMOTE GUI - void MemoryNameSystem::RemoteGui__createTab() + void MemoryNameSystem::createRemoteGuiTab() { using namespace armarx::RemoteGui::Client; std::scoped_lock lock(mnsMutex); - GridLayout grid = mns.RemoteGui_buildInfoGrid(); + GridLayout grid = mns().RemoteGui_buildInfoGrid(); VBoxLayout root = {grid, VSpacer()}; RemoteGui_createTab(getName(), root, &tab); @@ -110,7 +106,7 @@ namespace armarx { if (tab.rebuild.exchange(false)) { - RemoteGui__createTab(); + createRemoteGuiTab(); } } diff --git a/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.h b/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.h index 795aecc66f96423aa29b28660694e09ea50a1426..f0279f4a1103a6b6f5a88f4b31ab5692cc5bda74 100644 --- a/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.h +++ b/source/RobotAPI/components/armem/MemoryNameSystem/MemoryNameSystem.h @@ -22,33 +22,16 @@ #pragma once -#include <mutex> - -#include <ArmarXCore/core/Component.h> +#include <RobotAPI/libraries/armem/mns/plugins/PluginUser.h> +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> -// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> - -#include <RobotAPI/libraries/armem/mns/ComponentPlugin.h> +#include <ArmarXCore/core/Component.h> -namespace armarx +namespace armarx::armem { - /** - * @class MemoryNameSystemPropertyDefinitions - * @brief Property definitions of `MemoryNameSystem`. - */ - class MemoryNameSystemPropertyDefinitions : - public armarx::ComponentPropertyDefinitions - { - public: - MemoryNameSystemPropertyDefinitions(std::string prefix); - }; - - - /** * @defgroup Component-MemoryNameSystem MemoryNameSystem * @ingroup RobotAPI-Components @@ -62,11 +45,9 @@ namespace armarx */ class MemoryNameSystem : virtual public armarx::Component - , virtual public armem::mns::ComponentPluginUser + , virtual public armem::mns::plugins::PluginUser , virtual public LightweightRemoteGuiComponentPluginUser - // , virtual public armarx::ArVizComponentPluginUser { - using Plugin = ComponentPluginUser; public: /// @see armarx::ManagedIceObject::getDefaultName() @@ -75,20 +56,23 @@ namespace armarx // mns::MemoryNameSystemInterface interface public: - armem::data::RegisterMemoryResult registerMemory(const armem::data::RegisterMemoryInput& input, const Ice::Current&) override; - armem::data::RemoveMemoryResult removeMemory(const armem::data::RemoveMemoryInput& input, const Ice::Current&) override; + mns::dto::RegisterServerResult registerServer(const mns::dto::RegisterServerInput& input, const Ice::Current&) override; + mns::dto::RemoveServerResult removeServer(const mns::dto::RemoveServerInput& input, const Ice::Current&) override; // Others are inherited from ComponentPluginUser // LightweightRemoteGuiComponentPluginUser interface public: - void RemoteGui__createTab(); + void createRemoteGuiTab(); void RemoteGui_update() override; protected: + /// @see PropertyUser::createPropertyDefinitions() + armarx::PropertyDefinitionsPtr createPropertyDefinitions() override; + /// @see armarx::ManagedIceObject::onInitComponent() void onInitComponent() override; @@ -101,17 +85,13 @@ namespace armarx /// @see armarx::ManagedIceObject::onExitComponent() void onExitComponent() override; - /// @see PropertyUser::createPropertyDefinitions() - armarx::PropertyDefinitionsPtr createPropertyDefinitions() override; - private: struct Properties { - }; - Properties p; + Properties properties; struct RemoteGuiTab : RemoteGui::Client::Tab diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/CMakeLists.txt b/source/RobotAPI/components/armem/client/ExampleMemoryClient/CMakeLists.txt index d699638cd0eb88c194fd66a9382968012ce40660..96cb0013af5534281083ba693c20ff83770f6155 100644 --- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/CMakeLists.txt +++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/CMakeLists.txt @@ -3,11 +3,17 @@ armarx_component_set_name("ExampleMemoryClient") find_package(IVT QUIET) armarx_build_if(IVT_FOUND "IVT not available") +find_package(OpenCV QUIET) +armarx_build_if(OpenCV_FOUND "OpenCV not available") + + set(COMPONENT_LIBS ArmarXCore ArmarXCoreInterfaces # for DebugObserverInterface ArmarXGuiComponentPlugins RobotAPICore RobotAPIInterfaces armem + ${IVT_LIBRARIES} + ${OpenCV_LIBS} ) set(SOURCES diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp index 3678ecd55d64e033e03c1e5f7400db875054cc87..d8b6e4f89038a42fc137a78316cfa3fbd7bc7eb0 100644 --- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp +++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.cpp @@ -22,13 +22,9 @@ #include "ExampleMemoryClient.h" -#include <random> - -#include <SimoxUtility/color/cmaps.h> - -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> -#include <ArmarXCore/core/time/CycleUtil.h> +#include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h> +#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h> #include <RobotAPI/libraries/armem/client/query/Builder.h> #include <RobotAPI/libraries/armem/client/query/query_fns.h> @@ -37,7 +33,23 @@ #include <RobotAPI/libraries/armem/core/operations.h> #include <RobotAPI/libraries/armem/core/wm/ice_conversions.h> -#include <RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.aron.generated.h> +#include <ArmarXCore/core/exceptions/local/ExpressionException.h> +#include <ArmarXCore/core/time/CycleUtil.h> + +#include <SimoxUtility/color/cmaps.h> +#include <SimoxUtility/math/pose/pose.h> + +#include <Eigen/Geometry> + +#include <random> + + +#define STORE_IMAGES 0 + +#if STORE_IMAGES +#include <opencv2/imgcodecs.hpp> +#include <opencv2/imgproc.hpp> +#endif namespace armarx @@ -76,8 +88,8 @@ namespace armarx ARMARX_IMPORTANT << "Waiting for memory '" << p.usedMemoryName << "' ..."; try { - memoryReader = memoryNameSystem.useReader(p.usedMemoryName); - memoryWriter = memoryNameSystem.useWriter(p.usedMemoryName); + memoryReader = memoryNameSystem().useReader(p.usedMemoryName); + memoryWriter = memoryNameSystem().useWriter(p.usedMemoryName); } catch (const armem::error::CouldNotResolveMemoryServer& e) { @@ -93,12 +105,14 @@ namespace armarx // Subscribe to example_entity updates // Using a lambda: - memoryNameSystem.subscribe(exampleEntityID, [&](const armem::MemoryID & exampleEntityID, const std::vector<armem::MemoryID>& snapshotIDs) + memoryNameSystem().subscribe( + exampleEntityID, + [&](const armem::MemoryID & exampleEntityID, const std::vector<armem::MemoryID>& snapshotIDs) { ARMARX_INFO << "Entity " << exampleEntityID << " was updated by " << snapshotIDs.size() << " snapshots."; }); // Using a member function: - memoryNameSystem.subscribe(exampleEntityID, this, &ExampleMemoryClient::processExampleEntityUpdate); + memoryNameSystem().subscribe(exampleEntityID, this, &ExampleMemoryClient::processExampleEntityUpdate); task = new RunningTask<ExampleMemoryClient>(this, &ExampleMemoryClient::run); @@ -121,7 +135,6 @@ namespace armarx { ARMARX_IMPORTANT << "Running example."; run_started = IceUtil::Time::now(); - std::srand(std::time(nullptr)); armem::MemoryID snapshotID = commitSingleSnapshot(exampleEntityID); if (true) @@ -176,6 +189,9 @@ namespace armarx armem::MemoryID ExampleMemoryClient::commitSingleSnapshot(const armem::MemoryID& entityID) { + std::default_random_engine gen(std::random_device{}()); + std::uniform_int_distribution<int> distrib(-20, 20); + // Prepare the update with some empty instances. armem::EntityUpdate update; update.entityID = entityID; @@ -191,7 +207,7 @@ namespace armarx auto sqrt = std::make_shared<aron::datanavigator::DoubleNavigator>(std::sqrt(diff)); auto lin = std::make_shared<aron::datanavigator::LongNavigator>(static_cast<long>(diff * 1000)); - auto rand = std::make_shared<aron::datanavigator::IntNavigator>(std::rand()); + auto rand = std::make_shared<aron::datanavigator::IntNavigator>(distrib(gen)); dict1->addElement("sin", sin); dict1->addElement("cos", cos); @@ -377,25 +393,59 @@ namespace armarx { "three", 3 }, }; + data.the_position = { 42, 24, 4224 }; + data.the_orientation = Eigen::AngleAxisf(1.57f, Eigen::Vector3f(1, 1, 1).normalized()); + data.the_pose = simox::math::pose(data.the_position, data.the_orientation); + + data.the_3x1_vector = { 24, 42, 2442 }; + data.the_4x4_matrix = 42 * Eigen::Matrix4f::Identity(); + toAron(data.memoryLink, armem::MemoryID()); + simox::ColorMap cmap = simox::color::cmaps::plasma(); + { + cv::Mat& image = data.the_rgb24_image; + image.create(10, 20, image.type()); + cmap.set_vlimits(0, float(image.cols + image.rows)); + using Pixel = cv::Point3_<uint8_t>; + image.forEach<Pixel>([&cmap](Pixel& pixel, const int index[]) -> void + { + simox::Color color = cmap(float(index[0] + index[1])); + pixel.x = color.r; + pixel.y = color.g; + pixel.z = color.b; + }); + +#if STORE_IMAGES + cv::Mat out; + cv::cvtColor(image, out, CV_RGB2BGR); + cv::imwrite("the_rgb24_image.png", out); +#endif + } { - data.the_ivt_image = std::make_shared<CByteImage>(); - CByteImage& image = *data.the_ivt_image; - image.Set(20, 10, CByteImage::ImageType::eRGB24); - simox::ColorMap cmap = simox::color::cmaps::plasma(); - cmap.set_vmax(image.width + image.height); - for (int row = 0; row < image.height; ++row) + cv::Mat& image = data.the_depth32_image; + image.create(20, 10, image.type()); + image.forEach<float>([&image](float& pixel, const int index[]) -> void + { + pixel = 100 * float(index[0] + index[1]) / float(image.rows + image.cols); + }); + +#if STORE_IMAGES + cmap.set_vlimits(0, 100); + cv::Mat rgb(image.rows, image.cols, CV_8UC3); + using Pixel = cv::Point3_<uint8_t>; + rgb.forEach<Pixel>([&image, &cmap](Pixel& pixel, const int index[]) -> void { - for (int col = 0; col < image.width; ++col) - { - simox::Color color = cmap(row + col); - unsigned char* p = &image.pixels[(row * image.width + col) * image.bytesPerPixel]; - p[0] = color.r; - p[1] = color.g; - p[2] = color.b; - } - } + simox::Color color = cmap(image.at<float>(index)); + pixel.x = color.r; + pixel.y = color.g; + pixel.z = color.b; + }); + + cv::Mat out; + cv::cvtColor(rgb, out, CV_RGB2BGR); + cv::imwrite("the_depth32_image.png", out); +#endif } update.instancesData = { data.toAron() }; diff --git a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h index ca28ab86bc1e755c49b93649fd77b26aac0a4250..40eb57625848ba442e7be2abb10ed1c832ee8440 100644 --- a/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h +++ b/source/RobotAPI/components/armem/client/ExampleMemoryClient/ExampleMemoryClient.h @@ -23,18 +23,17 @@ #pragma once +#include <RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h> +#include <RobotAPI/libraries/armem/client/Reader.h> +#include <RobotAPI/libraries/armem/client/Writer.h> +#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> + +#include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> -// ArmarX #include <ArmarXCore/core/Component.h> #include <ArmarXCore/interface/observers/ObserverInterface.h> #include <ArmarXCore/util/tasks.h> -#include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> - -// RobotAPI -#include <RobotAPI/interface/armem/server/MemoryInterface.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> -#include <RobotAPI/libraries/armem/client/ComponentPlugin.h> -#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> namespace armarx @@ -54,8 +53,8 @@ namespace armarx */ class ExampleMemoryClient : virtual public armarx::Component, - virtual public armarx::armem::client::ComponentPluginUser, - virtual public LightweightRemoteGuiComponentPluginUser + virtual public armarx::armem::ListeningClientPluginUser, + virtual public armarx::LightweightRemoteGuiComponentPluginUser { public: @@ -111,6 +110,8 @@ namespace armarx }; Properties p; + armem::client::Reader memoryReader; + armem::client::Writer memoryWriter; armem::MemoryID exampleProviderID; armem::MemoryID exampleEntityID; diff --git a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp index 8ab75efc78ddad8492598356df374266947fe515..552f68ac7ea45c24a0041dbedaff43a06c3e2c31 100644 --- a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp +++ b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.cpp @@ -31,7 +31,7 @@ namespace armarx::robot_state { VirtualRobotReaderExampleClient::VirtualRobotReaderExampleClient() : - virtualRobotReader(this->memoryNameSystem) {} + virtualRobotReader(this->memoryNameSystem()) {} armarx::PropertyDefinitionsPtr VirtualRobotReaderExampleClient::createPropertyDefinitions() { diff --git a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h index 33770ad5425f8824fca2f40ae45323861f29cc91..8111d62c43d3b70546e4d070dd7aec7f55fc717f 100644 --- a/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h +++ b/source/RobotAPI/components/armem/client/VirtualRobotReaderExampleClient/VirtualRobotReaderExampleClient.h @@ -32,7 +32,7 @@ // RobotAPI #include <RobotAPI/interface/armem/server/MemoryInterface.h> #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> -#include <RobotAPI/libraries/armem/client/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/client/plugins.h> #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> #include <RobotAPI/libraries/armem_robot_state/client/common/VirtualRobotReader.h> diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/CMakeLists.txt b/source/RobotAPI/components/armem/server/ExampleMemory/CMakeLists.txt index 99070a2c52f970a6ac9f64992a5a9a113de7f227..cc053e479e74106b7a682d6c2c40549eb486f5d0 100644 --- a/source/RobotAPI/components/armem/server/ExampleMemory/CMakeLists.txt +++ b/source/RobotAPI/components/armem/server/ExampleMemory/CMakeLists.txt @@ -8,7 +8,6 @@ set(COMPONENT_LIBS ArmarXCore ArmarXCoreInterfaces # for DebugObserverInterface ArmarXGuiComponentPlugins RobotAPICore RobotAPIInterfaces armem - # RobotAPIComponentPlugins # for ArViz and other plugins ${IVT_LIBRARIES} ) diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp index 879809064b9cdb1429b49925e54ba5765cb534cf..446c0e2294ba03c7b9042d98416fc5a27f1513a7 100644 --- a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp +++ b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.cpp @@ -40,7 +40,7 @@ namespace armarx defs->topic(debugObserver); - defs->optional(p.memoryName, "memory.Name", "Name of this memory (server)."); + workingMemory().name() = "Example"; p.core._defaultSegmentsStr = simox::alg::join(p.core.defaultCoreSegments, ", "); defs->optional(p.core._defaultSegmentsStr, "core.DefaultSegments", @@ -60,10 +60,8 @@ namespace armarx void ExampleMemory::onInitComponent() { - this->setMemoryName(p.memoryName); - // Usually, the memory server will specify a number of core segments with a specific aron type. - workingMemory.addCoreSegment("ExampleData", armem::example::ExampleData::toAronType()); + workingMemory().addCoreSegment("ExampleData", armem::example::ExampleData::toAronType()); // For illustration purposes, we add more segments (without types). bool trim = true; @@ -72,13 +70,13 @@ namespace armarx for (const std::string& name : p.core.defaultCoreSegments) { - workingMemory.addCoreSegment(name); + workingMemory().addCoreSegment(name); } } void ExampleMemory::onConnectComponent() { - RemoteGui__createTab(); + createRemoteGuiTab(); RemoteGui_startRunningTask(); } @@ -97,7 +95,7 @@ namespace armarx armem::data::AddSegmentsResult ExampleMemory::addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) { // This function is overloaded to trigger the remote gui rebuild. - armem::data::AddSegmentsResult result = ComponentPluginUser::addSegments(input, p.core.addOnUsage); + armem::data::AddSegmentsResult result = ReadWritePluginUser::addSegments(input, p.core.addOnUsage); tab.rebuild = true; return result; } @@ -106,7 +104,7 @@ namespace armarx armem::data::CommitResult ExampleMemory::commit(const armem::data::Commit& commit, const Ice::Current&) { // This function is overloaded to trigger the remote gui rebuild. - armem::data::CommitResult result = ComponentPluginUser::commit(commit); + armem::data::CommitResult result = ReadWritePluginUser::commit(commit); tab.rebuild = true; return result; } @@ -120,13 +118,13 @@ namespace armarx // REMOTE GUI - void ExampleMemory::RemoteGui__createTab() + void ExampleMemory::createRemoteGuiTab() { using namespace armarx::RemoteGui::Client; { // Core segments are locked by MemoryRemoteGui. - tab.memoryGroup = armem::server::MemoryRemoteGui().makeGroupBox(workingMemory); + tab.memoryGroup = armem::server::MemoryRemoteGui().makeGroupBox(workingMemory()); } VBoxLayout root = {tab.memoryGroup, VSpacer()}; @@ -138,7 +136,7 @@ namespace armarx { if (tab.rebuild.exchange(false)) { - RemoteGui__createTab(); + createRemoteGuiTab(); } } diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.h b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.h index 37d20608bea3c0c14cda73332693768899d6ce90..a7dda191aa96c14567899a4f9064edf5f69d2bcf 100644 --- a/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.h +++ b/source/RobotAPI/components/armem/server/ExampleMemory/ExampleMemory.h @@ -27,9 +27,8 @@ #include <ArmarXCore/interface/observers/ObserverInterface.h> #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> -#include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> namespace armarx @@ -47,9 +46,8 @@ namespace armarx */ class ExampleMemory : virtual public armarx::Component - , virtual public armem::server::ComponentPluginUser + , virtual public armem::server::ReadWritePluginUser , virtual public LightweightRemoteGuiComponentPluginUser - // , virtual public armarx::ArVizComponentPluginUser { public: @@ -65,7 +63,7 @@ namespace armarx // LightweightRemoteGuiComponentPluginUser interface public: - void RemoteGui__createTab(); + void createRemoteGuiTab(); void RemoteGui_update() override; @@ -85,8 +83,6 @@ namespace armarx struct Properties { - std::string memoryName = "Example"; - struct CoreSegments { std::vector<std::string> defaultCoreSegments = { "ExampleModality", "ExampleConcept" }; diff --git a/source/RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.xml b/source/RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.xml index edd34d36d5d05c01ce7e40b2f1cbdc9213c2c2f6..6347fef0adf48e84d1104985481b05732db7b11f 100644 --- a/source/RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.xml +++ b/source/RobotAPI/components/armem/server/ExampleMemory/aron/ExampleData.xml @@ -1,97 +1,114 @@ -<!--Some fancy comment --> +<!-- +An example data containing different native ARON types. +--> <?xml version="1.0" encoding="UTF-8" ?> <AronTypeDefinition> - <CodeIncludes> - <Include include="<Eigen/Core>" /> - <Include include="<Image/ByteImage.h>" /> - <Include include="<RobotAPI/libraries/armem/aron/MemoryID.aron.generated.h>" /> - </CodeIncludes> + <CodeIncludes> + <!-- These should not be necessary in the future: --> + <Include include="<Eigen/Core>" /> <!-- For Position, Pose and Matrix. --> + <Include include="<Eigen/Geometry>" /> <!-- For Orientation. --> + <Include include="<opencv2/core/core.hpp>" /> <!-- For Image. --> + <!--Include include="<RobotAPI/libraries/armem/aron/MemoryID.aron.generated.h>" /--> + </CodeIncludes> - <AronIncludes> - <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" /> - </AronIncludes> + <AronIncludes> + <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" autoinclude="true" /> + </AronIncludes> - <GenerateTypes> - <Object name='armarx::armem::example::ExampleData'> + <GenerateTypes> + <Object name='armarx::armem::example::ExampleData'> - <ObjectChild key='the_int'> - <Int /> - </ObjectChild> - <ObjectChild key='the_long'> - <Long /> - </ObjectChild> - <ObjectChild key='the_float'> - <Float /> - </ObjectChild> - <ObjectChild key='the_double'> - <Double /> - </ObjectChild> - <ObjectChild key='the_string'> + <ObjectChild key='the_int'> + <Int /> + </ObjectChild> + <ObjectChild key='the_long'> + <Long /> + </ObjectChild> + <ObjectChild key='the_float'> + <Float /> + </ObjectChild> + <ObjectChild key='the_double'> + <Double /> + </ObjectChild> + <ObjectChild key='the_string'> <String /> - </ObjectChild> - <ObjectChild key='the_bool'> - <Bool /> - </ObjectChild> + </ObjectChild> + <ObjectChild key='the_bool'> + <Bool /> + </ObjectChild> - <ObjectChild key='the_eigen_position'> - <EigenMatrix rows="3" cols="1" type="float" /> - </ObjectChild> - <ObjectChild key='the_eigen_pose'> - <EigenMatrix rows="4" cols="4" type="float" /> - </ObjectChild> - <ObjectChild key='the_ivt_image'> - <IVTCByteImage type="GrayScale" shared_ptr="true"/> - </ObjectChild> + <ObjectChild key='the_position'> + <Position /> + </ObjectChild> + <ObjectChild key='the_orientation'> + <Orientation /> + </ObjectChild> + <ObjectChild key='the_pose'> + <Pose /> + </ObjectChild> - <ObjectChild key='the_float_list'> - <List> - <Float /> - </List> - </ObjectChild> - <ObjectChild key='the_int_list'> - <List> - <Int /> - </List> - </ObjectChild> - <ObjectChild key='the_string_list'> - <List> - <String /> - </List> - </ObjectChild> + <ObjectChild key='the_3x1_vector'> + <EigenMatrix rows="3" cols="1" type="float" /> + </ObjectChild> + <ObjectChild key='the_4x4_matrix'> + <EigenMatrix rows="4" cols="4" type="float" /> + </ObjectChild> + <ObjectChild key='the_rgb24_image'> + <Image pixelType="rgb24"/> + </ObjectChild> + <ObjectChild key='the_depth32_image'> + <Image pixelType="depth32"/> + </ObjectChild> - <ObjectChild key='the_object_list'> - <List> - <Object name='ListClass'> - <ObjectChild key='element_int'> - <Int /> - </ObjectChild> - <ObjectChild key='element_float'> - <Float /> - </ObjectChild> - <ObjectChild key='element_string'> + <ObjectChild key='the_float_list'> + <List> + <Float /> + </List> + </ObjectChild> + <ObjectChild key='the_int_list'> + <List> + <Int /> + </List> + </ObjectChild> + <ObjectChild key='the_string_list'> + <List> <String /> - </ObjectChild> - </Object> - </List> - </ObjectChild> + </List> + </ObjectChild> + + <ObjectChild key='the_object_list'> + <List> + <Object name='InnerClass'> + <ObjectChild key='element_int'> + <Int /> + </ObjectChild> + <ObjectChild key='element_float'> + <Float /> + </ObjectChild> + <ObjectChild key='element_string'> + <String /> + </ObjectChild> + </Object> + </List> + </ObjectChild> - <ObjectChild key='the_float_dict'> - <Dict> - <Float /> - </Dict> - </ObjectChild> - <ObjectChild key='the_int_dict'> - <Dict> - <Int /> - </Dict> - </ObjectChild> + <ObjectChild key='the_float_dict'> + <Dict> + <Float /> + </Dict> + </ObjectChild> + <ObjectChild key='the_int_dict'> + <Dict> + <Int /> + </Dict> + </ObjectChild> - <ObjectChild key="memoryLink"> - <armarx::armem::arondto::MemoryID /> - </ObjectChild> + <ObjectChild key="memoryLink"> + <armarx::armem::arondto::MemoryID /> + </ObjectChild> - </Object> - </GenerateTypes> + </Object> + </GenerateTypes> </AronTypeDefinition> diff --git a/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.cpp b/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.cpp index 3b17f4fc879dfb49fd1b816f8e4b0e450e3f926f..756ffdcabdaa97085db88e4d186058d24790dfb7 100644 --- a/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.cpp +++ b/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.cpp @@ -29,6 +29,7 @@ #include <RobotAPI/libraries/armem/core/error.h> #include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h> + namespace armarx { GeneralPurposeMemory::GeneralPurposeMemory() @@ -38,6 +39,9 @@ namespace armarx armarx::PropertyDefinitionsPtr GeneralPurposeMemory::createPropertyDefinitions() { armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier()); + + workingMemory().name() = "GeneralPurpose"; + return defs; } @@ -50,7 +54,6 @@ namespace armarx void GeneralPurposeMemory::onInitComponent() { - workingMemory.name() = memoryName; } @@ -70,17 +73,11 @@ namespace armarx - // WRITING armem::data::AddSegmentsResult GeneralPurposeMemory::addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) { - armem::data::AddSegmentsResult result = ComponentPluginUser::addSegments(input, addCoreSegmentOnUsage); + // Allowing adding core segments. + armem::data::AddSegmentsResult result = ReadWritePluginUser::addSegments(input, addCoreSegmentOnUsage); return result; } - - armem::data::CommitResult GeneralPurposeMemory::commit(const armem::data::Commit& commit, const Ice::Current&) - { - armem::data::CommitResult result = ComponentPluginUser::commit(commit); - return result; - } } diff --git a/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.h b/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.h index c91e38d07df966ec61c06653bc7d828358275797..0ee828883381d8e8272b2d49a1fdfa81179e69ed 100644 --- a/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.h +++ b/source/RobotAPI/components/armem/server/GeneralPurposeMemory/GeneralPurposeMemory.h @@ -25,11 +25,10 @@ #include <ArmarXCore/core/Component.h> -#include <ArmarXCore/interface/observers/ObserverInterface.h> #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> namespace armarx @@ -46,20 +45,28 @@ namespace armarx * Detailed description of class GeneralPurposeMemory. */ class GeneralPurposeMemory : - virtual public armarx::Component, - virtual public armem::server::ComponentPluginUser + virtual public armarx::Component + , virtual public armem::server::ReadWritePluginUser { public: + GeneralPurposeMemory(); /// @see armarx::ManagedIceObject::getDefaultName() std::string getDefaultName() const override; + public: - armem::data::AddSegmentsResult addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) override; - armem::data::CommitResult commit(const armem::data::Commit& commit, const Ice::Current&) override; + + armem::data::AddSegmentsResult + addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) override; + protected: + + /// @see PropertyUser::createPropertyDefinitions() + armarx::PropertyDefinitionsPtr createPropertyDefinitions() override; + /// @see armarx::ManagedIceObject::onInitComponent() void onInitComponent() override; @@ -72,12 +79,9 @@ namespace armarx /// @see armarx::ManagedIceObject::onExitComponent() void onExitComponent() override; - /// @see PropertyUser::createPropertyDefinitions() - armarx::PropertyDefinitionsPtr createPropertyDefinitions() override; - private: - std::string memoryName = "GeneralPurposeMemory"; + bool addCoreSegmentOnUsage = true; }; diff --git a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp index 15253dffb3eb8c7e49c114d2a7659627cd797071..3555cb2d4ed20b423c43dcc127f35f9983001ad3 100644 --- a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp +++ b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.cpp @@ -22,12 +22,6 @@ #include "MotionMemory.h" -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - -#include <SimoxUtility/algorithm/string.h> - -#include <RobotAPI/libraries/armem/core/error.h> - namespace armarx { @@ -35,16 +29,17 @@ namespace armarx { armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier()); + workingMemory().name() = "Motion"; + const std::string prefix = "mem."; - defs->optional(memoryName, prefix + "MemoryName", "Name of this memory (server)."); mdbMotions.defineProperties(defs, prefix + "mdbmotions."); return defs; } + MotionMemory::MotionMemory() : - mdbMotions(armem::server::ComponentPluginUser::iceMemory) + mdbMotions(iceAdapter()) { - } @@ -53,23 +48,26 @@ namespace armarx return "MotionMemory"; } + void MotionMemory::onInitComponent() { - this->setMemoryName(memoryName); - mdbMotions.onInit(); } + void MotionMemory::onConnectComponent() { mdbMotions.onConnect(); } + void MotionMemory::onDisconnectComponent() { } + void MotionMemory::onExitComponent() { } + } diff --git a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.h b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.h index 0218f010631a8f752985dce148c892bed145f5b3..b457d713a58a369b83f8f176d8bd241de95be37f 100644 --- a/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.h +++ b/source/RobotAPI/components/armem/server/MotionMemory/MotionMemory.h @@ -22,11 +22,12 @@ #pragma once +#include <RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h> + +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> #include <ArmarXCore/core/Component.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> -#include <RobotAPI/libraries/armem_motions/server/MotionDatabase/MDBMotions/Segment.h> namespace armarx { @@ -43,7 +44,7 @@ namespace armarx */ class MotionMemory : virtual public armarx::Component - , virtual public armem::server::ComponentPluginUser + , virtual public armem::server::ReadWritePluginUser { public: @@ -52,6 +53,7 @@ namespace armarx /// @see armarx::ManagedIceObject::getDefaultName() std::string getDefaultName() const override; + protected: armarx::PropertyDefinitionsPtr createPropertyDefinitions() override; @@ -63,7 +65,6 @@ namespace armarx private: - std::string memoryName = "Motion"; armem::server::motions::mdb::Segment mdbMotions; // TODO: mdt Segment diff --git a/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.cpp b/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.cpp index 40ceb2864360a7f9412091a39870c8a51846f015..c605df2efece207f0a0b11337dd96c61ca534470 100644 --- a/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.cpp +++ b/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.cpp @@ -33,7 +33,16 @@ namespace armarx::armem::server::obj { armarx::PropertyDefinitionsPtr defs(new ComponentPropertyDefinitions(getConfigIdentifier())); - // Offer + const std::string prefix = "mem."; + workingMemory().name() = defaultMemoryName; + + classSegment.defineProperties(defs, prefix + "cls."); + instance::SegmentAdapter::defineProperties(defs, prefix + "inst."); + + attachmentSegment.defineProperties(defs, prefix + "attachments."); + + + // Publish defs->topic(debugObserver); // Subscribe @@ -44,25 +53,14 @@ namespace armarx::armem::server::obj defs->defineOptionalProperty<std::string>("cmp.KinematicUnitObserverName", "KinematicUnitObserver", "Name of the kinematic unit observer."); - const std::string prefix = "mem."; - - workingMemory.name() = defaultMemoryName; - defs->optional(workingMemory.name(), prefix + "MemoryName", "Name of this memory server."); - - classSegment.defineProperties(defs, prefix + "cls."); - instance::SegmentAdapter::defineProperties(defs, prefix + "inst."); - - attachmentSegment.defineProperties(defs, prefix + "attachments."); - return defs; } ObjectMemory::ObjectMemory() : - server::ComponentPluginUser(), - instance::SegmentAdapter(server::ComponentPluginUser::iceMemory), - classSegment(server::ComponentPluginUser::iceMemory), - attachmentSegment(server::ComponentPluginUser::iceMemory) + instance::SegmentAdapter(iceAdapter()), + classSegment(iceAdapter()), + attachmentSegment(iceAdapter()) { } @@ -80,8 +78,6 @@ namespace armarx::armem::server::obj void ObjectMemory::onInitComponent() { - workingMemory.name() = defaultMemoryName; - const auto initSegmentWithCatch = [&](const std::string & segmentName, const auto&& fn) { try diff --git a/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.h b/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.h index 44332653fc095f826aac0ccf5e5e79c124769dfd..91217c90cc0dcb5be302663a0b472cac3327f3c0 100644 --- a/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.h +++ b/source/RobotAPI/components/armem/server/ObjectMemory/ObjectMemory.h @@ -26,7 +26,7 @@ #include <RobotAPI/libraries/armem_objects/server/instance/SegmentAdapter.h> #include <RobotAPI/libraries/armem_objects/server/attachments/Segment.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> #include <RobotAPI/libraries/RobotAPIComponentPlugins/RobotStateComponentPlugin.h> @@ -59,7 +59,7 @@ namespace armarx::armem::server::obj virtual public Component , virtual public armarx::armem::server::ObjectMemoryInterface - , virtual public armarx::armem::server::ComponentPluginUser + , virtual public armarx::armem::server::ReadWritePluginUser , virtual public armarx::armem::server::obj::instance::SegmentAdapter , virtual public armarx::RobotStateComponentPluginUser @@ -120,6 +120,6 @@ namespace armarx::armem::server::obj }; -} // namespace armarx::armem::server::obj +} #undef ICE_CURRENT_ARG diff --git a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp index 582cf20586d119f1ef232cb32c706bbd1eef1e4e..27aaa07ddf1c0f0dc819a9a74366036cdadfe11c 100644 --- a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp +++ b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.cpp @@ -22,33 +22,26 @@ #include "RobotStateMemory.h" -// STD -#include <memory> +#include <RobotAPI/libraries/armem_robot_state/server/proprioception/aron_conversions.h> -// Simox -#include <SimoxUtility/algorithm/string.h> +#include <RobotAPI/libraries/armem_robot_state/server/common/Visu.h> +#include <RobotAPI/libraries/RobotAPIComponentPlugins/RobotUnitComponentPlugin.h> -// ArmarX #include <ArmarXCore/core/exceptions/local/ExpressionException.h> -#include <ArmarXCore/core/logging/Logging.h> -#include <ArmarXCore/core/system/ArmarXDataPath.h> #include <ArmarXCore/libraries/ArmarXCoreComponentPlugins/DebugObserverComponentPlugin.h> +#include <ArmarXCore/core/logging/Logging.h> -#include <RobotAPI/libraries/armem/core/error.h> -#include <RobotAPI/libraries/armem_robot_state/server/common/Visu.h> -#include <RobotAPI/libraries/RobotAPIComponentPlugins/RobotUnitComponentPlugin.h> - -#include <RobotAPI/libraries/armem_robot_state/server/proprioception/aron_conversions.h> +#include <SimoxUtility/algorithm/string.h> namespace armarx::armem::server::robot_state { - RobotStateMemory::RobotStateMemory() - : descriptionSegment(server::ComponentPluginUser::iceMemory), - proprioceptionSegment(server::ComponentPluginUser::iceMemory), - localizationSegment(server::ComponentPluginUser::iceMemory), - commonVisu(descriptionSegment, proprioceptionSegment, localizationSegment) + RobotStateMemory::RobotStateMemory() : + descriptionSegment(iceAdapter()), + proprioceptionSegment(iceAdapter()), + localizationSegment(iceAdapter()), + commonVisu(descriptionSegment, proprioceptionSegment, localizationSegment) { addPlugin(debugObserver); ARMARX_CHECK_NOT_NULL(debugObserver); @@ -59,19 +52,17 @@ namespace armarx::armem::server::robot_state robotUnit.writer.setTag(getName()); } - RobotStateMemory::~RobotStateMemory() = default; + + RobotStateMemory::~RobotStateMemory() + { + } armarx::PropertyDefinitionsPtr RobotStateMemory::createPropertyDefinitions() { armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier()); - const std::string prefix = "mem."; - - this->setMemoryName("RobotState"); - defs->optional(workingMemory.name(), prefix + "MemoryName", "Name of this memory server."); - - const std::string robotUnitPrefix{sensorValuePrefix}; + const std::string robotUnitPrefix = sensorValuePrefix; defs->optional(robotUnit.reader.properties.sensorPrefix, robotUnitPrefix + "SensorValuePrefix", "Prefix of all sensor values."); @@ -83,6 +74,11 @@ namespace armarx::armem::server::robot_state "Minimum is 1, max is " + std::to_string(ROBOT_UNIT_MAXIMUM_FREQUENCY) + ".") .setMin(1).setMax(ROBOT_UNIT_MAXIMUM_FREQUENCY); + + const std::string prefix = "mem."; + + workingMemory().name() = "RobotState"; + descriptionSegment.defineProperties(defs, prefix + "desc."); proprioceptionSegment.defineProperties(defs, prefix + "prop."); localizationSegment.defineProperties(defs, prefix + "loc."); @@ -105,7 +101,7 @@ namespace armarx::armem::server::robot_state localizationSegment.onInit(); commonVisu.init(); - robotUnit.pollFrequency = std::clamp(robotUnit.pollFrequency, 1, ROBOT_UNIT_MAXIMUM_FREQUENCY); + robotUnit.pollFrequency = std::clamp(robotUnit.pollFrequency, 0.f, ROBOT_UNIT_MAXIMUM_FREQUENCY); robotUnit.writer.properties.memoryBatchSize = std::max(static_cast<unsigned int>(1), robotUnit.writer.properties.memoryBatchSize); std::vector<std::string> includePaths; @@ -158,7 +154,7 @@ namespace armarx::armem::server::robot_state { robotUnit.writer.run( robotUnit.pollFrequency, robotUnit.dataQueue, robotUnit.dataMutex, - iceMemory, localizationSegment + iceAdapter(), localizationSegment ); }, "Robot State Writer"); @@ -185,7 +181,6 @@ namespace armarx::armem::server::robot_state void RobotStateMemory::startRobotUnitStream() { - std::lock_guard lock{startStopMutex}; if (robotUnit.reader.task->isRunning() || robotUnit.writer.task->isRunning()) { if (robotUnit.reader.task->isRunning() && robotUnit.writer.task->isRunning()) @@ -213,7 +208,6 @@ namespace armarx::armem::server::robot_state void RobotStateMemory::stopRobotUnitStream() { - std::lock_guard lock{startStopMutex}; robotUnit.reader.task->stop(); robotUnit.writer.task->stop(); } diff --git a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.h b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.h index 2cd2be9e3a5838f16b1a385e829416429b7869cd..74dd4a3fa12fea08186ec14d1b93fdf6872ac7dd 100644 --- a/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.h +++ b/source/RobotAPI/components/armem/server/RobotStateMemory/RobotStateMemory.h @@ -22,17 +22,14 @@ #pragma once -// STD -#include <atomic> -#include <optional> +#include <mutex> #include <queue> -// ArmarX #include <ArmarXCore/core/Component.h> #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> #include <RobotAPI/libraries/RobotUnitDataStreamingReceiver/RobotUnitDataStreamingReceiver.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> #include <RobotAPI/libraries/armem_robot_state/server/description/Segment.h> #include <RobotAPI/libraries/armem_robot_state/server/localization/Segment.h> @@ -64,7 +61,7 @@ namespace armarx::armem::server::robot_state */ class RobotStateMemory : virtual public armarx::Component, - virtual public armem::server::ComponentPluginUser, + virtual public armem::server::ReadWritePluginUser, virtual public armarx::ArVizComponentPluginUser { public: @@ -96,7 +93,6 @@ namespace armarx::armem::server::robot_state armarx::plugins::DebugObserverComponentPlugin* debugObserver = nullptr; - mutable std::recursive_mutex startStopMutex; // Core segments // - description @@ -115,7 +111,7 @@ namespace armarx::armem::server::robot_state struct RobotUnit { - int pollFrequency = 50; + float pollFrequency = 50; armarx::plugins::RobotUnitComponentPlugin* plugin = nullptr; proprioception::RobotUnitReader reader; @@ -123,13 +119,13 @@ namespace armarx::armem::server::robot_state // queue std::queue<proprioception::RobotUnitData> dataQueue; - mutable std::mutex dataMutex; + std::mutex dataMutex; }; RobotUnit robotUnit; // params - static constexpr int ROBOT_UNIT_MAXIMUM_FREQUENCY = 100; + static constexpr float ROBOT_UNIT_MAXIMUM_FREQUENCY = 100; static constexpr const char* sensorValuePrefix = "RobotUnit."; diff --git a/source/RobotAPI/components/armem/server/SkillsMemory/CMakeLists.txt b/source/RobotAPI/components/armem/server/SkillsMemory/CMakeLists.txt index b9d1d4fd44ed2bf58f8eccd64faa9ab0eafc83ef..eee41fad2917ac3689f98d103f1a927a0715d205 100644 --- a/source/RobotAPI/components/armem/server/SkillsMemory/CMakeLists.txt +++ b/source/RobotAPI/components/armem/server/SkillsMemory/CMakeLists.txt @@ -2,10 +2,9 @@ armarx_component_set_name("SkillsMemory") set(COMPONENT_LIBS - ArmarXCore ArmarXCoreInterfaces ArmarXCoreObservers # for DebugObserverInterface - ArmarXGuiComponentPlugins - RobotAPICore RobotAPIInterfaces armem armem_skills - # RobotAPIComponentPlugins # for ArViz and other plugins + ArmarXCore ArmarXCoreInterfaces + RobotAPICore RobotAPIInterfaces + armem armem_skills ${IVT_LIBRARIES} ) diff --git a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp index 6c86b6afa76fe043b4dea16affb609f7db049caf..f7741f3d3991896c43f2d3172c515bfec35af0ef 100644 --- a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp +++ b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.cpp @@ -31,31 +31,29 @@ #include <RobotAPI/libraries/armem/core/error.h> #include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h> -#include <RobotAPI/libraries/armem/server/MemoryRemoteGui.h> - #include <RobotAPI/libraries/armem_skills/aron_conversions.h> namespace armarx { + SkillsMemory::SkillsMemory() - = default; + { + } + armarx::PropertyDefinitionsPtr SkillsMemory::createPropertyDefinitions() { armarx::PropertyDefinitionsPtr defs = new ComponentPropertyDefinitions(getConfigIdentifier()); - // Publish - defs->topic(debugObserver); + workingMemory().name() = "Skills"; + // Statechart Logging defs->optional(p.statechartCoreSegmentName, "StatechartCoreSegmentName", "Name of the core segment for statecharts."); defs->optional(p.statechartTransitionsProviderSegmentName, "TransitionsProviderSegmentName", "Name of the provider segment for statechart transitions."); defs->optional(p.statechartTransitionsTopicName, "tpc.sub.ProfilerListener", "Name of the ProfilerListenerInterface topics to subscribe."); - const std::string prefix = "mem."; - defs->optional(p.memoryName, prefix + "MemoryName", "Name of this memory server."); - return defs; } @@ -68,12 +66,10 @@ namespace armarx void SkillsMemory::onInitComponent() { - workingMemory.name() = p.memoryName; - - { - armarx::armem::server::wm::CoreSegment& c = workingMemory.addCoreSegment(p.statechartCoreSegmentName, armarx::armem::arondto::Statechart::Transition::toAronType()); - c.addProviderSegment("Transitions", armarx::armem::arondto::Statechart::Transition::toAronType()); - } + armarx::armem::server::wm::CoreSegment& c = workingMemory().addCoreSegment( + p.statechartCoreSegmentName, + armarx::armem::arondto::Statechart::Transition::toAronType()); + c.addProviderSegment("Transitions", armarx::armem::arondto::Statechart::Transition::toAronType()); } @@ -101,14 +97,7 @@ namespace armarx // WRITING armem::data::AddSegmentsResult SkillsMemory::addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) { - armem::data::AddSegmentsResult result = ComponentPluginUser::addSegments({input}, p.core.addOnUsage); - return result; - } - - - armem::data::CommitResult SkillsMemory::commit(const armem::data::Commit& commit, const Ice::Current&) - { - armem::data::CommitResult result = ComponentPluginUser::commit(commit); + armem::data::AddSegmentsResult result = ReadWritePluginUser::addSegments({input}, p.core.addOnUsage); return result; } @@ -132,6 +121,7 @@ namespace armarx [this](const std::vector<StatechartListener::Transition>& transitions, armarx::StatechartListener & source) { + (void) source; // Unused. this->reportTransitions(transitions); }); @@ -150,6 +140,7 @@ namespace armarx return listener; } + void SkillsMemory::reportTransitions(const std::vector<StatechartListener::Transition>& transitions) { @@ -160,7 +151,7 @@ namespace armarx armem::EntityUpdate update; update.entityID = armem::MemoryID() - .withMemoryName(p.memoryName) + .withMemoryName(workingMemory().name()) .withCoreSegmentName(p.statechartCoreSegmentName) .withProviderSegmentName(p.statechartTransitionsProviderSegmentName) .withEntityName(entityName); @@ -172,7 +163,7 @@ namespace armarx try { - workingMemory.update(update); + workingMemory().update(update); } catch (const armem::error::ArMemError& e) { @@ -181,6 +172,7 @@ namespace armarx } } + std::string SkillsMemory::getStatechartName(std::string stateName) { const std::string delimiter = "->"; diff --git a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.h b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.h index ebf0b02c48f90e31b5f93321343b12a66a2723c9..6eb9114c94a94c851ba6e7437bb74338353b90db 100644 --- a/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.h +++ b/source/RobotAPI/components/armem/server/SkillsMemory/SkillsMemory.h @@ -24,12 +24,9 @@ #include <ArmarXCore/core/Component.h> -#include <ArmarXCore/interface/observers/ObserverInterface.h> -#include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> -#include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> #include <RobotAPI/libraries/armem_skills/aron/Statechart.aron.generated.h> #include <RobotAPI/libraries/armem_skills/StatechartListener.h> @@ -49,22 +46,24 @@ namespace armarx */ class SkillsMemory : virtual public armarx::Component, - virtual public armem::server::ComponentPluginUser - // , virtual public armarx::ArVizComponentPluginUser + virtual public armem::server::ReadWritePluginUser { public: + SkillsMemory(); /// @see armarx::ManagedIceObject::getDefaultName() std::string getDefaultName() const override; + // WritingInterface interface public: + armem::data::AddSegmentsResult addSegments(const armem::data::AddSegmentsInput& input, const Ice::Current&) override; - armem::data::CommitResult commit(const armem::data::Commit& commit, const Ice::Current&) override; protected: + /// @see armarx::ManagedIceObject::onInitComponent() void onInitComponent() override; @@ -82,12 +81,9 @@ namespace armarx private: - DebugObserverInterfacePrx debugObserver; struct Properties { - std::string memoryName = "Skills"; - // Statechart transition logging std::string statechartCoreSegmentName = "Statechart"; std::string statechartTransitionsProviderSegmentName = "Transitions"; @@ -110,5 +106,6 @@ namespace armarx // Gets the statechart name from a state name (takes first two levels of the hierarchy) static std::string getStatechartName(std::string stateName); + }; } diff --git a/source/RobotAPI/components/armem/server/SubjectMemory/SubjectMemory.h b/source/RobotAPI/components/armem/server/SubjectMemory/SubjectMemory.h index 2382459ee2fa0ad5bd52300c25cbad0562ed5921..8018df78fc2b92de1353089521c8649aded3b377 100644 --- a/source/RobotAPI/components/armem/server/SubjectMemory/SubjectMemory.h +++ b/source/RobotAPI/components/armem/server/SubjectMemory/SubjectMemory.h @@ -24,7 +24,7 @@ #include <ArmarXCore/core/Component.h> -#include <RobotAPI/libraries/armem/server/ComponentPlugin.h> +#include <RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h> #include <RobotAPI/libraries/armem_subjects/server/MotionDatabase/Segment.h> @@ -43,7 +43,7 @@ namespace armarx */ class SubjectMemory : virtual public armarx::Component - , virtual public armem::server::ComponentPluginUser + , virtual public armem::server::ReadWritePluginUser { public: diff --git a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp index 61ff24e37fc43900f46ba2e74680b30787239759..d2d10aee0d547b4341c343d368e9c518de86b501 100644 --- a/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp +++ b/source/RobotAPI/components/units/RobotUnit/NJointControllers/NJointTaskSpaceImpedanceController.cpp @@ -96,7 +96,7 @@ void NJointTaskSpaceImpedanceController::rtRun(const IceUtil::Time& /*sensorValu velocitySensors, positionSensors ); - ARMARX_CHECK_EQUAL(targets.size(), jointDesiredTorques.size()); + ARMARX_CHECK_EQUAL(targets.size(), static_cast<size_t>(jointDesiredTorques.size())); for (size_t i = 0; i < targets.size(); ++i) { diff --git a/source/RobotAPI/interface/armem/mns/MemoryNameSystemInterface.ice b/source/RobotAPI/interface/armem/mns/MemoryNameSystemInterface.ice index 85a862f4cd815168d6163d2d085426d71b298068..95b6a9fa6b03d8f7d4644d2538ecfd64d5258229 100644 --- a/source/RobotAPI/interface/armem/mns/MemoryNameSystemInterface.ice +++ b/source/RobotAPI/interface/armem/mns/MemoryNameSystemInterface.ice @@ -1,87 +1,116 @@ #pragma once -#include <RobotAPI/interface/armem/server/MemoryInterface.ice> +#include <RobotAPI/interface/armem/server/ReadingMemoryInterface.ice> +#include <RobotAPI/interface/armem/server/WritingMemoryInterface.ice> module armarx { module armem { - module data + module mns { - struct RegisterMemoryInput - { - string name; - server::MemoryInterface* proxy; - - bool existOk = true; - }; - struct RegisterMemoryResult - { - bool success; - string errorMessage; - }; - - struct RemoveMemoryInput - { - string name; - bool notExistOk = true; - }; - struct RemoveMemoryResult - { - bool success; - string errorMessage; - }; - - dictionary<string, server::MemoryInterface*> MemoryInterfaces; - struct GetAllRegisteredMemoriesResult - { - bool success; - string errorMessage; - - MemoryInterfaces proxies; - }; - - struct ResolveMemoryNameInput - { - string name; - }; - struct ResolveMemoryNameResult - { - bool success; - string errorMessage; - - server::MemoryInterface* proxy; - }; - - struct WaitForMemoryInput - { - /// The memory name. - string name; - /// Negative for no timeout. - long timeoutMilliSeconds = -1; - }; - struct WaitForMemoryResult + module dto { - bool success; - string errorMessage; - - server::MemoryInterface* proxy; + /** + * A memory server can implement the reading and/or writing + * memory interface. They should be handled individually. + */ + struct MemoryServerInterfaces + { + server::ReadingMemoryInterface* reading; + server::WritingMemoryInterface* writing; + }; + dictionary<string, MemoryServerInterfaces> MemoryServerInterfacesMap; + + + /** + * @brief Register a memory server. + */ + struct RegisterServerInput + { + string name; + MemoryServerInterfaces server; + + bool existOk = true; + }; + struct RegisterServerResult + { + bool success; + string errorMessage; + }; + + + /** + * @brief Remove a memory server. + */ + struct RemoveServerInput + { + string name; + bool notExistOk = true; + }; + struct RemoveServerResult + { + bool success; + string errorMessage; + }; + + /** + * @brief Resolve a memory name. + */ + struct ResolveServerInput + { + string name; + }; + struct ResolveServerResult + { + bool success; + string errorMessage; + + MemoryServerInterfaces server; + }; + + + /** + * @brief Get all registered entries. + */ + struct GetAllRegisteredServersResult + { + bool success; + string errorMessage; + + MemoryServerInterfacesMap servers; + }; + + + /** + * @brief Wait until a server is registered. + */ + struct WaitForServerInput + { + string name; + }; + struct WaitForServerResult + { + bool success; + string errorMessage; + + MemoryServerInterfaces server; + }; }; - }; - module mns - { interface MemoryNameSystemInterface { - data::RegisterMemoryResult registerMemory(data::RegisterMemoryInput input); - data::RemoveMemoryResult removeMemory(data::RemoveMemoryInput input); + dto::RegisterServerResult registerServer(dto::RegisterServerInput input); + dto::RemoveServerResult removeServer(dto::RemoveServerInput input); + + dto::GetAllRegisteredServersResult getAllRegisteredServers(); - data::GetAllRegisteredMemoriesResult getAllRegisteredMemories(); + dto::ResolveServerResult resolveServer(dto::ResolveServerInput input); - data::ResolveMemoryNameResult resolveMemoryName(data::ResolveMemoryNameInput input); - data::WaitForMemoryResult waitForMemory(data::WaitForMemoryInput input); + ["amd"] // Asynchronous Method Dispatch + dto::WaitForServerResult waitForServer(dto::WaitForServerInput input); }; } diff --git a/source/RobotAPI/interface/aron/Aron.ice b/source/RobotAPI/interface/aron/Aron.ice index dc88e0484490476691ee98e3c3bf338964c02e6d..9c3baf7929680117c4b933960fa00342600ee06b 100644 --- a/source/RobotAPI/interface/aron/Aron.ice +++ b/source/RobotAPI/interface/aron/Aron.ice @@ -72,11 +72,25 @@ module armarx class AronDict extends AronType { AronType acceptedType; } // Complex Types (serialize to ndarray) + + class AronNDArray extends AronType { AronIntSequence dimensions; int elementSize; string typeName; } + // NdArray should look like this: + // class AronNDArray extends AronType { int ndim; string type; } + // type can be: "uint8", "int8", "uint16", "int16", "uint32", "int32", "float32", "float64" + + + class AronEigenMatrix extends AronType { int rows; int cols; string typeName; } class AronEigenQuaternion extends AronType { string typeName; } + + // pixelType can be: "rgb24", "depth32" + class AronImage extends AronType { string pixelType; } + + // to be removed: class AronIVTCByteImage extends AronType { } - class AronOpenCVMat extends AronType { } + class AronOpenCVMat extends AronType { AronIntSequence shape; string typeName; } + class AronPCLPointCloud extends AronType { string typeName; } class AronPosition extends AronType { } class AronOrientation extends AronType { } @@ -114,6 +128,10 @@ module armarx // Further, note the difference between the type's dimensions (e.g. 128x128) and the data's dimensions (128x128x3 for RGB) class AronNDArray extends AronData { AronIntSequence dimensions; string type; AronByteSequence data; }; + // NDArray should look like this: (type is be as above and implies the bit-width of an element) + // class AronNDArray extends AronData { AronIntSequence shape; string type; AronByteSequence data; }; + + // Primitive Data #define RUN_ARON_MACRO(upperType, lowerType, capsType) \ class Aron##upperType extends AronData { lowerType value; }; diff --git a/source/RobotAPI/libraries/ArmarXObjects/test/ArmarXObjectsTest.cpp b/source/RobotAPI/libraries/ArmarXObjects/test/ArmarXObjectsTest.cpp index 85ca31bec07bbe8af4108a64a24805da44dd19d5..433fc67ec7890cbb7fede64d2edda22533e46eb8 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/test/ArmarXObjectsTest.cpp +++ b/source/RobotAPI/libraries/ArmarXObjects/test/ArmarXObjectsTest.cpp @@ -97,8 +97,10 @@ BOOST_AUTO_TEST_CASE(test_find) BOOST_TEST_CONTEXT("Object: " << object.id() << " at " << objectDir) { BOOST_CHECK(fs::is_directory(objectDir)); +#if 0 BOOST_CHECK(fs::is_regular_file(simoxXML) || fs::is_regular_file(object.articulatedSimoxXML().absolutePath)); +#endif } } } diff --git a/source/RobotAPI/libraries/armem/CMakeLists.txt b/source/RobotAPI/libraries/armem/CMakeLists.txt index 1fdf140a9507cd439b45226e4886ec89fe0ccfcf..c524ecd93da7721ee95cc111beb518cafd848de5 100644 --- a/source/RobotAPI/libraries/armem/CMakeLists.txt +++ b/source/RobotAPI/libraries/armem/CMakeLists.txt @@ -60,13 +60,15 @@ set(LIB_FILES core/error/ArMemError.cpp core/error/mns.cpp - client/ComponentPlugin.cpp + client/MemoryNameSystem.cpp - client/MemoryNameSystemComponentPlugin.cpp client/Reader.cpp - client/ReaderComponentPlugin.cpp client/Writer.cpp - client/WriterComponentPlugin.cpp + + client/plugins/ListeningPluginUser.cpp + client/plugins/ListeningPlugin.cpp + client/plugins/PluginUser.cpp + client/plugins/Plugin.cpp client/util/MemoryListener.cpp client/util/SimpleReaderBase.cpp @@ -76,8 +78,8 @@ set(LIB_FILES client/query/Builder.cpp client/query/selectors.cpp + server/MemoryToIceAdapter.cpp - server/ComponentPlugin.cpp server/MemoryRemoteGui.cpp server/RemoteGuiAronDataVisitor.cpp @@ -90,6 +92,10 @@ set(LIB_FILES server/wm/ice_conversions.cpp server/wm/detail/MaxHistorySize.cpp + server/plugins/Plugin.cpp + server/plugins/ReadOnlyPluginUser.cpp + server/plugins/ReadWritePluginUser.cpp + server/segment/Segment.cpp server/segment/SpecializedSegment.cpp @@ -102,8 +108,11 @@ set(LIB_FILES server/query_proc/ltm.cpp server/query_proc/wm.cpp + mns/MemoryNameSystem.cpp - mns/ComponentPlugin.cpp + mns/Registry.cpp + mns/plugins/Plugin.cpp + mns/plugins/PluginUser.cpp util/util.cpp ) @@ -153,15 +162,18 @@ set(LIB_HEADERS core/wm/visitor/Visitor.h core/wm/visitor/FunctionalVisitor.h + client.h client/forward_declarations.h - client/ComponentPlugin.h client/MemoryNameSystem.h - client/MemoryNameSystemComponentPlugin.h client/Reader.h - client/ReaderComponentPlugin.h client/Writer.h - client/WriterComponentPlugin.h + + client/plugins.h + client/plugins/ListeningPluginUser.h + client/plugins/ListeningPlugin.h + client/plugins/PluginUser.h + client/plugins/Plugin.h client/query.h client/Query.h @@ -175,10 +187,10 @@ set(LIB_HEADERS client/util/SimpleReaderBase.h client/util/SimpleWriterBase.h + server.h server/forward_declarations.h - server/ComponentPlugin.h server/MemoryToIceAdapter.h server/MemoryRemoteGui.h server/RemoteGuiAronDataVisitor.h @@ -192,6 +204,11 @@ set(LIB_HEADERS server/wm/ice_conversions.h server/wm/detail/MaxHistorySize.h + server/plugins.h + server/plugins/Plugin.h + server/plugins/ReadOnlyPluginUser.h + server/plugins/ReadWritePluginUser.h + server/segment/Segment.h server/segment/SpecializedSegment.h @@ -207,9 +224,12 @@ set(LIB_HEADERS server/query_proc/ltm.h server/query_proc/wm.h + mns.h mns/MemoryNameSystem.h - mns/ComponentPlugin.h + mns/Registry.h + mns/plugins/Plugin.h + mns/plugins/PluginUser.h util/util.h ) diff --git a/source/RobotAPI/libraries/armem/client.h b/source/RobotAPI/libraries/armem/client.h index 834d62ab45d88d18e4277929c47acd55c5825263..fa61feb250a44f58dbc3c0d8b00a0c7ad67d8d31 100644 --- a/source/RobotAPI/libraries/armem/client.h +++ b/source/RobotAPI/libraries/armem/client.h @@ -1,15 +1,12 @@ #pragma once -#include "client/ComponentPlugin.h" #include "client/MemoryNameSystem.h" -#include "client/MemoryNameSystemComponentPlugin.h" +#include "client/plugins.h" #include "client/Query.h" #include "client/query/Builder.h" #include "client/query/query_fns.h" #include "client/Reader.h" -#include "client/ReaderComponentPlugin.h" #include "client/Writer.h" -#include "client/WriterComponentPlugin.h" namespace armarx::armem @@ -23,8 +20,4 @@ namespace armarx::armem using ClientQueryBuilder = client::query::Builder; namespace client_query_fns = client::query_fns; - using ClientComponentPluginUser = client::ComponentPluginUser; - using ClientReaderComponentPluginUser = client::ReaderComponentPluginUser; - using ClientWriterComponentPluginUser = client::WriterComponentPluginUser; - } diff --git a/source/RobotAPI/libraries/armem/client/ComponentPlugin.cpp b/source/RobotAPI/libraries/armem/client/ComponentPlugin.cpp deleted file mode 100644 index a88f374d6bddede5fd0b05eb28481d524f5f6b0a..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/ComponentPlugin.cpp +++ /dev/null @@ -1,41 +0,0 @@ -#include <RobotAPI/libraries/armem/client/ComponentPlugin.h> - - -// ArmarX -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - -// RobotAPI -#include <RobotAPI/libraries/armem/core/error.h> - - -armarx::armem::client::ComponentPluginUser::ComponentPluginUser() -{ - // pass -} - - -armarx::armem::client::ComponentPluginUser::~ComponentPluginUser() -{ - // pass -} - - -void -armarx::armem::client::ComponentPluginUser::setMemoryServer(server::MemoryInterfacePrx memory) -{ - setReadingMemoryServer(memory); - setWritingMemoryServer(memory); -} - - -armarx::armem::data::WaitForMemoryResult -armarx::armem::client::ComponentPluginUser::useMemoryServer(const std::string& memoryName) -{ - armem::data::WaitForMemoryResult result; - result.proxy = memoryNameSystem.useServer(MemoryID().withMemoryName(memoryName)); - if (result.proxy) - { - setMemoryServer(result.proxy); - } - return result; -} diff --git a/source/RobotAPI/libraries/armem/client/ComponentPlugin.h b/source/RobotAPI/libraries/armem/client/ComponentPlugin.h deleted file mode 100644 index ae3f26b26557c11046d84cde8a07483e4ba9ad49..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/ComponentPlugin.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - - -// ArmarX -#include <ArmarXCore/core/ComponentPlugin.h> - -// RobotAPI -#include <RobotAPI/interface/armem/server/MemoryInterface.h> -#include <RobotAPI/libraries/armem/client/ReaderComponentPlugin.h> -#include <RobotAPI/libraries/armem/client/WriterComponentPlugin.h> - - - -namespace armarx::armem::client -{ - - /** - * @brief Utility for connecting a Client via Ice to ArMem. - */ - class ComponentPluginUser : - virtual public ReaderComponentPluginUser, - virtual public WriterComponentPluginUser - { - - public: - - ComponentPluginUser(); - ~ComponentPluginUser() override; - - - /** - * @brief Resolve the given memory name, add it as dependency and update the readers and writers. - * @param The memory's name. - * @return The result of `waitForMemory()`. - * @see `armem::MemoryNameSystemComponentPluginUser::useMemory()` - */ - virtual armem::data::WaitForMemoryResult useMemoryServer(const std::string& memoryName) override; - using MemoryNameSystemComponentPluginUser::useMemoryServer; - - - protected: - - void setMemoryServer(server::MemoryInterfacePrx memory); - - }; - -} diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp index 79140344ee99a143e29bcc655d6e1ed23d77b041..121b2924802c1a8c7d6ab411fd1c88755ee56621 100644 --- a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp +++ b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.cpp @@ -9,6 +9,8 @@ #include <SimoxUtility/algorithm/string/string_tools.h> + + namespace armarx::armem::client { @@ -27,10 +29,10 @@ namespace armarx::armem::client { ARMARX_CHECK_NOT_NULL(mns); - data::GetAllRegisteredMemoriesResult result; + mns::dto::GetAllRegisteredServersResult result; try { - result = mns->getAllRegisteredMemories(); + result = mns->getAllRegisteredServers(); } catch (const Ice::NotRegisteredException& e) { @@ -39,24 +41,32 @@ namespace armarx::armem::client if (result.success) { - for (const auto& [name, proxy] : result.proxies) + for (const auto& [name, server] : result.servers) { - auto [it, inserted] = servers.try_emplace(name, proxy); - // inserted: OK - if (not inserted) + auto [it, inserted] = servers.try_emplace(name, server); + if (inserted) + { + // OK + } + else { // Compare ice identities, update if it changed. - if (it->second->ice_getIdentity() != proxy->ice_getIdentity()) + auto foo = [](auto & oldProxy, const auto & newProxy) { - // Replace old proxy by new one. - it->second = proxy; - } + if (oldProxy->ice_getIdentity() != newProxy->ice_getIdentity()) + { + // Replace old proxy by new one. + oldProxy = newProxy; + } + }; + foo(it->second.reading, server.reading); + foo(it->second.writing, server.writing); } } // Remove all entries which are not there anymore. for (auto it = servers.begin(); it != servers.end();) { - if (result.proxies.count(it->first) == 0) + if (result.servers.count(it->first) == 0) { it = servers.erase(it); } @@ -73,7 +83,8 @@ namespace armarx::armem::client } - server::MemoryInterfacePrx MemoryNameSystem::resolveServer(const MemoryID& memoryID) + mns::dto::MemoryServerInterfaces + MemoryNameSystem::resolveServer(const MemoryID& memoryID) { if (auto it = servers.find(memoryID.memoryName); it != servers.end()) { @@ -94,7 +105,7 @@ namespace armarx::armem::client } - server::MemoryInterfacePrx MemoryNameSystem::waitForServer(const MemoryID& memoryID, Time timeout) + mns::dto::MemoryServerInterfaces MemoryNameSystem::waitForServer(const MemoryID& memoryID) { if (auto it = servers.find(memoryID.memoryName); it != servers.end()) { @@ -102,15 +113,14 @@ namespace armarx::armem::client } else { - armem::data::WaitForMemoryInput input; + mns::dto::WaitForServerInput input; input.name = memoryID.memoryName; - input.timeoutMilliSeconds = timeout.toMilliSeconds(); ARMARX_CHECK_NOT_NULL(mns); - armem::data::WaitForMemoryResult result = mns->waitForMemory(input); + mns::dto::WaitForServerResult result = mns->waitForServer(input); if (result.success) { - return result.proxy; + return result.server; } else { @@ -119,7 +129,7 @@ namespace armarx::armem::client } } - server::MemoryInterfacePrx MemoryNameSystem::useServer(const MemoryID& memoryID) + mns::dto::MemoryServerInterfaces MemoryNameSystem::useServer(const MemoryID& memoryID) { ARMARX_CHECK_NOT_NULL(component) << "Owning component not set when using a memory server. \n" @@ -131,22 +141,22 @@ namespace armarx::armem::client } - server::MemoryInterfacePrx MemoryNameSystem::useServer(const MemoryID& memoryID, ManagedIceObject& component) + mns::dto::MemoryServerInterfaces MemoryNameSystem::useServer(const MemoryID& memoryID, ManagedIceObject& component) { - server::MemoryInterfacePrx server = waitForServer(memoryID); + mns::dto::MemoryServerInterfaces server = waitForServer(memoryID); // Add dependency. - component.usingProxy(server->ice_getIdentity().name); + component.usingProxy(server.reading->ice_getIdentity().name); return server; } - server::MemoryInterfacePrx MemoryNameSystem::useServer(const std::string& memoryName) + mns::dto::MemoryServerInterfaces MemoryNameSystem::useServer(const std::string& memoryName) { return useServer(MemoryID().withMemoryName(memoryName)); } - server::MemoryInterfacePrx MemoryNameSystem::useServer(const std::string& memoryName, ManagedIceObject& component) + mns::dto::MemoryServerInterfaces MemoryNameSystem::useServer(const std::string& memoryName, ManagedIceObject& component) { return useServer(MemoryID().withMemoryName(memoryName), component); } @@ -154,19 +164,19 @@ namespace armarx::armem::client Reader MemoryNameSystem::getReader(const MemoryID& memoryID) { - return Reader(resolveServer(memoryID)); + return Reader(resolveServer(memoryID).reading); } Reader MemoryNameSystem::useReader(const MemoryID& memoryID) { - return Reader(useServer(memoryID)); + return Reader(useServer(memoryID).reading); } Reader MemoryNameSystem::useReader(const MemoryID& memoryID, ManagedIceObject& component) { - return Reader(useServer(memoryID, component)); + return Reader(useServer(memoryID, component).reading); } @@ -182,56 +192,55 @@ namespace armarx::armem::client } + template <class ClientT> - std::map<std::string, ClientT> MemoryNameSystem::_getAllClients() const + std::map<std::string, ClientT> + MemoryNameSystem::_getAllClients(auto&& getProxyFn) const { std::map<std::string, ClientT> result; for (const auto& [name, server] : servers) { - result[name] = ClientT(server); + if (auto proxy = getProxyFn(server)) + { + result[name] = ClientT(proxy); + } } return result; } - template <class ClientT> - std::map<std::string, ClientT> MemoryNameSystem::_getAllClients(bool update) + + std::map<std::string, Reader> MemoryNameSystem::getAllReaders(bool update) { if (update) { this->update(); } - return const_cast<const MemoryNameSystem&>(*this)._getAllClients<ClientT>(); - } - - - std::map<std::string, Reader> MemoryNameSystem::getAllReaders(bool update) - { - return _getAllClients<Reader>(update); + return _getAllClients<Reader>(&mns::getReadingInterface); } std::map<std::string, Reader> MemoryNameSystem::getAllReaders() const { - return _getAllClients<Reader>(); + return _getAllClients<Reader>(&mns::getReadingInterface); } Writer MemoryNameSystem::getWriter(const MemoryID& memoryID) { - return Writer(resolveServer(memoryID)); + return Writer(resolveServer(memoryID).writing); } Writer MemoryNameSystem::useWriter(const MemoryID& memoryID) { - return Writer(useServer(memoryID)); + return Writer(useServer(memoryID).writing); } Writer MemoryNameSystem::useWriter(const MemoryID& memoryID, ManagedIceObject& component) { - return Writer(useServer(memoryID, component)); + return Writer(useServer(memoryID, component).writing); } @@ -249,13 +258,17 @@ namespace armarx::armem::client std::map<std::string, Writer> MemoryNameSystem::getAllWriters(bool update) { - return _getAllClients<Writer>(update); + if (update) + { + this->update(); + } + return _getAllClients<Writer>(&mns::getWritingInterface); } std::map<std::string, Writer> MemoryNameSystem::getAllWriters() const { - return _getAllClients<Writer>(); + return _getAllClients<Writer>(&mns::getWritingInterface); } @@ -341,15 +354,15 @@ namespace armarx::armem::client } - void MemoryNameSystem::registerServer(const MemoryID& memoryID, server::MemoryInterfacePrx proxy) + void MemoryNameSystem::registerServer(const MemoryID& memoryID, mns::dto::MemoryServerInterfaces server) { - data::RegisterMemoryInput input; + mns::dto::RegisterServerInput input; input.name = memoryID.memoryName; - input.proxy = proxy; - ARMARX_CHECK_NOT_NULL(input.proxy); + input.server = server; + ARMARX_CHECK(server.reading or server.writing) << VAROUT(server.reading) << " | " << VAROUT(server.writing); ARMARX_CHECK_NOT_NULL(mns); - data::RegisterMemoryResult result = mns->registerMemory(input); + mns::dto::RegisterServerResult result = mns->registerServer(input); if (!result.success) { throw error::ServerRegistrationOrRemovalFailed("register", memoryID, result.errorMessage); @@ -359,11 +372,11 @@ namespace armarx::armem::client void MemoryNameSystem::removeServer(const MemoryID& memoryID) { - data::RemoveMemoryInput input; + mns::dto::RemoveServerInput input; input.name = memoryID.memoryName; ARMARX_CHECK_NOT_NULL(mns); - data::RemoveMemoryResult result = mns->removeMemory(input); + mns::dto::RemoveServerResult result = mns->removeServer(input); if (!result.success) { throw error::ServerRegistrationOrRemovalFailed("remove", memoryID, result.errorMessage); diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.h b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.h index d981bab0383f0d04fdc221fbbd2cbd062d061c53..7779ca2d8b1a65b07ef446675685695dc243de58 100644 --- a/source/RobotAPI/libraries/armem/client/MemoryNameSystem.h +++ b/source/RobotAPI/libraries/armem/client/MemoryNameSystem.h @@ -30,6 +30,7 @@ #include <RobotAPI/libraries/armem/core/MemoryID.h> #include <RobotAPI/libraries/armem/client/util/MemoryListener.h> +#include <RobotAPI/libraries/armem/mns/Registry.h> namespace armarx @@ -97,41 +98,6 @@ namespace armarx::armem::client */ void update(); - /** - * @brief Resolve the given memory server for the given memory ID. - * - * @param memoryID The memory ID. - * @return The memory server proxy. - * - * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. - */ - server::MemoryInterfacePrx resolveServer(const MemoryID& memoryID); - - /** - * @brief Wait for the given memory server. - * - * @param memoryID The memory ID. - * @param timeout How long to wait at maximum. Negative values indicate infinite wait. - * @return The memory server proxy. - * - * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. - */ - server::MemoryInterfacePrx waitForServer(const MemoryID& memoryID, Time timeout = Time::milliSeconds(-1)); - - /** - * @brief Wait for the given memory server and add a dependency to the memory server. - * - * @param memoryID The memory ID. - * @param component The component that should depend on the memory server. - * @return The memory server proxy. - * - * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. - */ - server::MemoryInterfacePrx useServer(const MemoryID& memoryID); - server::MemoryInterfacePrx useServer(const MemoryID& memoryID, ManagedIceObject& component); - server::MemoryInterfacePrx useServer(const std::string& memoryName); - server::MemoryInterfacePrx useServer(const std::string& memoryName, ManagedIceObject& component); - // Reader/Writer construction @@ -225,7 +191,7 @@ namespace armarx::armem::client * * @throw `error::ServerRegistrationOrRemovalFailed` If the registration failed. */ - void registerServer(const MemoryID& memoryID, server::MemoryInterfacePrx server); + void registerServer(const MemoryID& memoryID, mns::dto::MemoryServerInterfaces server); /** * @brief Remove a memory server from the MNS. @@ -247,12 +213,47 @@ namespace armarx::armem::client } + private: + + /** + * @brief Resolve the given memory server for the given memory ID. + * + * @param memoryID The memory ID. + * @return The memory server proxy. + * + * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. + */ + mns::dto::MemoryServerInterfaces resolveServer(const MemoryID& memoryID); + + /** + * @brief Wait for the given memory server. + * + * @param memoryID The memory ID. + * @return The memory server proxy. + * + * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. + */ + mns::dto::MemoryServerInterfaces waitForServer(const MemoryID& memoryID); + + /** + * @brief Wait for the given memory server and add a dependency to the memory server. + * + * @param memoryID The memory ID. + * @param component The component that should depend on the memory server. + * @return The memory server proxy. + * + * @throw `error::CouldNotResolveMemoryServer` If the memory name could not be resolved. + */ + mns::dto::MemoryServerInterfaces useServer(const MemoryID& memoryID); + mns::dto::MemoryServerInterfaces useServer(const MemoryID& memoryID, ManagedIceObject& component); + mns::dto::MemoryServerInterfaces useServer(const std::string& memoryName); + mns::dto::MemoryServerInterfaces useServer(const std::string& memoryName, ManagedIceObject& component); + + private: template <class ClientT> - std::map<std::string, ClientT> _getAllClients(bool update); - template <class ClientT> - std::map<std::string, ClientT> _getAllClients() const; + std::map<std::string, ClientT> _getAllClients(auto&& proxyFn) const; /// The MNS proxy. @@ -262,7 +263,7 @@ namespace armarx::armem::client ManagedIceObject* component = nullptr; /// The registered memory servers. - std::map<std::string, server::MemoryInterfacePrx> servers; + std::map<std::string, mns::dto::MemoryServerInterfaces> servers; }; diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.cpp b/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.cpp deleted file mode 100644 index 60fae2cf9b37e450fcfbaee806af8115f496c678..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.cpp +++ /dev/null @@ -1,154 +0,0 @@ -#include "MemoryNameSystemComponentPlugin.h" - -#include <ArmarXCore/core/Component.h> -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - -#include <RobotAPI/libraries/armem/core/error.h> -#include <RobotAPI/libraries/armem/core/ice_conversions.h> - - - -namespace armarx::armem::client::plugins -{ - - MemoryNameSystemComponentPlugin::~MemoryNameSystemComponentPlugin() - {} - - - void MemoryNameSystemComponentPlugin::postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties) - { - if (!properties->hasDefinition(makePropertyName(PROPERTY_MNS_NAME_NAME))) - { - properties->defineOptionalProperty<std::string>( - makePropertyName(PROPERTY_MNS_NAME_NAME), - parent<MemoryNameSystemComponentPluginUser>().memoryNameSystemName, - "Name of the Memory Name System (MNS) component."); - } - if (!properties->hasDefinition(makePropertyName(PROPERTY_MNS_ENABLED_NAME))) - { - properties->defineOptionalProperty<bool>( - makePropertyName(PROPERTY_MNS_ENABLED_NAME), - parent<MemoryNameSystemComponentPluginUser>().memoryNameSystemEnabled, - "Whether to use (and depend on) the Memory Name System (MNS)." - "\nSet to false to use this memory as a stand-alone."); - } - - // Subscribe topics by single servers, use this as a prefix. - properties->topic<MemoryListenerInterface>("MemoryUpdates"); - } - - void MemoryNameSystemComponentPlugin::preOnInitComponent() - { - if (isMemoryNameSystemEnabled()) - { - parent().usingProxy(getMemoryNameSystemName()); - } - } - - void MemoryNameSystemComponentPlugin::preOnConnectComponent() - { - if (isMemoryNameSystemEnabled()) - { - ARMARX_DEBUG << "Creating MemoryNameSystem client with owning component '" << parent().getName() << "'."; - parent<MemoryNameSystemComponentPluginUser>().memoryNameSystem = - MemoryNameSystem(getMemoryNameSystem(), &parent()); - } - } - - bool MemoryNameSystemComponentPlugin::isMemoryNameSystemEnabled() - { - return parentDerives<Component>() ? - parent<Component>().getProperty<bool>(makePropertyName(PROPERTY_MNS_ENABLED_NAME)) : - parent<MemoryNameSystemComponentPluginUser>().memoryNameSystemEnabled; - } - - std::string MemoryNameSystemComponentPlugin::getMemoryNameSystemName() - { - return parentDerives<Component>() ? - parent<Component>().getProperty<std::string>(makePropertyName(PROPERTY_MNS_NAME_NAME)) : - std::string{parent<MemoryNameSystemComponentPluginUser>().memoryNameSystemName}; - } - - mns::MemoryNameSystemInterfacePrx MemoryNameSystemComponentPlugin::getMemoryNameSystem() - { - return isMemoryNameSystemEnabled() && parentDerives<Component>() - ? parent<Component>().getProxy<mns::MemoryNameSystemInterfacePrx>(getMemoryNameSystemName()) - : nullptr; - } - -} - -namespace armarx::armem::client -{ - - MemoryNameSystemComponentPluginUser::MemoryNameSystemComponentPluginUser() - { - addPlugin(plugin); - } - - MemoryNameSystemComponentPluginUser::~MemoryNameSystemComponentPluginUser() - { - } - - void MemoryNameSystemComponentPluginUser::memoryUpdated( - const std::vector<data::MemoryID>& updatedSnapshotIDs, const Ice::Current&) - { - memoryNameSystem.updated(updatedSnapshotIDs); - } - - armem::data::WaitForMemoryResult MemoryNameSystemComponentPluginUser::useMemoryServer(const MemoryID& id) - { - armem::data::WaitForMemoryResult result; - try - { - // Add dependency. - result.proxy = memoryNameSystem.useServer(id); - result.success = true; - } - catch (const armem::error::CouldNotResolveMemoryServer& e) - { - result.success = false; - result.errorMessage = e.what(); - } - return result; - } - - armem::data::WaitForMemoryResult MemoryNameSystemComponentPluginUser::useMemoryServer(const std::string& memoryName) - { - return useMemoryServer(MemoryID().withMemoryName(memoryName)); - } - - armem::data::WaitForMemoryResult MemoryNameSystemComponentPluginUser::waitForMemoryServer(const std::string& memoryName) - { - armem::data::WaitForMemoryResult result; - try - { - result.proxy = memoryNameSystem.waitForServer(MemoryID().withMemoryName(memoryName)); - result.success = true; - } - catch (const armem::error::CouldNotResolveMemoryServer& e) - { - result.success = false; - result.errorMessage = e.what(); - } - return result; - } - - armem::data::ResolveMemoryNameResult MemoryNameSystemComponentPluginUser::resolveMemoryServer(const std::string& memoryName) - { - armem::data::ResolveMemoryNameResult result; - try - { - result.proxy = memoryNameSystem.resolveServer(MemoryID().withMemoryName(memoryName)); - result.success = true; - } - catch (const armem::error::CouldNotResolveMemoryServer& e) - { - result.success = false; - result.errorMessage = e.what(); - } - return result; - } - -} - diff --git a/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h b/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h deleted file mode 100644 index a6a2434a68a033d3e540729c08e83c90babda847..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h +++ /dev/null @@ -1,101 +0,0 @@ -#pragma once - -#include <ArmarXCore/core/ComponentPlugin.h> - -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> -#include <RobotAPI/interface/armem/client/MemoryListenerInterface.h> -#include <RobotAPI/libraries/armem/core/MemoryID.h> -#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> - - -namespace armarx::armem::mns -{ - class MemoryNameSystemComponentPluginUser; -} - - -namespace armarx::armem::client::plugins -{ - /** - * @brief A base plugin offering optional access and dependency - * to the Memory Name System (MNS). - */ - class MemoryNameSystemComponentPlugin : public ComponentPlugin - { - public: - - using ComponentPlugin::ComponentPlugin; - virtual ~MemoryNameSystemComponentPlugin() override; - - void postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) override; - - void preOnInitComponent() override; - void preOnConnectComponent() override; - - /** - * @brief Indicate whether the Memory Name System (MNS) is enabled. - */ - bool isMemoryNameSystemEnabled(); - /** - * @brief Get the name of the MNS component. - */ - std::string getMemoryNameSystemName(); - - /** - * @brief Get the MNS proxy. - * @return The MNS proxy when MNS is enabled, nullptr when MNS is disabled. - */ - mns::MemoryNameSystemInterfacePrx getMemoryNameSystem(); - - public: - static constexpr const char* PROPERTY_MNS_ENABLED_NAME = "mns.MemoryNameSystemEnabled"; - static constexpr const char* PROPERTY_MNS_NAME_NAME = "mns.MemoryNameSystemName"; - }; - -} - - -#include <ArmarXCore/core/ManagedIceObject.h> - -namespace armarx::armem::client -{ - - class MemoryNameSystemComponentPluginUser : - virtual public ManagedIceObject, - virtual public MemoryListenerInterface - { - protected: - - MemoryNameSystemComponentPluginUser(); - virtual ~MemoryNameSystemComponentPluginUser() override; - - - virtual void memoryUpdated(const std::vector<data::MemoryID>& updatedSnapshotIDs, const Ice::Current& current) override; - - - [[deprecated("Use memoryNameSystem member instead of function inherited by MemoryNameSystemComponentPluginUser.")]] - armem::data::WaitForMemoryResult waitForMemoryServer(const std::string& memoryName); - [[deprecated("Use memoryNameSystem member instead of function inherited by MemoryNameSystemComponentPluginUser.")]] - armem::data::ResolveMemoryNameResult resolveMemoryServer(const std::string& memoryName); - - [[deprecated("Use memoryNameSystem member instead of function inherited by MemoryNameSystemComponentPluginUser.")]] - armem::data::WaitForMemoryResult useMemoryServer(const MemoryID& id); - [[deprecated("Use memoryNameSystem member instead of function inherited by MemoryNameSystemComponentPluginUser.")]] - virtual armem::data::WaitForMemoryResult useMemoryServer(const std::string& memoryName); - - - public: - - /// Only valid when enabled. - MemoryNameSystem memoryNameSystem; - - bool memoryNameSystemEnabled = true; - std::string memoryNameSystemName = "MemoryNameSystem"; - - - private: - - plugins::MemoryNameSystemComponentPlugin* plugin = nullptr; - - }; -} diff --git a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp deleted file mode 100644 index c2e4d5ed6df5c3e12c0d3e2ada0b93c91e232133..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.cpp +++ /dev/null @@ -1,48 +0,0 @@ -#include <RobotAPI/libraries/armem/client/ReaderComponentPlugin.h> - - -// ArmarX -#include <ArmarXCore/core/Component.h> -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - -// RobotAPI -#include <RobotAPI/libraries/armem/core/error.h> - - -namespace armarx::armem::client::plugins -{ - ReaderComponentPlugin::ReaderComponentPlugin(ManagedIceObject& parent, std::string pre) : - ComponentPlugin(parent, pre) - { - addPlugin(mnsPlugin, pre); - addPluginDependency(mnsPlugin); - } - - - ReaderComponentPlugin::~ReaderComponentPlugin() - { - } -} - - - -namespace armarx::armem::client -{ - ReaderComponentPluginUser::ReaderComponentPluginUser() - { - addPlugin(plugin); - } - - - ReaderComponentPluginUser::~ReaderComponentPluginUser() - { - } - - - void - ReaderComponentPluginUser::setReadingMemoryServer(server::ReadingMemoryInterfacePrx memory) - { - memoryReader.setReadingMemory(memory); - } - -} diff --git a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h b/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h deleted file mode 100644 index 059c5f93d5e8d872ecdc9bff86593db2c3de1163..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/ReaderComponentPlugin.h +++ /dev/null @@ -1,67 +0,0 @@ -#pragma once - - -// STD/STL -#include <vector> - -// ArmarX -#include <ArmarXCore/core/ComponentPlugin.h> - -// RobotAPI -#include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> -#include <RobotAPI/interface/armem/server/ReadingMemoryInterface.h> - -#include <RobotAPI/libraries/armem/client/Reader.h> -#include <RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h> - - -namespace armarx::armem::client::plugins -{ - - class ReaderComponentPlugin : public ComponentPlugin - { - - public: - - ReaderComponentPlugin(ManagedIceObject& parent, std::string pre); - ~ReaderComponentPlugin() override; - - - private: - - plugins::MemoryNameSystemComponentPlugin* mnsPlugin = nullptr; - - }; - -} - - -namespace armarx::armem::client -{ - - class ReaderComponentPluginUser : - virtual public ManagedIceObject, - virtual public MemoryNameSystemComponentPluginUser - { - - public: - - ReaderComponentPluginUser(); - ~ReaderComponentPluginUser() override; - - - protected: - - void setReadingMemoryServer(server::ReadingMemoryInterfacePrx memory); - - Reader memoryReader; - - - private: - - plugins::ReaderComponentPlugin* plugin = nullptr; - - }; - -} diff --git a/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.cpp b/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.cpp deleted file mode 100644 index d4b95ca3565e8552322e7e7cdfac131335ca06f3..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.cpp +++ /dev/null @@ -1,59 +0,0 @@ -#include <RobotAPI/libraries/armem/client/WriterComponentPlugin.h> - - -// ArmarX -#include <ArmarXCore/core/Component.h> -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - -// RobotAPI -#include <RobotAPI/libraries/armem/core/error.h> - - -namespace armarx::armem::client::plugins -{ - WriterComponentPlugin::WriterComponentPlugin(ManagedIceObject& parent, std::string pre) : - ComponentPlugin(parent, pre) - { - addPlugin(mnsPlugin, pre); - addPluginDependency(mnsPlugin); - } - - WriterComponentPlugin::~WriterComponentPlugin() - { - } -} - - -namespace armarx::armem::client -{ - WriterComponentPluginUser::WriterComponentPluginUser() - { - addPlugin(plugin); - } - - - WriterComponentPluginUser::~WriterComponentPluginUser() - { - // pass - } - - - void - WriterComponentPluginUser::setWritingMemoryServer(server::WritingMemoryInterfacePrx memory) - { - memoryWriter.setWritingMemory(memory); - } - - - armem::data::WaitForMemoryResult WriterComponentPluginUser::useMemoryServer(const std::string& memoryName) - { - armem::data::WaitForMemoryResult result; - result.proxy = memoryNameSystem.useServer(MemoryID().withMemoryName(memoryName)); - if (result.proxy) - { - setWritingMemoryServer(result.proxy); - } - return result; - } -} - diff --git a/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.h b/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.h deleted file mode 100644 index 3ae9a66bfab912237934d4bea6580a2e32a2c7fb..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/client/WriterComponentPlugin.h +++ /dev/null @@ -1,64 +0,0 @@ -#pragma once - - -// ArmarX -#include <ArmarXCore/core/ComponentPlugin.h> - -// RobotAPI -#include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h> -#include <RobotAPI/interface/armem/server/WritingMemoryInterface.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> - -#include <RobotAPI/libraries/armem/client/Writer.h> -#include <RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h> - - -namespace armarx::armem::client::plugins -{ - - class WriterComponentPlugin : public ComponentPlugin - { - - public: - - WriterComponentPlugin(ManagedIceObject& parent, std::string pre); - ~WriterComponentPlugin() override; - - private: - - plugins::MemoryNameSystemComponentPlugin* mnsPlugin = nullptr; - - }; -} - - -namespace armarx::armem::client -{ - class WriterComponentPluginUser : - virtual public ManagedIceObject, - virtual public MemoryNameSystemComponentPluginUser - { - - public: - - WriterComponentPluginUser(); - ~WriterComponentPluginUser() override; - - virtual armem::data::WaitForMemoryResult useMemoryServer(const std::string& memoryName) override; - using MemoryNameSystemComponentPluginUser::useMemoryServer; - - - protected: - - void setWritingMemoryServer(server::WritingMemoryInterfacePrx memory); - - Writer memoryWriter; - - - private: - - plugins::WriterComponentPlugin* plugin = nullptr; - - }; - -} diff --git a/source/RobotAPI/libraries/armem/client/forward_declarations.h b/source/RobotAPI/libraries/armem/client/forward_declarations.h index 205f56634456d4179d1baac494837d1ecdfe7069..ab6a8fb90cabb42d6838bcc2f57561aeafe01a30 100644 --- a/source/RobotAPI/libraries/armem/client/forward_declarations.h +++ b/source/RobotAPI/libraries/armem/client/forward_declarations.h @@ -8,9 +8,9 @@ namespace armarx::armem::client::query { class Builder; } + namespace armarx::armem::client { - class ComponentPluginUser; class MemoryNameSystem; class Reader; @@ -19,6 +19,20 @@ namespace armarx::armem::client using QueryBuilder = query::Builder; struct QueryInput; struct QueryResult; +} +namespace armarx::armem::client::plugins +{ + class Plugin; + class PluginUser; + class ListeningPluginUser; } +namespace armarx::armem +{ + using ClientPlugin = client::plugins::Plugin; + using ClientPluginUser = client::plugins::PluginUser; + using ListeningClientPluginUser = client::plugins::ListeningPluginUser; +} + + diff --git a/source/RobotAPI/libraries/armem/client/plugins.h b/source/RobotAPI/libraries/armem/client/plugins.h new file mode 100644 index 0000000000000000000000000000000000000000..b91ccec3895f6a817c800278b3b3c0318d038750 --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins.h @@ -0,0 +1,13 @@ +#pragma once + +#include <RobotAPI/libraries/armem/client/forward_declarations.h> + +#include <RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h> +#include <RobotAPI/libraries/armem/client/plugins/Plugin.h> +#include <RobotAPI/libraries/armem/client/plugins/PluginUser.h> + + +namespace armarx::armem::client +{ + using ComponentPluginUser = plugins::ListeningPluginUser; +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.cpp b/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.cpp new file mode 100644 index 0000000000000000000000000000000000000000..463c6443e11ddd0ec92d6c5bb4b1001e4e97dfed --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.cpp @@ -0,0 +1,21 @@ +#include "ListeningPlugin.h" + +#include <RobotAPI/interface/armem/client/MemoryListenerInterface.h> + +#include <ArmarXCore/core/application/properties/PropertyDefinitionContainer.h> + + +namespace armarx::armem::client::plugins +{ + + ListeningPlugin::~ListeningPlugin() + {} + + + void ListeningPlugin::postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties) + { + // Subscribe topics by single servers, use this as a prefix. + properties->topic<MemoryListenerInterface>("MemoryUpdates"); + } + +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.h b/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.h new file mode 100644 index 0000000000000000000000000000000000000000..80aac20c61d49ffc67963da3b14be0c984ab5a3a --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/ListeningPlugin.h @@ -0,0 +1,29 @@ +#pragma once + +#include <ArmarXCore/core/ComponentPlugin.h> + + +namespace armarx::armem::client::plugins +{ + + /** + * @brief Subscribes the memory updates topic. + * + * When using this plugin, the component needs to implement the + * `MemoryListenerInterface`. + * + * @see MemoryListenerInterface + */ + class ListeningPlugin : + public armarx::ComponentPlugin + { + public: + + using ComponentPlugin::ComponentPlugin; + virtual ~ListeningPlugin() override; + + virtual void postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties) override; + + }; + +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.cpp b/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.cpp new file mode 100644 index 0000000000000000000000000000000000000000..3a40a9ffe27b1116fe5a78f5d1a3088652818b38 --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.cpp @@ -0,0 +1,29 @@ +#include "ListeningPluginUser.h" + +#include "ListeningPlugin.h" + +#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> + + +namespace armarx::armem::client::plugins +{ + + ListeningPluginUser::ListeningPluginUser() + { + addPlugin(listeningPlugin); + } + + + ListeningPluginUser::~ListeningPluginUser() + { + } + + + void ListeningPluginUser::memoryUpdated( + const std::vector<data::MemoryID>& updatedSnapshotIDs, const Ice::Current&) + { + memoryNameSystem().updated(updatedSnapshotIDs); + } + +} + diff --git a/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h b/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h new file mode 100644 index 0000000000000000000000000000000000000000..7314b32c048ddfff685ad2095d440cf0f515194c --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h @@ -0,0 +1,51 @@ +#pragma once + +#include "PluginUser.h" + +#include <RobotAPI/interface/armem/client/MemoryListenerInterface.h> + +#include <vector> + + +namespace armarx::armem::client::plugins +{ + class ListeningPlugin; + + + /** + * @brief A memory name system client which listens to the memory updates + * topic (`MemoryListenerInterface`). + * + * Derive from this plugin user class to receive memory update events. + */ + class ListeningPluginUser : + virtual public PluginUser, + virtual public MemoryListenerInterface + { + protected: + + ListeningPluginUser(); + virtual ~ListeningPluginUser() override; + + + // MemoryListenerInterface + virtual void + memoryUpdated(const std::vector<data::MemoryID>& updatedSnapshotIDs, + const Ice::Current&) override; + + + private: + + ListeningPlugin* listeningPlugin = nullptr; + + }; + +} +namespace armarx::armem::client +{ + using ListeningPluginUser = plugins::ListeningPluginUser; +} +namespace armarx::armem +{ + using ListeningClientPluginUser = client::ListeningPluginUser; +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/Plugin.cpp b/source/RobotAPI/libraries/armem/client/plugins/Plugin.cpp new file mode 100644 index 0000000000000000000000000000000000000000..74cf798f6f65d31ee1e4bb2a2ba239c264d9f88b --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/Plugin.cpp @@ -0,0 +1,100 @@ +#include "Plugin.h" + +#include <RobotAPI/libraries/armem/core/error.h> +#include <RobotAPI/libraries/armem/core/ice_conversions.h> + +#include <ArmarXCore/core/Component.h> +#include <ArmarXCore/core/exceptions/local/ExpressionException.h> +#include <ArmarXCore/core/logging/Logging.h> + + +namespace armarx::armem::client::plugins +{ + + Plugin::Plugin( + ManagedIceObject& parent, std::string pre) : + ComponentPlugin(parent, pre) + { + } + + + Plugin::~Plugin() + {} + + + void Plugin::postCreatePropertyDefinitions(armarx::PropertyDefinitionsPtr& properties) + { + if (not properties->hasDefinition(makePropertyName(PROPERTY_MNS_NAME_NAME))) + { + properties->defineOptionalProperty<std::string>( + makePropertyName(PROPERTY_MNS_NAME_NAME), + memoryNameSystemName, + "Name of the Memory Name System (MNS) component."); + } + if (not properties->hasDefinition(makePropertyName(PROPERTY_MNS_ENABLED_NAME))) + { + properties->defineOptionalProperty<bool>( + makePropertyName(PROPERTY_MNS_ENABLED_NAME), + memoryNameSystemEnabled, + "Whether to use (and depend on) the Memory Name System (MNS)." + "\nSet to false to use this memory as a stand-alone."); + } + } + + + void Plugin::preOnInitComponent() + { + if (isMemoryNameSystemEnabled()) + { + parent().usingProxy(getMemoryNameSystemName()); + } + } + + + void Plugin::preOnConnectComponent() + { + if (isMemoryNameSystemEnabled()) + { + ARMARX_DEBUG << "Creating MemoryNameSystem client with owning component '" << parent().getName() << "'."; + memoryNameSystem = MemoryNameSystem(getMemoryNameSystemProxy(), &parent()); + } + } + + + bool + Plugin::isMemoryNameSystemEnabled() + { + return memoryNameSystemEnabled; + } + + + std::string + Plugin::getMemoryNameSystemName() + { + return memoryNameSystemName; + } + + + mns::MemoryNameSystemInterfacePrx + Plugin::getMemoryNameSystemProxy() + { + return isMemoryNameSystemEnabled() and parentDerives<ManagedIceObject>() + ? parent<ManagedIceObject>().getProxy<mns::MemoryNameSystemInterfacePrx>(getMemoryNameSystemName()) + : nullptr; + } + + + MemoryNameSystem& + Plugin::getMemoryNameSystemClient() + { + return memoryNameSystem; + } + + + const MemoryNameSystem& + Plugin::getMemoryNameSystemClient() const + { + return memoryNameSystem; + } + +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/Plugin.h b/source/RobotAPI/libraries/armem/client/plugins/Plugin.h new file mode 100644 index 0000000000000000000000000000000000000000..eff9134fda523d7b91b6cda2fdd4845dd78238cb --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/Plugin.h @@ -0,0 +1,79 @@ +#pragma once + +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> +#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> + +#include <ArmarXCore/core/ComponentPlugin.h> + +#include <string> + + +namespace armarx::armem::client::plugins +{ + + /** + * @brief A component plugin offering client-side access to to the + * working memory system by providing a Memory Name System (MNS) client. + * + * @see MemoryNameSystem + */ + class Plugin : + public armarx::ComponentPlugin + { + public: + + Plugin(ManagedIceObject& parent, std::string pre); + virtual ~Plugin() override; + + + void postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) override; + + void preOnInitComponent() override; + void preOnConnectComponent() override; + + + public: + + /** + * @brief Get the MNS client. + * + * Only valid when enabled. + */ + MemoryNameSystem& getMemoryNameSystemClient(); + const MemoryNameSystem& getMemoryNameSystemClient() const; + + + /** + * @brief Indicate whether the Memory Name System (MNS) is enabled. + */ + bool isMemoryNameSystemEnabled(); + + /** + * @brief Get the name of the MNS component. + */ + std::string getMemoryNameSystemName(); + + /** + * @brief Get the MNS proxy. + * @return The MNS proxy when MNS is enabled, nullptr when MNS is disabled. + */ + mns::MemoryNameSystemInterfacePrx getMemoryNameSystemProxy(); + + + protected: + + /// The MNS client. + MemoryNameSystem memoryNameSystem; + + bool memoryNameSystemEnabled = true; + std::string memoryNameSystemName = "MemoryNameSystem"; + + + protected: + + static constexpr const char* PROPERTY_MNS_ENABLED_NAME = "mns.MemoryNameSystemEnabled"; + static constexpr const char* PROPERTY_MNS_NAME_NAME = "mns.MemoryNameSystemName"; + + }; + +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/PluginUser.cpp b/source/RobotAPI/libraries/armem/client/plugins/PluginUser.cpp new file mode 100644 index 0000000000000000000000000000000000000000..c4129c63d9c51b011bbeb42f412a5372f244a532 --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/PluginUser.cpp @@ -0,0 +1,33 @@ +#include "PluginUser.h" +#include "Plugin.h" + +#include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> + + + +namespace armarx::armem::client::plugins +{ + + PluginUser::PluginUser() + { + addPlugin(plugin); + } + + + PluginUser::~PluginUser() + { + } + + + MemoryNameSystem& PluginUser::memoryNameSystem() + { + return plugin->getMemoryNameSystemClient(); + } + + + const MemoryNameSystem& PluginUser::memoryNameSystem() const + { + return plugin->getMemoryNameSystemClient(); + } + +} diff --git a/source/RobotAPI/libraries/armem/client/plugins/PluginUser.h b/source/RobotAPI/libraries/armem/client/plugins/PluginUser.h new file mode 100644 index 0000000000000000000000000000000000000000..0638084dd61bc6563a6a99797a0e7eef96415204 --- /dev/null +++ b/source/RobotAPI/libraries/armem/client/plugins/PluginUser.h @@ -0,0 +1,58 @@ +#pragma once + +#include <RobotAPI/libraries/armem/client/forward_declarations.h> + +#include <ArmarXCore/core/ManagedIceObject.h> + + +// Use this one include in your .cpp: +// #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> + + +namespace armarx::armem::client::plugins +{ + class Plugin; + + + /** + * @brief Adds the Memory Name System client component plugin. + * + * This plugin class does not implement the `MemoryListenerInterface`. + * Therefore, it will not receive and process memory udpate events via the + * memory updates topic. If you want to receive these updates, use the + * `ListeningMemoryNameSystemPluginUser`. + * + * + * @see MemoryNameSystemPlugin + * @see ListeningMemoryNameSystemPluginUser + */ + class PluginUser : + virtual public armarx::ManagedIceObject + { + protected: + + PluginUser(); + virtual ~PluginUser() override; + + + public: + + MemoryNameSystem& memoryNameSystem(); + const MemoryNameSystem& memoryNameSystem() const; + + + private: + + plugins::Plugin* plugin = nullptr; + + }; + +} +namespace armarx::armem::client +{ + using PluginUser = plugins::PluginUser; +} +namespace armarx::armem +{ + using ClientPluginUser = client::PluginUser; +} diff --git a/source/RobotAPI/libraries/armem/mns/ComponentPlugin.cpp b/source/RobotAPI/libraries/armem/mns/ComponentPlugin.cpp deleted file mode 100644 index 79e58300a6968dfda3f60d89ff0511f9ec72f267..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/mns/ComponentPlugin.cpp +++ /dev/null @@ -1,63 +0,0 @@ -#include "ComponentPlugin.h" - -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> -#include <ArmarXCore/core/time/CycleUtil.h> - -#include "../error.h" - - -namespace armarx::armem::mns::plugins -{ - -} - - -namespace armarx::armem::mns -{ - - ComponentPluginUser::ComponentPluginUser() - { - addPlugin(plugin); - } - - - armem::data::RegisterMemoryResult ComponentPluginUser::registerMemory(const armem::data::RegisterMemoryInput& input, const Ice::Current&) - { - std::scoped_lock lock(mnsMutex); - armem::data::RegisterMemoryResult result = mns.registerMemory(input); - return result; - } - - - armem::data::RemoveMemoryResult ComponentPluginUser::removeMemory(const armem::data::RemoveMemoryInput& input, const Ice::Current&) - { - std::scoped_lock lock(mnsMutex); - armem::data::RemoveMemoryResult result = mns.removeMemory(input); - return result; - } - - - armem::data::GetAllRegisteredMemoriesResult - ComponentPluginUser::getAllRegisteredMemories(const Ice::Current&) - { - std::scoped_lock lock(mnsMutex); - armem::data::GetAllRegisteredMemoriesResult result = mns.getAllRegisteredMemories(); - return result; - } - - - armem::data::ResolveMemoryNameResult ComponentPluginUser::resolveMemoryName(const armem::data::ResolveMemoryNameInput& input, const Ice::Current&) - { - std::scoped_lock lock(mnsMutex); - armem::data::ResolveMemoryNameResult result = mns.resolveMemoryName(input); - return result; - } - - - armem::data::WaitForMemoryResult ComponentPluginUser::waitForMemory(const armem::data::WaitForMemoryInput& input, const Ice::Current&) - { - // No lock - this call blocks internally. - return mns.waitForMemory(input); - } - -} diff --git a/source/RobotAPI/libraries/armem/mns/ComponentPlugin.h b/source/RobotAPI/libraries/armem/mns/ComponentPlugin.h deleted file mode 100644 index 1347c197e6d4f560b5773abfed30b92e8f8a7604..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/mns/ComponentPlugin.h +++ /dev/null @@ -1,62 +0,0 @@ -#pragma once - -#include <mutex> - -#include <ArmarXCore/core/Component.h> - -#include <RobotAPI/interface/armem/server/MemoryInterface.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> - -#include "MemoryNameSystem.h" - - -namespace armarx::armem::mns::plugins -{ - - class ComponentPlugin : public armarx::ComponentPlugin - { - public: - using armarx::ComponentPlugin::ComponentPlugin; - }; - -} - - -namespace armarx::armem::mns -{ - - /** - * @brief Utility for connecting a Memory to Ice. - */ - class ComponentPluginUser : - virtual public ManagedIceObject - , virtual public mns::MemoryNameSystemInterface - { - public: - - ComponentPluginUser(); - - // mns::MemoryNameSystemInterface interface - public: - armem::data::RegisterMemoryResult registerMemory(const armem::data::RegisterMemoryInput& input, const Ice::Current& = Ice::emptyCurrent) override; - armem::data::RemoveMemoryResult removeMemory(const armem::data::RemoveMemoryInput& input, const Ice::Current& = Ice::emptyCurrent) override; - armem::data::GetAllRegisteredMemoriesResult getAllRegisteredMemories(const Ice::Current&) override; - armem::data::ResolveMemoryNameResult resolveMemoryName(const armem::data::ResolveMemoryNameInput& input, const Ice::Current& = Ice::emptyCurrent) override; - armem::data::WaitForMemoryResult waitForMemory(const armem::data::WaitForMemoryInput& input, const Ice::Current& = Ice::emptyCurrent) override; - - - public: - - std::mutex mnsMutex; - MemoryNameSystem mns; - - - private: - - plugins::ComponentPlugin* plugin = nullptr; - - - }; - - -} diff --git a/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.cpp b/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.cpp index 6e001784b90104580a49b2510bdb6583fa36783c..a80a189ff585c7610bebe0978468aec82ebe48b9 100644 --- a/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.cpp +++ b/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.cpp @@ -4,185 +4,41 @@ namespace armarx::armem::mns { - MemoryNameSystem::MemoryNameSystem(const std::string& logTag) + // dto::WaitForServerResult MemoryNameSystem::waitForServer(const dto::WaitForServerInput& input) + void MemoryNameSystem::waitForServer_async( + const AMD_MemoryNameSystemInterface_waitForServerPtr& future, + const dto::WaitForServerInput& input) { - armarx::Logging::setTag(logTag); + waitForServerFutures[input.name].push_back(future); + waitForServer_processOnce(); } - armem::data::RegisterMemoryResult MemoryNameSystem::registerMemory(const armem::data::RegisterMemoryInput& input) + void MemoryNameSystem::waitForServer_processOnce() { - armem::data::RegisterMemoryResult result; - - if (!input.proxy) - { - result.success = false; - std::stringstream ss; - ss << "Could not register the memory '" << input.name << "'." - << "\nGiven proxy is null." - << "\nIf you want to remove a memory, use `removeMemory()`."; - result.errorMessage = ss.str(); - return result; - } - - auto it = memoryMap.find(input.name); - if (it == memoryMap.end()) - { - it = memoryMap.emplace(input.name, MemoryInfo{}).first; - } - else if (!input.existOk) - { - result.success = false; - std::stringstream ss; - ss << "Could not register the memory '" << input.name << "'." - << "\nMemory '" << input.name << "' is already registered. " - << "\nIf this is ok, set 'existOk' to true when registering the memory."; - result.errorMessage = ss.str(); - return result; - } - - MemoryInfo& info = it->second; - info.name = input.name; - info.proxy = input.proxy; - info.timeRegistered = armem::Time::now(); - ARMARX_DEBUG << "Registered memory '" << info.name << "'."; - - { - std::unique_lock lock(waitForMemoryMutex); - waitForMemoryCond.notify_all(); - } - - result.success = true; - return result; - } - - - armem::data::RemoveMemoryResult MemoryNameSystem::removeMemory(const armem::data::RemoveMemoryInput& input) - { - armem::data::RemoveMemoryResult result; - - if (auto it = memoryMap.find(input.name); it != memoryMap.end()) - { - result.success = true; - memoryMap.erase(it); - - ARMARX_DEBUG << "Removed memory '" << input.name << "'."; - } - else if (!input.notExistOk) - { - result.success = false; - std::stringstream ss; - ss << "Could not remove the memory '" << input.name << "." - << "\nMemory '" << input.name << "' is not registered. " - << "\nIf this is ok, set 'notExistOk' to true when removing the memory."; - result.errorMessage = ss.str(); - } - - return result; - } - - - data::GetAllRegisteredMemoriesResult - MemoryNameSystem::getAllRegisteredMemories() - { - data::GetAllRegisteredMemoriesResult result; - result.success = true; - result.errorMessage = ""; - - for (const auto& [name, info] : memoryMap) + for (auto it = waitForServerFutures.begin(); it != waitForServerFutures.end();) { - try + auto& [name, futures] = *it; + if (auto st = servers.find(name); st != servers.end()) { - info.proxy->ice_ping(); - result.proxies[name] = info.proxy; - } - catch (const Ice::Exception&) - { - } - } - - return result; - } - - - armem::data::ResolveMemoryNameResult MemoryNameSystem::resolveMemoryName(const armem::data::ResolveMemoryNameInput& input) - { - armem::data::ResolveMemoryNameResult result; - try - { - MemoryInfo& info = memoryMap.at(input.name); - - result.success = true; - result.proxy = info.proxy; - - ARMARX_DEBUG << "Resolved memory name '" << input.name << "'."; - } - catch (const std::out_of_range&) - { - result.success = false; - std::stringstream ss; - ss << "Could not resolve the memory name '" << input.name << "'." - << "\nMemory '" << input.name << "' is not registered."; - result.errorMessage = ss.str(); - } - - return result; - } - - - data::WaitForMemoryResult MemoryNameSystem::waitForMemory(const data::WaitForMemoryInput& input) - { - data::ResolveMemoryNameInput resInput; - resInput.name = input.name; - - Time start = Time::now(); - data::ResolveMemoryNameResult resResult; - { - std::unique_lock lock(waitForMemoryMutex); - auto pred = [this, resInput, &resResult]() - { - resResult = resolveMemoryName(resInput); - return resResult.success; - }; - if (input.timeoutMilliSeconds >= 0) - { - waitForMemoryCond.wait_for(lock, std::chrono::milliseconds(input.timeoutMilliSeconds), pred); + ServerInfo& info = st->second; + + dto::WaitForServerResult result; + result.success = true; + result.server = info.server; + + // Send responses and remove entry. + for (auto& future : futures) + { + future->ice_response(result); + } + it = waitForServerFutures.erase(it); } else { - waitForMemoryCond.wait(lock, pred); + ++it; // Skip. } } - - armem::data::WaitForMemoryResult result; - result.success = resResult.success; - - if (resResult.success) - { - ARMARX_CHECK(resResult.proxy); - result.proxy = resResult.proxy; - } - else - { - ARMARX_CHECK((Time::now() - start).toMilliSeconds() > input.timeoutMilliSeconds) - << (Time::now() - start).toMilliSeconds() << " > " << input.timeoutMilliSeconds; - - std::stringstream ss; - ss << "Timeout (" << input.timeoutMilliSeconds << " ms) while waiting for memory '" << input.name << "'."; - if (resResult.errorMessage.size() > 0) - { - ss << "\n" << resResult.errorMessage; - } - result.errorMessage = ss.str(); - } - - return result; - } - - - bool MemoryNameSystem::hasMemory(const std::string& memoryName) const - { - return memoryMap.count(memoryName) > 0; } @@ -195,20 +51,41 @@ namespace armarx::armem::mns int row = 0; grid.add(Label("Memory Name"), {row, 0}) .add(Label("Component Name"), {row, 1}) - .add(Label("Registration Time"), {row, 2}) + .add(Label("R/W"), {row, 2}) + .add(Label("Registration Time"), {row, 3}) ; row++; - for (const auto& [name, info] : memoryMap) + for (const auto& [name, info] : servers) { ARMARX_CHECK_EQUAL(name, info.name); - grid - .add(Label(name), {row, 0}) - .add(Label(info.proxy->ice_getIdentity().name), {row, 1}) - .add(Label(armem::toDateTimeMilliSeconds(info.timeRegistered, 0)), {row, 2}) - ; + std::string componentName = ""; + std::string mode = ""; + if (info.server.reading) + { + componentName = info.server.reading->ice_getIdentity().name; + mode += "R"; + } + if (info.server.writing) + { + componentName = info.server.writing->ice_getIdentity().name; + mode += "W"; + } + + int col = 0; + grid.add(Label(name), {row, col}); + ++col; + + grid.add(Label(componentName), {row, col}); + ++col; + + grid.add(Label(mode), {row, col}); + ++col; + + grid.add(Label(armem::toDateTimeMilliSeconds(info.timeRegistered, 0)), {row, col}); + ++col; - row++; + ++row; } return grid; diff --git a/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.h b/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.h index 7372246d7e8059787f97f117931830d12c9dc082..51e4719f127ee576073e0c9b45cb0635241a185d 100644 --- a/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.h +++ b/source/RobotAPI/libraries/armem/mns/MemoryNameSystem.h @@ -1,55 +1,36 @@ #pragma once -#include <condition_variable> -#include <mutex> - -#include <ArmarXCore/core/logging/Logging.h> +#include "Registry.h" #include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> -#include <RobotAPI/interface/armem/server/MemoryInterface.h> #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> -#include "../core/Time.h" +#include <map> +#include <string> namespace armarx::armem::mns { - class MemoryNameSystem : armarx::Logging + class MemoryNameSystem : public Registry { public: - MemoryNameSystem(const std::string& logTag = "MemoryNameSystem"); - - - /** - * @brief Register a new memory or update an existing entry. - * - * Causes threads waiting in `waitForMemory()` to resume if the respective - * memory was added. - */ - data::RegisterMemoryResult registerMemory(const data::RegisterMemoryInput& input); - /** - * @brief Remove a memory entry. - */ - data::RemoveMemoryResult removeMemory(const data::RemoveMemoryInput& input); + using WaitForServerFuturePtr = AMD_MemoryNameSystemInterface_waitForServerPtr; - data::GetAllRegisteredMemoriesResult getAllRegisteredMemories(); - /** - * @brief Gets a memory entry, if it is available. - */ - data::ResolveMemoryNameResult resolveMemoryName(const data::ResolveMemoryNameInput& input); + public: /** - * @brief Blocks until the specified memory is available, returning its proxy. + * @brief Store the call in a container for later response. */ - data::WaitForMemoryResult waitForMemory(const data::WaitForMemoryInput& input); + void waitForServer_async( + const AMD_MemoryNameSystemInterface_waitForServerPtr& future, + const dto::WaitForServerInput& input); + void waitForServer_processOnce(); - /// Indicates whether a memory entry for that name exists. - bool hasMemory(const std::string& memoryName) const; /// Builds a RemoteGui grid containing information about registered memories. armarx::RemoteGui::Client::GridLayout RemoteGui_buildInfoGrid(); @@ -57,22 +38,8 @@ namespace armarx::armem::mns public: - /// Information about a memory entry. - struct MemoryInfo - { - std::string name; - server::MemoryInterfacePrx proxy; - Time timeRegistered; - }; - - /// The registered memories. - std::map<std::string, MemoryInfo> memoryMap; - - - /// Mutex for `waitForMemoryCond`. - std::mutex waitForMemoryMutex; - /// Condition variable used by `waitForMemory()`. - std::condition_variable waitForMemoryCond; + /// Queued calls to `waitForServer`. + std::map<std::string, std::vector<WaitForServerFuturePtr>> waitForServerFutures; }; diff --git a/source/RobotAPI/libraries/armem/mns/Registry.cpp b/source/RobotAPI/libraries/armem/mns/Registry.cpp new file mode 100644 index 0000000000000000000000000000000000000000..260cfcd818a426ae7b4f18c6cde5a4180a459f0b --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/Registry.cpp @@ -0,0 +1,162 @@ +#include "Registry.h" + +#include <ArmarXCore/core/logging/Logging.h> + + +namespace armarx::armem::mns +{ + + Registry::Registry(const std::string& logTag) + { + armarx::Logging::setTag(logTag); + } + + + bool Registry::hasServer(const std::string& memoryName) const + { + return servers.count(memoryName) > 0; + } + + + dto::RegisterServerResult Registry::registerServer(const dto::RegisterServerInput& input) + { + dto::RegisterServerResult result; + + if (not(input.server.reading or input.server.writing)) + { + result.success = false; + std::stringstream ss; + ss << "Could not register the memory server '" << input.name << "'." + << "\nGiven proxies are null." + << "\nIf you want to remove a memory server, use `removeServer()`."; + result.errorMessage = ss.str(); + return result; + } + + auto it = servers.find(input.name); + if (it == servers.end()) + { + it = servers.emplace(input.name, ServerInfo{}).first; + } + else if (not input.existOk) + { + result.success = false; + std::stringstream ss; + ss << "Could not register the memory '" << input.name << "'." + << "\nMemory '" << input.name << "' is already registered. " + << "\nIf this is ok, set 'existOk' to true when registering the memory."; + result.errorMessage = ss.str(); + return result; + } + + ServerInfo& info = it->second; + info.name = input.name; + info.server = input.server; + info.timeRegistered = armem::Time::now(); + ARMARX_DEBUG << "Registered memory '" << info.name << "'."; + + result.success = true; + return result; + } + + + dto::RemoveServerResult Registry::removeServer(const dto::RemoveServerInput& input) + { + dto::RemoveServerResult result; + + if (auto it = servers.find(input.name); it != servers.end()) + { + result.success = true; + servers.erase(it); + + ARMARX_DEBUG << "Removed memory '" << input.name << "'."; + } + else if (!input.notExistOk) + { + result.success = false; + std::stringstream ss; + ss << "Could not remove the memory '" << input.name << "." + << "\nMemory '" << input.name << "' is not registered. " + << "\nIf this is ok, set 'notExistOk' to true when removing the memory."; + result.errorMessage = ss.str(); + } + + return result; + } + + + template <class Prx> + bool isAvailable(const Prx& proxy) + { + if (proxy) + { + try + { + proxy->ice_ping(); + return true; + } + catch (const Ice::Exception&) + { + } + } + return false; + } + + + dto::GetAllRegisteredServersResult + Registry::getAllRegisteredServers() + { + dto::GetAllRegisteredServersResult result; + result.success = true; + result.errorMessage = ""; + + for (const auto& [name, info] : servers) + { + if (isAvailable(info.server.reading) or isAvailable(info.server.writing)) + { + result.servers[name] = info.server; + } + } + + return result; + } + + + dto::ResolveServerResult Registry::resolveServer(const dto::ResolveServerInput& input) + { + dto::ResolveServerResult result; + try + { + ServerInfo& info = servers.at(input.name); + + result.success = true; + result.server = info.server; + + ARMARX_DEBUG << "Resolved memory name '" << input.name << "'."; + } + catch (const std::out_of_range&) + { + result.success = false; + std::stringstream ss; + ss << "Could not resolve the memory name '" << input.name << "'." + << "\nServer '" << input.name << "' is not registered."; + result.errorMessage = ss.str(); + } + + return result; + } + + + server::ReadingMemoryInterfacePrx getReadingInterface(const dto::MemoryServerInterfaces& server) + { + return server.reading; + } + + + server::WritingMemoryInterfacePrx getWritingInterface(const dto::MemoryServerInterfaces& server) + { + return server.writing; + } + +} + diff --git a/source/RobotAPI/libraries/armem/mns/Registry.h b/source/RobotAPI/libraries/armem/mns/Registry.h new file mode 100644 index 0000000000000000000000000000000000000000..bf9348d157ee990f6032c4cf115b9fd56c70f716 --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/Registry.h @@ -0,0 +1,71 @@ +#pragma once + +#include <RobotAPI/libraries/armem/core/Time.h> + +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> +#include <RobotAPI/interface/armem/server/ReadingMemoryInterface.h> +#include <RobotAPI/interface/armem/server/WritingMemoryInterface.h> + +#include <ArmarXCore/core/logging/Logging.h> + +#include <map> +#include <string> + + +namespace armarx::armem::mns +{ + + /** + * @brief A registry for memory servers. + */ + class Registry : armarx::Logging + { + public: + + Registry(const std::string& logTag = "MemoryNameSystem Registry"); + + + /// Indicates whether a server entry for that name exists. + bool hasServer(const std::string& memoryName) const; + + + /** + * @brief Register a new memory server or update an existing entry. + * + * Causes threads waiting in `waitForMemory()` to resume if the respective + * memory server was added. + */ + dto::RegisterServerResult registerServer(const dto::RegisterServerInput& input); + /** + * @brief Remove a server entry. + */ + dto::RemoveServerResult removeServer(const dto::RemoveServerInput& input); + + + /** + * @brief Gets a server entry, if it is available. + */ + dto::ResolveServerResult resolveServer(const dto::ResolveServerInput& input); + + dto::GetAllRegisteredServersResult getAllRegisteredServers(); + + + public: + + /// Information about a memory entry. + struct ServerInfo + { + std::string name; + mns::dto::MemoryServerInterfaces server; + Time timeRegistered; + }; + + /// The registered memories. + std::map<std::string, ServerInfo> servers; + + }; + + + server::ReadingMemoryInterfacePrx getReadingInterface(const dto::MemoryServerInterfaces& server); + server::WritingMemoryInterfacePrx getWritingInterface(const dto::MemoryServerInterfaces& server); +} diff --git a/source/RobotAPI/libraries/armem/mns/plugins/Plugin.cpp b/source/RobotAPI/libraries/armem/mns/plugins/Plugin.cpp new file mode 100644 index 0000000000000000000000000000000000000000..a2e7c5dbf3fe87d6fdf24fee0181504a5f85abe9 --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/plugins/Plugin.cpp @@ -0,0 +1,8 @@ +#include "Plugin.h" + + +namespace armarx::armem::mns::plugins +{ + +} + diff --git a/source/RobotAPI/libraries/armem/mns/plugins/Plugin.h b/source/RobotAPI/libraries/armem/mns/plugins/Plugin.h new file mode 100644 index 0000000000000000000000000000000000000000..5caa973a9ebb7025f42978c608c033ce47722074 --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/plugins/Plugin.h @@ -0,0 +1,24 @@ +#pragma once + +#include <RobotAPI/libraries/armem/mns/MemoryNameSystem.h> + +#include <ArmarXCore/core/ComponentPlugin.h> + + +namespace armarx::armem::mns::plugins +{ + + class Plugin : public armarx::ComponentPlugin + { + public: + + using armarx::ComponentPlugin::ComponentPlugin; + + + public: + + MemoryNameSystem mns; + + }; + +} diff --git a/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.cpp b/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.cpp new file mode 100644 index 0000000000000000000000000000000000000000..4ad29cdeec3c2b732cf1b9074931ab3c116fa42b --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.cpp @@ -0,0 +1,69 @@ +#include "PluginUser.h" +#include "Plugin.h" + + +namespace armarx::armem::mns::plugins +{ + + PluginUser::PluginUser() + { + addPlugin(plugin); + } + + + dto::RegisterServerResult PluginUser::registerServer(const dto::RegisterServerInput& input, const Ice::Current&) + { + std::scoped_lock lock(mnsMutex); + dto::RegisterServerResult result = plugin->mns.registerServer(input); + return result; + } + + + dto::RemoveServerResult PluginUser::removeServer(const dto::RemoveServerInput& input, const Ice::Current&) + { + std::scoped_lock lock(mnsMutex); + dto::RemoveServerResult result = plugin->mns.removeServer(input); + return result; + } + + + dto::GetAllRegisteredServersResult + PluginUser::getAllRegisteredServers(const Ice::Current&) + { + std::scoped_lock lock(mnsMutex); + dto::GetAllRegisteredServersResult result = plugin->mns.getAllRegisteredServers(); + return result; + } + + + dto::ResolveServerResult PluginUser::resolveServer(const dto::ResolveServerInput& input, const Ice::Current&) + { + std::scoped_lock lock(mnsMutex); + dto::ResolveServerResult result = plugin->mns.resolveServer(input); + return result; + } + + + // dto::WaitForServerResult PluginUser::waitForServer(const dto::WaitForServerInput& input, const Ice::Current&) + void PluginUser::waitForServer_async( + const AMD_MemoryNameSystemInterface_waitForServerPtr& future, + const dto::WaitForServerInput& input, + const Ice::Current&) + { + std::scoped_lock lock(mnsMutex); + plugin->mns.waitForServer_async(future, input); + } + + + MemoryNameSystem& PluginUser::mns() + { + return plugin->mns; + } + + + const MemoryNameSystem& PluginUser::mns() const + { + return plugin->mns; + } + +} diff --git a/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.h b/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.h new file mode 100644 index 0000000000000000000000000000000000000000..1e8134ad5d372b1d69252cdc0cf2f5916c948b1e --- /dev/null +++ b/source/RobotAPI/libraries/armem/mns/plugins/PluginUser.h @@ -0,0 +1,55 @@ +#pragma once + +#include <RobotAPI/libraries/armem/mns/MemoryNameSystem.h> + +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> + +#include <ArmarXCore/core/ManagedIceObject.h> + +#include <mutex> + + +namespace armarx::armem::mns::plugins +{ + class Plugin; + + + class PluginUser : + virtual public ManagedIceObject + , virtual public mns::MemoryNameSystemInterface + { + public: + + PluginUser(); + + // mns::MemoryNameSystemInterface interface + public: + + dto::RegisterServerResult registerServer(const dto::RegisterServerInput& input, const Ice::Current& = Ice::emptyCurrent) override; + dto::RemoveServerResult removeServer(const dto::RemoveServerInput& input, const Ice::Current& = Ice::emptyCurrent) override; + + dto::GetAllRegisteredServersResult getAllRegisteredServers(const Ice::Current&) override; + + dto::ResolveServerResult resolveServer(const dto::ResolveServerInput& input, const Ice::Current& = Ice::emptyCurrent) override; + + // Uses Asynchronous Method Dispatch (AMD) + void waitForServer_async( + const AMD_MemoryNameSystemInterface_waitForServerPtr& future, + const dto::WaitForServerInput& input, + const Ice::Current& = Ice::emptyCurrent) override; + + + protected: + + std::mutex mnsMutex; + MemoryNameSystem& mns(); + const MemoryNameSystem& mns() const; + + + private: + + plugins::Plugin* plugin = nullptr; + + }; + +} diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp b/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp deleted file mode 100644 index 18a24d77f82baf4f07879caeb21bb52b308fdac7..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.cpp +++ /dev/null @@ -1,165 +0,0 @@ -#include "ComponentPlugin.h" - -#include "MemoryToIceAdapter.h" - -#include <RobotAPI/libraries/armem/core/error.h> - -#include <ArmarXCore/core/Component.h> -#include <ArmarXCore/core/exceptions/local/ExpressionException.h> - - -namespace armarx::armem::server::plugins -{ - ComponentPlugin::~ComponentPlugin() = default; - - - void ComponentPlugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) - { - MemoryNameSystemComponentPlugin::postCreatePropertyDefinitions(properties); - - ComponentPluginUser& parent = this->parent<ComponentPluginUser>(); - properties->topic(memoryListener, parent.memoryListenerDefaultName); - - properties->optional(parent.longtermMemoryEnabled, "mem.ltm.00_enabled"); - } - - - void ComponentPlugin::postOnConnectComponent() - { - ComponentPluginUser& parent = this->parent<ComponentPluginUser>(); - - if (isMemoryNameSystemEnabled() && parent.memoryNameSystem) - { - registerMemory(parent); - } - parent.iceMemory.setMemoryListener(memoryListener); - - // establishing connection to ltm and mongodb - if (parent.longtermMemoryEnabled) - { - parent.longtermMemoryManager.reload(); - } - } - - - void ComponentPlugin::preOnDisconnectComponent() - { - ComponentPluginUser& parent = this->parent<ComponentPluginUser>(); - if (isMemoryNameSystemEnabled() && parent.memoryNameSystem) - { - removeMemory(parent); - } - } - - - data::RegisterMemoryResult ComponentPlugin::registerMemory(ComponentPluginUser& parent) - { - MemoryID id = MemoryID().withMemoryName(parent.workingMemory.name()); - MemoryInterfacePrx proxy = MemoryInterfacePrx::checkedCast(parent.getProxy()); - ARMARX_CHECK_NOT_NULL(proxy); - - data::RegisterMemoryResult result; - try - { - parent.memoryNameSystem.registerServer(id, proxy); - result.success = true; - ARMARX_DEBUG << "Registered memory server for " << id << " in the Memory Name System (MNS)."; - } - catch (const armem::error::ServerRegistrationOrRemovalFailed& e) - { - result.success = false; - result.errorMessage = e.what(); - ARMARX_WARNING << e.what(); - } - return result; - } - - - data::RemoveMemoryResult ComponentPlugin::removeMemory(ComponentPluginUser& parent) - { - MemoryID id = MemoryID().withMemoryName(parent.workingMemory.name()); - - data::RemoveMemoryResult result; - try - { - parent.memoryNameSystem.removeServer(id); - result.success = true; - ARMARX_DEBUG << "Removed memory server for " << id << " from the Memory Name System (MNS)."; - } - catch (const armem::error::ServerRegistrationOrRemovalFailed& e) - { - result.success = false; - result.errorMessage = e.what(); - ARMARX_WARNING << e.what(); - } - catch (const Ice::NotRegisteredException&) - { - // It's ok, the MNS is gone. - result.success = false; - result.errorMessage = "Memory Name System is gone."; - } - return result; - } - -} - - -namespace armarx::armem::server -{ - ComponentPluginUser::ComponentPluginUser() - { - addPlugin(plugin); - } - - ComponentPluginUser::~ComponentPluginUser() = default; - - // Set the name of a memory - void ComponentPluginUser::setMemoryName(const std::string& memoryName) - { - workingMemory.name() = memoryName; - longtermMemoryManager.setName(memoryName); - } - - - // WRITING - data::AddSegmentsResult ComponentPluginUser::addSegments(const data::AddSegmentsInput& input, const Ice::Current&) - { - ARMARX_TRACE; - bool addCoreSegmentOnUsage = false; - return addSegments(input, addCoreSegmentOnUsage); - } - - data::AddSegmentsResult ComponentPluginUser::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments) - { - ARMARX_TRACE; - data::AddSegmentsResult result = iceMemory.addSegments(input, addCoreSegments); - return result; - } - - - data::CommitResult ComponentPluginUser::commit(const data::Commit& commitIce, const Ice::Current&) - { - ARMARX_TRACE; - return iceMemory.commit(commitIce); - } - - - // READING - armem::query::data::Result ComponentPluginUser::query(const armem::query::data::Input& input, const Ice::Current&) - { - ARMARX_TRACE; - return iceMemory.query(input); - } - - - // LTM STORING - data::StoreResult ComponentPluginUser::store(const data::StoreInput& input, const Ice::Current&) - { - ARMARX_TRACE; - return iceMemory.store(input); - } - - - // LTM LOADING - -} diff --git a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h b/source/RobotAPI/libraries/armem/server/ComponentPlugin.h deleted file mode 100644 index f55bfc6c024922f10b84d76a52b21135db58e928..0000000000000000000000000000000000000000 --- a/source/RobotAPI/libraries/armem/server/ComponentPlugin.h +++ /dev/null @@ -1,127 +0,0 @@ -#pragma once - -#include <mutex> - -#include <ArmarXCore/core/ComponentPlugin.h> - -#include <RobotAPI/interface/armem/server/MemoryInterface.h> -#include <RobotAPI/interface/armem/client/MemoryListenerInterface.h> -#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> - -#include <RobotAPI/libraries/armem/core/wm/memory_definitions.h> -#include <RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h> -#include <RobotAPI/libraries/armem/client/MemoryNameSystemComponentPlugin.h> - -#include "MemoryToIceAdapter.h" - - -namespace armarx::armem::server -{ - class ComponentPluginUser; -} - - -namespace armarx::armem::server::plugins -{ - - class ComponentPlugin : public client::plugins::MemoryNameSystemComponentPlugin - { - using Base = client::plugins::MemoryNameSystemComponentPlugin; - public: - - using Base::MemoryNameSystemComponentPlugin; - virtual ~ComponentPlugin() override; - - void postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) override; - - void postOnConnectComponent() override; - void preOnDisconnectComponent() override; - - - /** - * @brief Register the parent component in the MNS. - * Called before onConnect() if MNS is enabled. - */ - data::RegisterMemoryResult registerMemory(ComponentPluginUser& parent); - /** - * @brief Remove the parent component from the MNS. - * Called before onDisconnect() if MNS is enabled. - */ - data::RemoveMemoryResult removeMemory(ComponentPluginUser& parent); - - client::MemoryListenerInterfacePrx memoryListener; - - std::string longTermMemoryDatabaseHost; - std::string longTermMemoryDatabaseUser; - std::string longTermMemoryDatabasePassword; - }; - -} - - -namespace armarx::armem::server -{ - - /** - * @brief Base class of memory server components. - */ - class ComponentPluginUser : - virtual public ManagedIceObject - , virtual public MemoryInterface - , virtual public client::MemoryNameSystemComponentPluginUser - { - public: - - ComponentPluginUser(); - virtual ~ComponentPluginUser() override; - - /// Set the name of the wm and the ltm (if enabled) - void setMemoryName(const std::string& memoryName); - - - // WritingInterface interface - virtual data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, const Ice::Current& = Ice::emptyCurrent) override; - data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, bool addCoreSegments); - - virtual data::CommitResult commit(const data::Commit& commit, const Ice::Current& = Ice::emptyCurrent) override; - - - // ReadingInterface interface - virtual armem::query::data::Result query(const armem::query::data::Input& input, const Ice::Current& = Ice::emptyCurrent) override; - - - // StoringInterface interface - virtual data::StoreResult store(const data::StoreInput&, const Ice::Current& = Ice::emptyCurrent) override; - - - // LoadingInterface interface - - - public: - - /// The actual memory. - server::wm::Memory workingMemory; - // [[deprecated ("The global working memory mutex is deprecated. Use the core segment mutexes instead.")]] - // std::mutex workingMemoryMutex; - - /// Parameter to indicate whether to use or not to use the ltm feature - bool longtermMemoryEnabled = true; - - /// A manager class for the ltm. It internally holds a normal wm instance - server::ltm::mongodb::MemoryManager longtermMemoryManager; - - /// property defaults - std::string memoryListenerDefaultName = "MemoryUpdates"; - - /// Helps connecting `memory` to ice. Used to handle Ice callbacks. - MemoryToIceAdapter iceMemory { &workingMemory, &longtermMemoryManager}; - - - private: - - plugins::ComponentPlugin* plugin = nullptr; - - }; - - -} diff --git a/source/RobotAPI/libraries/armem/server/forward_declarations.h b/source/RobotAPI/libraries/armem/server/forward_declarations.h index 6872e2584352195ca8e587043e275acfbffb3739..d65ec0f36b9f60e680c6e720d80cd9cc3d6e789f 100644 --- a/source/RobotAPI/libraries/armem/server/forward_declarations.h +++ b/source/RobotAPI/libraries/armem/server/forward_declarations.h @@ -16,3 +16,7 @@ namespace armarx::armem::server::wm class CoreSegment; class Memory; } +namespace armarx::armem::server::ltm::mongodb +{ + class MemoryManager; +} diff --git a/source/RobotAPI/libraries/armem/server/plugins.h b/source/RobotAPI/libraries/armem/server/plugins.h new file mode 100644 index 0000000000000000000000000000000000000000..9f1255994daba045756a8c90dcbcfd57a9c63a11 --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins.h @@ -0,0 +1,20 @@ +#pragma once + +#include "plugins/Plugin.h" +#include "plugins/ReadOnlyPluginUser.h" +#include "plugins/ReadWritePluginUser.h" + + +namespace armarx::armem::server +{ + using plugins::Plugin; + using plugins::ReadOnlyPluginUser; + using plugins::ReadWritePluginUser; +} + +namespace armarx::armem +{ + using ServerPlugin = server::Plugin; + using ReadOnlyServerPluginUser = server::ReadOnlyPluginUser; + using ReadWriteServerPluginUser = server::ReadWritePluginUser; +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp b/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp new file mode 100644 index 0000000000000000000000000000000000000000..031e8fbdfe55b1024bac050b341327e6ef16e482 --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/Plugin.cpp @@ -0,0 +1,125 @@ +#include "Plugin.h" + +#include <RobotAPI/libraries/armem/core/error.h> +#include <RobotAPI/libraries/armem/client/plugins/Plugin.h> + +#include <ArmarXCore/core/Component.h> +#include <ArmarXCore/core/exceptions/local/ExpressionException.h> + + +namespace armarx::armem::server::plugins +{ + + Plugin::~Plugin() = default; + + + Plugin::Plugin(ManagedIceObject& parent, std::string prefix) : + armarx::ComponentPlugin(parent, prefix) + { + addPlugin(clientPlugin); + ARMARX_CHECK_NOT_NULL(clientPlugin); + addPluginDependency(clientPlugin); + } + + + void Plugin::postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) + { + const std::string prefix = "mem."; + if (not workingMemory.name().empty() + and not properties->hasDefinition(prefix + "MemoryName")) + { + properties->optional(workingMemory.name(), prefix + "MemoryName", "Name of this memory server."); + } + properties->optional(longtermMemoryEnabled, prefix + "ltm.00_enabled"); + + + // Publish memory updates topic + properties->topic(memoryTopic, memoryTopicDefaultName); + } + + + void Plugin::postOnConnectComponent() + { + Component& parent = this->parent<Component>(); + + if (clientPlugin->isMemoryNameSystemEnabled() and clientPlugin->getMemoryNameSystemClient()) + { + registerServer(parent); + } + iceAdapter.setMemoryListener(memoryTopic); + + // establishing connection to ltm and mongodb + if (longtermMemoryEnabled) + { + longtermMemoryManager.reload(); + } + } + + + void Plugin::preOnDisconnectComponent() + { + if (clientPlugin->isMemoryNameSystemEnabled() and clientPlugin->getMemoryNameSystemClient()) + { + removeServer(); + } + } + + + void Plugin::setMemoryName(const std::string& memoryName) + { + workingMemory.name() = memoryName; + longtermMemoryManager.setName(memoryName); + } + + + mns::dto::RegisterServerResult Plugin::registerServer(armarx::Component& parent) + { + MemoryID id = MemoryID().withMemoryName(workingMemory.name()); + mns::dto::MemoryServerInterfaces server; + server.reading = ReadingMemoryInterfacePrx::uncheckedCast(parent.getProxy()); + server.writing = WritingMemoryInterfacePrx::uncheckedCast(parent.getProxy()); + + mns::dto::RegisterServerResult result; + try + { + clientPlugin->getMemoryNameSystemClient().registerServer(id, server); + result.success = true; + ARMARX_DEBUG << "Registered memory server for " << id << " in the Memory Name System (MNS)."; + } + catch (const armem::error::ServerRegistrationOrRemovalFailed& e) + { + result.success = false; + result.errorMessage = e.what(); + ARMARX_WARNING << e.what(); + } + return result; + } + + + mns::dto::RemoveServerResult Plugin::removeServer() + { + MemoryID id = MemoryID().withMemoryName(workingMemory.name()); + + mns::dto::RemoveServerResult result; + try + { + clientPlugin->getMemoryNameSystemClient().removeServer(id); + result.success = true; + ARMARX_DEBUG << "Removed memory server for " << id << " from the Memory Name System (MNS)."; + } + catch (const armem::error::ServerRegistrationOrRemovalFailed& e) + { + result.success = false; + result.errorMessage = e.what(); + ARMARX_WARNING << e.what(); + } + catch (const Ice::NotRegisteredException&) + { + // It's ok, the MNS is gone. + result.success = false; + result.errorMessage = "Memory Name System is gone."; + } + return result; + } + +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/Plugin.h b/source/RobotAPI/libraries/armem/server/plugins/Plugin.h new file mode 100644 index 0000000000000000000000000000000000000000..49cc07bb08dc7265fa797e2f5f77a3d81511c33c --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/Plugin.h @@ -0,0 +1,105 @@ +#pragma once + +#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h> + +#include <RobotAPI/libraries/armem/server/wm/memory_definitions.h> +#include <RobotAPI/libraries/armem/server/ltm/mongodb/MemoryManager.h> + +#include <RobotAPI/interface/armem/client/MemoryListenerInterface.h> +#include <RobotAPI/interface/armem/mns/MemoryNameSystemInterface.h> + +#include <ArmarXCore/core/ComponentPlugin.h> + + +namespace armarx +{ + class Component; +} +namespace armarx::armem::client::plugins +{ + class Plugin; +} + +namespace armarx::armem::server::plugins +{ + + class Plugin : + public armarx::ComponentPlugin + { + public: + + Plugin(ManagedIceObject& parent, std::string prefix); + virtual ~Plugin() override; + + + virtual void postCreatePropertyDefinitions(PropertyDefinitionsPtr& properties) override; + + virtual void postOnConnectComponent() override; + virtual void preOnDisconnectComponent() override; + + + public: + + /// Set the name of the wm and the ltm (if enabled). + void setMemoryName(const std::string& memoryName); + + + protected: + + /** + * @brief Register the parent component in the MNS. + * + * Called before onConnect() if MNS is enabled. + */ + mns::dto::RegisterServerResult registerServer(armarx::Component& parent); + + /** + * @brief Remove the parent component from the MNS. + * + * Called before onDisconnect() if MNS is enabled. + */ + mns::dto::RemoveServerResult removeServer(); + + + + public: + + // Working Memory + + /// The actual memory. + server::wm::Memory workingMemory; + + /// Helps connecting `memory` to ice. Used to handle Ice callbacks. + MemoryToIceAdapter iceAdapter { &workingMemory, &longtermMemoryManager}; + + + // Working Memory Updates (publishing) + + std::string memoryTopicDefaultName = "MemoryUpdates"; + client::MemoryListenerInterfacePrx memoryTopic; + + + // Long-Term Memory + + /// Indicates whether to use or not to use the ltm feature. + bool longtermMemoryEnabled = true; + + /// A manager class for the ltm. It internally holds a normal wm instance as a cache. + server::ltm::mongodb::MemoryManager longtermMemoryManager; + + std::string longTermMemoryDatabaseHost; + std::string longTermMemoryDatabaseUser; + std::string longTermMemoryDatabasePassword; + + + private: + + client::plugins::Plugin* clientPlugin; + + }; +} + +namespace armarx::armem::server +{ + using plugins::Plugin; +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.cpp b/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.cpp new file mode 100644 index 0000000000000000000000000000000000000000..b95b94afb85f31efd41384283409460b706a729e --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.cpp @@ -0,0 +1,56 @@ +#include "ReadOnlyPluginUser.h" +#include "Plugin.h" + +#include <RobotAPI/libraries/armem/core/error.h> +#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h> + +#include <ArmarXCore/core/Component.h> +#include <ArmarXCore/core/exceptions/local/ExpressionException.h> + + + +namespace armarx::armem::server::plugins +{ + + ReadOnlyPluginUser::ReadOnlyPluginUser() + { + addPlugin(plugin); + } + + + ReadOnlyPluginUser::~ReadOnlyPluginUser() + { + } + + + void ReadOnlyPluginUser::setMemoryName(const std::string& memoryName) + { + plugin->setMemoryName(memoryName); + } + + + armem::query::data::Result ReadOnlyPluginUser::query(const armem::query::data::Input& input, const Ice::Current&) + { + ARMARX_TRACE; + return iceAdapter().query(input); + } + + + Plugin& ReadOnlyPluginUser::memoryServerPlugin() + { + return *plugin; + } + + + wm::Memory& ReadOnlyPluginUser::workingMemory() + { + return plugin->workingMemory; + } + + + MemoryToIceAdapter& ReadOnlyPluginUser::iceAdapter() + { + return plugin->iceAdapter; + } + +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.h b/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.h new file mode 100644 index 0000000000000000000000000000000000000000..f56d66b0f35e173d3076dedb729a7dc77ab9bb6b --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/ReadOnlyPluginUser.h @@ -0,0 +1,61 @@ +#pragma once + +#include <RobotAPI/libraries/armem/server/forward_declarations.h> + +#include <RobotAPI/libraries/armem/client/plugins/PluginUser.h> +#include <RobotAPI/interface/armem/server/MemoryInterface.h> + +#include <ArmarXCore/core/ManagedIceObject.h> + + +namespace armarx::armem::server::plugins +{ + + class Plugin; + + + /** + * @brief Base class of memory server components. + * + * Implements the server ice interfaces using the ice adapter of the plugin. + */ + class ReadOnlyPluginUser : + virtual public ManagedIceObject + , virtual public ReadingMemoryInterface + , virtual public client::plugins::PluginUser + { + public: + + ReadOnlyPluginUser(); + virtual ~ReadOnlyPluginUser() override; + + + void setMemoryName(const std::string& memoryName); + + + // ReadingInterface interface + virtual armem::query::data::Result query( + const armem::query::data::Input& input, + const Ice::Current& = Ice::emptyCurrent) override; + + + public: + + Plugin& memoryServerPlugin(); + + server::wm::Memory& workingMemory(); + MemoryToIceAdapter& iceAdapter(); + + + private: + + plugins::Plugin* plugin = nullptr; + + }; + +} + +namespace armarx::armem::server +{ + using plugins::ReadOnlyPluginUser; +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp new file mode 100644 index 0000000000000000000000000000000000000000..f3da4f3ee885a2f1cda0a86ad195ae466f4fb9e5 --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.cpp @@ -0,0 +1,100 @@ +#include "ReadWritePluginUser.h" +#include "Plugin.h" + +#include <RobotAPI/libraries/armem/core/error.h> +#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h> + +#include <ArmarXCore/core/Component.h> +#include <ArmarXCore/core/exceptions/local/ExpressionException.h> + + + +namespace armarx::armem::server::plugins +{ + + ReadWritePluginUser::ReadWritePluginUser() + { + addPlugin(plugin); + } + + + ReadWritePluginUser::~ReadWritePluginUser() + { + } + + + void ReadWritePluginUser::setMemoryName(const std::string& memoryName) + { + plugin->setMemoryName(memoryName); + } + + + // WRITING + data::AddSegmentsResult ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, const Ice::Current&) + { + ARMARX_TRACE; + bool addCoreSegmentOnUsage = false; + return addSegments(input, addCoreSegmentOnUsage); + } + + data::AddSegmentsResult ReadWritePluginUser::addSegments(const data::AddSegmentsInput& input, bool addCoreSegments) + { + ARMARX_TRACE; + data::AddSegmentsResult result = iceAdapter().addSegments(input, addCoreSegments); + return result; + } + + + data::CommitResult ReadWritePluginUser::commit(const data::Commit& commitIce, const Ice::Current&) + { + ARMARX_TRACE; + return iceAdapter().commit(commitIce); + } + + + // READING + armem::query::data::Result ReadWritePluginUser::query(const armem::query::data::Input& input, const Ice::Current&) + { + ARMARX_TRACE; + return iceAdapter().query(input); + } + + + // LTM STORING + data::StoreResult ReadWritePluginUser::store(const data::StoreInput& input, const Ice::Current&) + { + ARMARX_TRACE; + return iceAdapter().store(input); + } + + + Plugin& ReadWritePluginUser::memoryServerPlugin() + { + return *plugin; + } + + + wm::Memory& ReadWritePluginUser::workingMemory() + { + return plugin->workingMemory; + } + + + MemoryToIceAdapter& ReadWritePluginUser::iceAdapter() + { + return plugin->iceAdapter; + } + + + bool ReadWritePluginUser::isLongtermMemoryEnabled() + { + return plugin->longtermMemoryEnabled; + } + + + ltm::mongodb::MemoryManager& ReadWritePluginUser::longtermMemoryManager() + { + return plugin->longtermMemoryManager; + } + +} diff --git a/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h new file mode 100644 index 0000000000000000000000000000000000000000..6736224199489fb171d49b092fd91e88e59fd9b0 --- /dev/null +++ b/source/RobotAPI/libraries/armem/server/plugins/ReadWritePluginUser.h @@ -0,0 +1,74 @@ +#pragma once + +#include <RobotAPI/libraries/armem/server/forward_declarations.h> + +#include <RobotAPI/libraries/armem/client/plugins/ListeningPluginUser.h> +#include <RobotAPI/interface/armem/server/MemoryInterface.h> + +#include <ArmarXCore/core/ManagedIceObject.h> + + +namespace armarx::armem::server::plugins +{ + + class Plugin; + + + /** + * @brief Base class of memory server components. + * + * Implements the server ice interfaces using the ice adapter of the plugin. + */ + class ReadWritePluginUser : + virtual public ManagedIceObject + , virtual public MemoryInterface + , virtual public client::plugins::ListeningPluginUser + { + public: + + ReadWritePluginUser(); + virtual ~ReadWritePluginUser() override; + + + void setMemoryName(const std::string& memoryName); + + + // WritingInterface interface + virtual data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, const Ice::Current& = Ice::emptyCurrent) override; + data::AddSegmentsResult addSegments(const data::AddSegmentsInput& input, bool addCoreSegments); + + virtual data::CommitResult commit(const data::Commit& commit, const Ice::Current& = Ice::emptyCurrent) override; + + + // ReadingInterface interface + virtual armem::query::data::Result query(const armem::query::data::Input& input, const Ice::Current& = Ice::emptyCurrent) override; + + + // StoringInterface interface + virtual data::StoreResult store(const data::StoreInput&, const Ice::Current& = Ice::emptyCurrent) override; + + + public: + + Plugin& memoryServerPlugin(); + + server::wm::Memory& workingMemory(); + MemoryToIceAdapter& iceAdapter(); + + bool isLongtermMemoryEnabled(); + server::ltm::mongodb::MemoryManager& longtermMemoryManager(); + + + private: + + plugins::Plugin* plugin = nullptr; + + }; + +} + +namespace armarx::armem::server +{ + using plugins::ReadWritePluginUser; +} + diff --git a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp index c56cc1077ef852c2a92d53cb3ae24f65a3974ccd..6e2bbb30bd3d2258796da97ce8a81b24224d201e 100644 --- a/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp +++ b/source/RobotAPI/libraries/armem_gui/MemoryViewer.cpp @@ -69,7 +69,6 @@ namespace armarx::armem::gui processQueryResultTimer->setInterval(1000 / 60); // Keep this stable. processQueryResultTimer->start(); - // Memory View memoryGroup = new armem::gui::MemoryGroupBox(); armarx::gui::replaceWidget(memoryGroupBox, memoryGroup, memoryGroupBoxParentLayout); @@ -133,7 +132,7 @@ namespace armarx::armem::gui void MemoryViewer::onConnect(ManagedIceObject& component) { - if (!mnsName.empty()) + if (not mnsName.empty()) { armem::mns::MemoryNameSystemInterfacePrx mnsProxy; component.getProxy(mnsProxy, mnsName); @@ -143,7 +142,7 @@ namespace armarx::armem::gui memoryReaders = mns.getAllReaders(update); } // DebugObserver is optional (check for null on every call) - if (!debugObserverName.empty()) + if (not debugObserverName.empty()) { component.getProxy(debugObserver, debugObserverName, false, "", false); } @@ -381,13 +380,13 @@ namespace armarx::armem::gui const armem::wm::Memory* data = getSingleMemoryData(selectedID.memoryName); if (data) { - if (!selectedID.hasEntityName()) + if (not selectedID.hasEntityName()) { return; } armem::MemoryID id = selectedID; const armem::wm::EntitySnapshot* snapshot = nullptr; - if (!id.hasTimestamp()) + if (not id.hasTimestamp()) { const armem::wm::Entity& entity = data->getEntity(id); if (entity.empty()) @@ -397,9 +396,9 @@ namespace armarx::armem::gui snapshot = &entity.getLatestSnapshot(); id.timestamp = snapshot->time(); } - if (!id.hasInstanceIndex()) + if (not id.hasInstanceIndex()) { - if (!snapshot) + if (not snapshot) { try { @@ -509,7 +508,14 @@ namespace armarx::armem::gui if (debugObserver) { - debugObserver->setDebugDatafield(Logging::tag.tagName, "GUI Update [ms]", new Variant(GuiUpdate.toMilliSecondsDouble())); + try + { + debugObserver->setDebugDatafield(Logging::tag.tagName, "GUI Update [ms]", new Variant(GuiUpdate.toMilliSecondsDouble())); + } + catch (const Ice::Exception&) + { + // Ignore ... + } } } diff --git a/source/RobotAPI/libraries/armem_gui/instance/ImageView.cpp b/source/RobotAPI/libraries/armem_gui/instance/ImageView.cpp index 05979fe8f669c3d0bc0cf30c7f7ea78004e49372..8c75fbd87d715add23701374643ff22d37f281ec 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/ImageView.cpp +++ b/source/RobotAPI/libraries/armem_gui/instance/ImageView.cpp @@ -13,7 +13,6 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see <http://www.gnu.org/licenses/>. * -* @package ArmarX:: * @author Rainer Kartmann ( rainer dot kartmann at kit dot edu) * @date 2021 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt diff --git a/source/RobotAPI/libraries/armem_gui/instance/ImageView.h b/source/RobotAPI/libraries/armem_gui/instance/ImageView.h index d684bbcccc37482f358d9350ba78812e9d065cc3..4b85e093a9ef522b7d125a6a0362a98dc4e11c52 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/ImageView.h +++ b/source/RobotAPI/libraries/armem_gui/instance/ImageView.h @@ -13,7 +13,6 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see <http://www.gnu.org/licenses/>. * -* @package ArmarX:: * @author Rainer Kartmann ( rainer dot kartmann at kit dot edu) * @date 2021 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt @@ -29,6 +28,9 @@ namespace armarx::armem::gui::instance { + /** + * @brief A widget drawing an image in itself. + */ class ImageView : public QWidget { Q_OBJECT diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp index 8fda3cc4bafd3458cc76f1829466afc8f84abeb9..da6ee43303128a3a73bf8db917301c41fe4b7695 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp +++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.cpp @@ -15,6 +15,8 @@ #include <QVBoxLayout> #include <SimoxUtility/algorithm/string.h> +#include <SimoxUtility/color/cmaps.h> +#include <SimoxUtility/math/SoftMinMax.h> #include <ArmarXCore/core/exceptions/local/ExpressionException.h> @@ -266,6 +268,7 @@ namespace armarx::armem::gui::instance aron::type::Descriptor type = static_cast<aron::type::Descriptor>(item->data(int(Columns::TYPE), Qt::UserRole).toInt()); switch (type) { + case aron::type::Descriptor::eImage: case aron::type::Descriptor::eIVTCByteImage: { if (const std::optional<aron::Path> path = getElementPath(item)) @@ -276,6 +279,26 @@ namespace armarx::armem::gui::instance { this->showImageView(path.value()); }); + + try + { + aron::datanavigator::NavigatorPtr element = currentInstance->data()->navigateAbsolute(path.value()); + if (auto imageData = aron::datanavigator::NDArrayNavigator::DynamicCast(element)) + { + const std::vector<int> shape = imageData->getDimensions(); + if (std::find(shape.begin(), shape.end(), 0) != shape.end()) + { + viewAction->setText(viewAction->text() + " (image is empty)"); + viewAction->setEnabled(false); + } + } + } + catch (const aron::error::AronException&) + { + } + catch (const armarx::LocalException&) + { + } } } break; @@ -395,11 +418,11 @@ namespace armarx::armem::gui::instance void InstanceView::showImageView(const aron::Path& elementPath) { - if (!currentInstance) + if (not currentInstance) { return; } - if (!imageView) + if (not imageView) { WidgetsWithToolbar* toolbar = new WidgetsWithToolbar(); @@ -425,15 +448,106 @@ namespace armarx::armem::gui::instance } + + QImage InstanceView::ImageView::convertDepth32ToRGB32( + const aron::datanavigator::NDArrayNavigator& aron) + { + const std::vector<int> shape = aron.getDimensions(); + ARMARX_CHECK_EQUAL(shape.size(), 3); + ARMARX_CHECK_EQUAL(shape.at(2), 4) << "Expected Depth32 image to have 4 bytes per pixel."; + + const int rows = shape.at(0); + const int cols = shape.at(1); + + // Rendering seems to be optimized for RGB32 + // rows go along 0 = height, cols go along 1 = width + QImage image(cols, rows, QImage::Format::Format_RGB32); + const float* data = reinterpret_cast<float*>(aron.getData()); + + auto updateLimits = [](float value, Limits& limits) + { + if (value > 0) // Exclude 0 from normalization (it may be only background) + { + limits.min = std::min(limits.min, value); + } + limits.max = std::max(limits.max, value); + }; + + // Find data range and adapt cmap. + Limits limits; + if (limitsHistory.empty()) + { + const float* sourceRow = data; + for (int row = 0; row < rows; ++row) + { + for (int col = 0; col < cols; ++col) + { + float value = sourceRow[col]; + updateLimits(value, limits); + } + sourceRow += cols; + } + cmap.set_vlimits(limits.min, limits.max); + } + // Only do it at the beginning and stop after enough samples were collected. + else if (limitsHistory.size() < limitsHistoryMaxSize) + { + simox::math::SoftMinMax softMin(0.25, limitsHistory.size()); + simox::math::SoftMinMax softMax(0.25, limitsHistory.size()); + + for (auto& l : limitsHistory) + { + softMin.add(l.min); + softMax.add(l.max); + } + + cmap.set_vlimits(softMin.getSoftMin(), softMax.getSoftMax()); + } + + // Update image + { + const float* sourceRow = data; + + const int bytesPerLine = image.bytesPerLine(); + uchar* targetRow = image.bits(); + + for (int row = 0; row < rows; ++row) + { + for (int col = 0; col < cols; ++col) + { + float value = sourceRow[col]; + simox::Color color = value <= 0 + ? simox::Color::white() + : cmap(value); + targetRow[col*4 + 0] = color.b; + targetRow[col*4 + 1] = color.g; + targetRow[col*4 + 2] = color.r; + targetRow[col*4 + 3] = color.a; + + updateLimits(value, limits); + } + sourceRow += cols; + targetRow += bytesPerLine; + } + } + if (limitsHistory.size() < limitsHistoryMaxSize) + { + limitsHistory.push_back(limits); + } + + return image; + } + + void InstanceView::updateImageView(const aron::datanavigator::DictNavigatorPtr& data) { using aron::datanavigator::NDArrayNavigator; - if (!imageView) + if (not imageView) { return; } - if (!data) + if (not data) { removeImageView(); return; @@ -460,48 +574,92 @@ namespace armarx::armem::gui::instance } NDArrayNavigator::PointerType imageData = NDArrayNavigator::DynamicCast(element); - if (!imageData) + if (not imageData) { showErrorMessage("Expected NDArrayNavigator, but got: " + simox::meta::get_type_name(element)); return; } - std::vector<int> shape = imageData->getDimensions(); + const std::vector<int> shape = imageData->getDimensions(); if (shape.size() != 3) { showErrorMessage("Expected array shape with 3 dimensions, but got: " + NDArrayNavigator::DimensionsToString(shape)); return; } + const int rows = shape.at(0); + const int cols = shape.at(1); + + using aron::typenavigator::ImagePixelType; + std::optional<ImagePixelType> pixelType; + try + { + pixelType = aron::typenavigator::ImageNavigator::pixelTypeFromName(imageData->getType()); + } + catch (const aron::error::AronException&) + { + } - QImage::Format format = QImage::Format::Format_Invalid; - switch (shape.at(2)) + bool clearLimitsHistory = true; + std::optional<QImage> image; + if (pixelType) + { + switch (pixelType.value()) + { + case ImagePixelType::Rgb24: + ARMARX_CHECK_EQUAL(shape.at(2), 3) << "Expected Rgb24 image to have 3 bytes per pixel."; + image = QImage(imageData->getData(), cols, rows, QImage::Format::Format_RGB888); + break; + + case ImagePixelType::Depth32: + image = imageView->convertDepth32ToRGB32(*imageData); + clearLimitsHistory = false; + break; + } + } + else { + QImage::Format format = QImage::Format_Invalid; + switch (shape.at(2)) + { case 1: format = QImage::Format::Format_Grayscale8; break; + case 3: format = QImage::Format::Format_RGB888; break; + default: showErrorMessage("Expected 1 or 3 elements in last dimension, but got shape: " + NDArrayNavigator::DimensionsToString(shape)); return; + } + image = QImage(imageData->getData(), cols, rows, format); } + ARMARX_CHECK(image.has_value()); + std::stringstream title; - title << "Image element '" << imageView->elementPath.toString() << "'"; // of entity instance " << currentInstance->id(); + title << "Image element '" << imageView->elementPath.toString() << "'"; // of entity instance " << currentInstance->id(); imageView->setTitle(QString::fromStdString(title.str())); - imageView->view->setImage(QImage(imageData->getData(), shape.at(0), shape.at(1), format)); + imageView->view->setImage(image.value()); + + if (clearLimitsHistory) + { + imageView->limitsHistory.clear(); + } } - InstanceView::ImageView::ImageView() + InstanceView::ImageView::ImageView() : + cmap(simox::color::cmaps::plasma().reversed()), + limitsHistoryMaxSize(32) { setLayout(new QHBoxLayout()); int margin = 2; layout()->setContentsMargins(margin, margin, margin, margin); - if (false) + if (/* DISABLES CODE */ (false)) { QFont font = this->font(); font.setPointSizeF(font.pointSize() * 0.75); diff --git a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h index 76a3988db8112f9b9437172710e05a900bb95f8f..ab434ba10c6084d4440f7ae2c08758f05f038ed4 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h +++ b/source/RobotAPI/libraries/armem_gui/instance/InstanceView.h @@ -1,10 +1,13 @@ #pragma once #include <optional> +#include <deque> #include <QWidget> #include <QGroupBox> +#include <SimoxUtility/color/ColorMap.h> + #include <ArmarXCore/core/logging/Logging.h> #include <RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h> @@ -104,10 +107,26 @@ namespace armarx::armem::gui::instance public: ImageView(); + QImage convertDepth32ToRGB32(const aron::datanavigator::NDArrayNavigator& aron); + instance::ImageView* view; aron::Path elementPath; WidgetsWithToolbar* toolbar; + + + struct Limits + { + float min = std::numeric_limits<float>::max(); + float max = -std::numeric_limits<float>::max(); + }; + + /// Color map to visualize depth images. + simox::ColorMap cmap; + /// History over first n extremal depth values used to calibrate the colormap. + std::deque<Limits> limitsHistory; + /// In this context, n. + const size_t limitsHistoryMaxSize; }; ImageView* imageView = nullptr; diff --git a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/DataDisplayVisitor.cpp b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/DataDisplayVisitor.cpp index f41f5d4cb447e9571d5145f26af5cbff6c9db2cf..af2192c2a36de2c89fcda1caa4f556cd5781315f 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/DataDisplayVisitor.cpp +++ b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/DataDisplayVisitor.cpp @@ -68,7 +68,8 @@ namespace armarx::aron bool DataDisplayVisitor::visit(NDArrayDataNavigator& n) { - value << "shape " << aron::datanavigator::NDArrayNavigator::DimensionsToString(n.getDimensions()); + value << "shape " << aron::datanavigator::NDArrayNavigator::DimensionsToString(n.getDimensions()) + << ", type '" << n.getType() << "'"; return false; } diff --git a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp index eb1cda5fd7ffd8b4b06f7286d7292e3a058cdc35..16c54007a40ad0f04d85c3bc4e9ecebcb4e74416 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp +++ b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.cpp @@ -140,6 +140,14 @@ namespace armarx::aron return false; } + bool TypedDataDisplayVisitor::visit(ImageNavigator&, NDArrayDataNavigator& data) + { + // aron::typenavigator::ImagePixelType pixelType = ImageNavigator::pixelTypeFromName(data.getType()); + //value << DataDisplayVisitor::getValue(data) << " pixel type: " << data.getType()"; + value << DataDisplayVisitor::getValue(data); + return false; + } + bool TypedDataDisplayVisitor::visit(IVTCByteImageTypeNavigator&, NDArrayDataNavigator& data) { value << DataDisplayVisitor::getValue(data); diff --git a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.h b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.h index 87220babb8b64d78d7db6bfb1fe7cce41b070fd6..4bf2ec5d8cd149eb40ad1f9a0d3a655424183e72 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.h +++ b/source/RobotAPI/libraries/armem_gui/instance/display_visitors/TypedDataDisplayVisitor.h @@ -44,6 +44,7 @@ namespace armarx::aron bool visit(EigenMatrixTypeNavigator&, NDArrayDataNavigator& data) override; bool visit(EigenQuaternionTypeNavigator&, NDArrayDataNavigator& data) override; + bool visit(ImageNavigator&, NDArrayDataNavigator& data) override; bool visit(IVTCByteImageTypeNavigator&, NDArrayDataNavigator& data) override; bool visit(OpenCVMatTypeNavigator&, NDArrayDataNavigator& data) override; bool visit(PCLPointCloudTypeNavigator&, NDArrayDataNavigator& data) override; diff --git a/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp b/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp index c548192cb7a98a390f708c8bd7789e51e63089cc..e8ece36b766dec34b3bce7325b7a62e78513bbc2 100644 --- a/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp +++ b/source/RobotAPI/libraries/armem_gui/instance/sanitize_typename.cpp @@ -13,12 +13,6 @@ const std::string armarx::armem::gui::instance::sanitizedMemoryIDTypeName = "Mem namespace { - std::string remove_prefix(const std::string& string, const std::string& prefix) - { - return simox::alg::starts_with(string, prefix) - ? string.substr(prefix.size(), std::string::npos) - : string; - } std::string remove_wrap(const std::string& string, const std::string& prefix, const std::string& suffix) { if (simox::alg::starts_with(string, prefix) && simox::alg::ends_with(string, suffix)) @@ -58,7 +52,7 @@ std::string armarx::armem::gui::instance::sanitizeTypeName(const std::string& ty } - n = remove_prefix(n, "Aron"); + n = simox::alg::remove_prefix(n, "Aron"); n = remove_wrap(n, "Object<", ">"); if (true) diff --git a/source/RobotAPI/libraries/aron/core/CMakeLists.txt b/source/RobotAPI/libraries/aron/core/CMakeLists.txt index c5282fb54aba97b583f15f2df1876c0dde3e4ead..6fb2477169dd25daf0c77564e49d2e737825ef7c 100644 --- a/source/RobotAPI/libraries/aron/core/CMakeLists.txt +++ b/source/RobotAPI/libraries/aron/core/CMakeLists.txt @@ -45,6 +45,7 @@ set(LIB_FILES navigator/type/ndarray/NDArray.cpp navigator/type/ndarray/EigenMatrix.cpp navigator/type/ndarray/EigenQuaternion.cpp + navigator/type/ndarray/Image.cpp navigator/type/ndarray/IVTCByteImage.cpp navigator/type/ndarray/OpenCVMat.cpp navigator/type/ndarray/PCLPointCloud.cpp @@ -102,6 +103,7 @@ set(LIB_FILES codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.cpp codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.cpp codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.cpp + codegenerator/codeWriter/cpp/serializer/ndarray/Image.cpp codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.cpp codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.cpp codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.cpp @@ -167,6 +169,7 @@ set(LIB_HEADERS navigator/type/ndarray/EigenMatrix.h navigator/type/ndarray/EigenQuaternion.h navigator/type/ndarray/IVTCByteImage.h + navigator/type/ndarray/Image.h navigator/type/ndarray/OpenCVMat.h navigator/type/ndarray/PCLPointCloud.h navigator/type/ndarray/Position.h @@ -248,6 +251,7 @@ set(LIB_HEADERS codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.h codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.h codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.h + codegenerator/codeWriter/cpp/serializer/ndarray/Image.h codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.h codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.h codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.h diff --git a/source/RobotAPI/libraries/aron/core/Config.h b/source/RobotAPI/libraries/aron/core/Config.h index 7db99c2f1aaa298eb50f076a371677408dac113e..a8c7d0fb044619530635da4c3cb709f579fe7757 100644 --- a/source/RobotAPI/libraries/aron/core/Config.h +++ b/source/RobotAPI/libraries/aron/core/Config.h @@ -89,6 +89,7 @@ namespace armarx RUN_ARON_MACRO(NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(EigenMatrix, eigenmatrix, EIGEN_MATRIX) \ RUN_ARON_MACRO(EigenQuaternion, eigenquaternion, EIGEN_QUATERNION) \ + RUN_ARON_MACRO(Image, image, IMAGE) \ RUN_ARON_MACRO(IVTCByteImage, ivtcbyteimage, IVT_CBYTE_IMAGE) \ RUN_ARON_MACRO(OpenCVMat, opencvmat, OPENCV_MAT) \ RUN_ARON_MACRO(PCLPointCloud, pclpointcloud, PCL_POINTCLOUD) \ @@ -168,6 +169,7 @@ namespace armarx RUN_ARON_MACRO(NDArray, ndarray, NDARRAY, NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(EigenMatrix, eigenmatrix, EIGEN_MATRIX, NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(EigenQuaternion, eigenmatrix, EIGEN_MATRIX, NDArray, ndarray, NDARRAY) \ + RUN_ARON_MACRO(Image, image, IMAGE, NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(IVTCByteImage, ivtcbyteimage, IVT_CBYTE_IMAGE, NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(OpenCVMat, opencvmat, OPENCV_MAT, NDArray, ndarray, NDARRAY) \ RUN_ARON_MACRO(PCLPointCloud, pclpointcloud, PCL_POINTCLOUD, NDArray, ndarray, NDARRAY) \ diff --git a/source/RobotAPI/libraries/aron/core/Randomizer.h b/source/RobotAPI/libraries/aron/core/Randomizer.h index 00f355baa9c01e66792a886b027ad4186b808016..170f4b2b8b1a471a09ff0e4cf9b51a05c1470fe7 100644 --- a/source/RobotAPI/libraries/aron/core/Randomizer.h +++ b/source/RobotAPI/libraries/aron/core/Randomizer.h @@ -24,8 +24,10 @@ #pragma once // STD/STL +#include <map> #include <memory> #include <numeric> +#include <set> // ArmarX #include <RobotAPI/libraries/aron/core/Exception.h> @@ -152,6 +154,12 @@ namespace armarx::aron t->setTypename(type); return t; } + case type::Descriptor::eImage: + { + auto t = std::make_shared<typenavigator::ImageNavigator>(); + auto type = getRandomKey(typenavigator::ImageNavigator::pixelTypeNames()); + return t; + } case type::Descriptor::eIVTCByteImage: { auto t = std::make_shared<typenavigator::IVTCByteImageNavigator>(); @@ -359,8 +367,8 @@ case type::Descriptor::e##upperType: \ return vec.at(i); } - template <class T> - std::string getRandomKey(const std::map<std::string, T>& m) const + template <class ValueT> + std::string getRandomKey(const std::map<std::string, ValueT>& m) const { std::vector<std::string> keys; for (const auto [k, _] : m) @@ -370,6 +378,16 @@ case type::Descriptor::e##upperType: \ return getRandomElement(keys); } + std::string getRandomKey(const std::set<std::string>& set) const + { + std::vector<std::string> keys; + for (const auto k : set) + { + keys.push_back(k); + } + return getRandomElement(keys); + } + bool fiftyPercentChance() const { return generateRandom(2, 0); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/AllSerializers.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/AllSerializers.h index dd01bd127edd43a72cdafa370d96b68d8ebd77fa..7e1934e88f17b309ce3117d4312557359c300c07 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/AllSerializers.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/AllSerializers.h @@ -8,6 +8,7 @@ #include "ndarray/NDArray.h" #include "ndarray/EigenMatrix.h" #include "ndarray/EigenQuaternion.h" +#include "ndarray/Image.h" #include "ndarray/IVTCByteImage.h" #include "ndarray/OpenCVMat.h" #include "ndarray/PCLPointCloud.h" diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.cpp index 5169a4fcc46d3142ce61df9d717cc03942f62781..7cc42a41503cf690be9fccab82acd41b342cfb7b 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.cpp @@ -23,21 +23,22 @@ // STD/STL -// Header -#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h> +#include "Serializer.h" +#include "SerializerFactory.h" + +#include <SimoxUtility/meta/type_name.h> +#include <SimoxUtility/algorithm/string.h> -// ArmarX -#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/SerializerFactory.h> namespace armarx::aron::cppserializer { // constantes - const std::string Serializer::ARON_DATA_NAME = simox::meta::get_type_name(typeid(armarx::aron::data::AronData)); + const std::string Serializer::ARON_DATA_NAME = simox::meta::get_type_name<armarx::aron::data::AronData>(); const std::string Serializer::ARON_DATA_PTR_NAME = Serializer::ARON_DATA_NAME + "::PointerType"; const std::string Serializer::READ_START_RETURN_TYPE_ACCESSOR = "_return_type"; - const std::string Serializer::ARON_TYPE_NAME = simox::meta::get_type_name(typeid(armarx::aron::type::AronType)); + const std::string Serializer::ARON_TYPE_NAME = simox::meta::get_type_name<armarx::aron::type::AronType>(); const std::string Serializer::ARON_TYPE_PTR_NAME = Serializer::ARON_TYPE_NAME + "::PointerType"; const std::map<std::string, std::string> Serializer::ESCAPE_ACCESSORS = @@ -263,7 +264,7 @@ namespace armarx::aron::cppserializer } else { - b->addLine("// Ressetting soft the type " + ExtractCppTypename(typenavigator)); + b->addLine("// Resetting soft the type " + ExtractCppTypename(typenavigator)); } switch (typenavigator->getMaybe()) @@ -310,7 +311,7 @@ namespace armarx::aron::cppserializer } else { - b->addLine("// Ressetting hard the type " + ExtractCppTypename(typenavigator)); + b->addLine("// Resetting hard the type " + ExtractCppTypename(typenavigator)); } switch (typenavigator->getMaybe()) diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h index e7a544b8fb8342c0b83b0c27e4ecaf35e82ba933..0bee9f4be10ef71312e56e89122fc1ef100bca18 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h @@ -23,27 +23,21 @@ #pragma once -// STD/STL -#include <memory> -#include <vector> -#include <map> -#include <string> - -// Simox -#include <SimoxUtility/meta/type_name.h> -#include <SimoxUtility/algorithm/string.h> -#include <SimoxUtility/algorithm/vector.hpp> +#include <RobotAPI/interface/aron.h> +#include <RobotAPI/libraries/aron/core/Exception.h> +#include <RobotAPI/libraries/aron/core/navigator/type/Navigator.h> -// ArmarX #include <ArmarXCore/libraries/cppgen/CppBlock.h> #include <ArmarXCore/libraries/cppgen/CppField.h> #include <ArmarXCore/libraries/cppgen/CppCtor.h> #include <ArmarXCore/libraries/cppgen/CppMethod.h> #include <ArmarXCore/libraries/cppgen/CppClass.h> -#include <RobotAPI/interface/aron.h> -#include <RobotAPI/libraries/aron/core/Exception.h> -#include <RobotAPI/libraries/aron/core/navigator/type/Navigator.h> +#include <memory> +#include <map> +#include <string> +#include <vector> + namespace armarx::aron::cppserializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.cpp index f494c591c7828dbd4435a02336a03d52361620ad..4bb11ad7cafabe9d329217cf003c3b7aa82a61bd 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.cpp @@ -24,14 +24,18 @@ // Header #include "Dict.h" +#include <SimoxUtility/meta/type_name.h> + namespace armarx::aron::cppserializer::serializer { // constructors DictSerializer::DictSerializer(const typenavigator::DictNavigatorPtr& e) : - detail::ContainerSerializerBase<typenavigator::DictNavigator, DictSerializer>("std::map<std::string, " + FromAronTypeNaviagtorPtr(e->getAcceptedType())->getFullCppTypename() + ">", - simox::meta::get_type_name(typeid(data::AronDict)), - simox::meta::get_type_name(typeid(type::AronDict)), e) + detail::ContainerSerializerBase<typenavigator::DictNavigator, DictSerializer>( + "std::map<std::string, " + FromAronTypeNaviagtorPtr(e->getAcceptedType())->getFullCppTypename() + ">", + simox::meta::get_type_name<data::AronDict>(), + simox::meta::get_type_name<type::AronDict>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.h index 9bd48144aeb8cdf578ac4d8c491343f539e0bcc8..a8f4734f4f5c0f0050dd9758bb9fa6e36637a2a6 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Dict.h @@ -23,15 +23,8 @@ #pragma once -// STD/STL -#include <string> -#include <map> - -// Base Class -#include "../detail/ContainerSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/Dict.h" +#include <RobotAPI/libraries/aron/core/navigator/type/container/Dict.h> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h> namespace armarx::aron::cppserializer::serializer diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.cpp index 8483320c75efeca4c8cf573358d04d0539fb36d4..53e8bbcb28809e8a077e0724b05d26469040e875 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.cpp @@ -24,13 +24,18 @@ // Header #include "List.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors ListSerializer::ListSerializer(const typenavigator::ListNavigatorPtr& e) : - detail::ContainerSerializerBase<typenavigator::ListNavigator, ListSerializer>("std::vector<" + FromAronTypeNaviagtorPtr(e->getAcceptedType())->getFullCppTypename() + ">", - simox::meta::get_type_name(typeid(data::AronList)), - simox::meta::get_type_name(typeid(type::AronList)), e) + detail::ContainerSerializerBase<typenavigator::ListNavigator, ListSerializer>( + "std::vector<" + FromAronTypeNaviagtorPtr(e->getAcceptedType())->getFullCppTypename() + ">", + simox::meta::get_type_name<data::AronList>(), + simox::meta::get_type_name<type::AronList>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.h index 6b8afaabeef27186acee30d0167be5f1632d1ad7..6358a08ce649a5d482d9906af861d1e5bb8841a5 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/List.h @@ -23,15 +23,9 @@ #pragma once -// STD/STL -#include <string> -#include <vector> +#include <RobotAPI/libraries/aron/core/navigator/type/container/List.h> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h> -// Base Class -#include "../detail/ContainerSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/List.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.cpp index 49e06676e286dc773da88d6c12ab50062e2f1eb5..8b2bea70b9cbf9506e59fd3c56f04044400db9c7 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.cpp @@ -24,14 +24,18 @@ // Header #include "Object.h" +#include <SimoxUtility/meta/type_name.h> + namespace armarx::aron::cppserializer::serializer { // constructors ObjectSerializer::ObjectSerializer(const typenavigator::ObjectNavigatorPtr& e) : - detail::ContainerSerializerBase<typenavigator::ObjectNavigator, ObjectSerializer>(e->getObjectName(), - simox::meta::get_type_name(typeid(data::AronDict)), - simox::meta::get_type_name(typeid(type::AronObject)), e) + detail::ContainerSerializerBase<typenavigator::ObjectNavigator, ObjectSerializer>( + e->getObjectName(), + simox::meta::get_type_name<data::AronDict>(), + simox::meta::get_type_name<type::AronObject>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.h index d04a44557a19b5337f8678b788c68361a7b0ff0a..222e37c166b790cc3092a2c8a4fc04f6cd5ec892 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Object.h @@ -23,15 +23,8 @@ #pragma once -// STD/STL -#include <string> -#include <map> - -// Base Class -#include "../detail/ContainerSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/Object.h" +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h> namespace armarx::aron::cppserializer::serializer diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.cpp index c465862acc74bac36c8f9f8e1c1cbf3b341890e3..ab4013664318c76526ecbebec1ac4c90ade479a1 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.cpp @@ -24,13 +24,17 @@ // Header #include "Pair.h" +#include <SimoxUtility/meta/type_name.h> + namespace armarx::aron::cppserializer::serializer { PairSerializer::PairSerializer(const typenavigator::PairNavigatorPtr& e) : - detail::ContainerSerializerBase<typenavigator::PairNavigator, PairSerializer>("std::pair<" + ExtractCppTypename(e->getFirstAcceptedType()) + ", " + ExtractCppTypename(e->getSecondAcceptedType()) + ">", - simox::meta::get_type_name(typeid(data::AronList)), - simox::meta::get_type_name(typeid(type::AronPair)), e) + detail::ContainerSerializerBase<typenavigator::PairNavigator, PairSerializer>( + "std::pair<" + ExtractCppTypename(e->getFirstAcceptedType()) + ", " + ExtractCppTypename(e->getSecondAcceptedType()) + ">", + simox::meta::get_type_name<data::AronList>(), + simox::meta::get_type_name<type::AronPair>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.h index a7ef2495bcd4939820808a1298dcda92d1c9e12c..fab1eb592ceb5c0f1b373a3170f0908953545be4 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Pair.h @@ -23,15 +23,9 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/navigator/type/container/Pair.h> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h> -// Base Class -#include "../detail/ContainerSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/Pair.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.cpp index a6b5e2080e97d0514cbb4bbda9131adb68a3a860..188ff3a449994c71109d1fd7f1e213c78c6189f8 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.cpp @@ -24,13 +24,17 @@ // Header #include "Tuple.h" +#include <SimoxUtility/meta/type_name.h> + namespace armarx::aron::cppserializer::serializer { TupleSerializer::TupleSerializer(const typenavigator::TupleNavigatorPtr& e) : - detail::ContainerSerializerBase<typenavigator::TupleNavigator, TupleSerializer>("std::tuple<" + simox::alg::join(ExtractCppTypenames(e->getAcceptedTypes()), ", ") + ">", - simox::meta::get_type_name(typeid(data::AronList)), - simox::meta::get_type_name(typeid(type::AronTuple)), e) + detail::ContainerSerializerBase<typenavigator::TupleNavigator, TupleSerializer>( + "std::tuple<" + simox::alg::join(ExtractCppTypenames(e->getAcceptedTypes()), ", ") + ">", + simox::meta::get_type_name<data::AronList>(), + simox::meta::get_type_name<type::AronTuple>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.h index d8ec0bf428b98cc8290600b7556fc503d4acf5ee..e8039607eedb467608482459770e40a345d74157 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/container/Tuple.h @@ -23,15 +23,9 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/navigator/type/container/Tuple.h> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h> -// Base Class -#include "../detail/ContainerSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/Tuple.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h index d2ca8f77efce232d34c15c7d9f7cd24513a46f53..baf4be57effcf3bff72b53ad4bf5a668ee471990 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/ContainerSerializerBase.h @@ -23,15 +23,8 @@ #pragma once -// STD/STL -#include <memory> -#include <string> -#include <unordered_map> - -// Base class #include "SerializerBase.h" -// ArmarX namespace armarx::aron::cppserializer::detail { @@ -40,9 +33,8 @@ namespace armarx::aron::cppserializer::detail public SerializerBase<TypenavigatorT, DerivedT> { public: - ContainerSerializerBase(const std::string& cppName, const std::string& aronDataTypename, const std::string& aronTypeTypename, const typename TypenavigatorT::PointerType& t) : - SerializerBase<TypenavigatorT, DerivedT>(cppName, aronDataTypename, aronTypeTypename, t) - { - } + + using SerializerBase<TypenavigatorT, DerivedT>::SerializerBase; + }; } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h index f0af4cfdd143da41629057e68a1291643b079eec..7acb76328abdc2be4ee0b08577e546900c4e3d46 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h @@ -23,15 +23,8 @@ #pragma once -// STD/STL -#include <memory> -#include <string> -#include <unordered_map> - -// Base class #include "SerializerBase.h" -// ArmarX namespace armarx::aron::cppserializer::detail { @@ -40,7 +33,12 @@ namespace armarx::aron::cppserializer::detail public SerializerBase<TypenavigatorT, DerivedT> { public: - NDArraySerializerBase(const std::string& cppName, const std::string& aronDataTypename, const std::string& aronTypeTypename, const typename TypenavigatorT::PointerType& t) : + + NDArraySerializerBase( + const std::string& cppName, + const std::string& aronDataTypename, + const std::string& aronTypeTypename, + const typename TypenavigatorT::PointerType& t) : SerializerBase<TypenavigatorT, DerivedT>(cppName, aronDataTypename, aronTypeTypename, t) {} diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h index cf84eec049e341a83318dd3544fca0684e64236a..b20979f807c42981c0f9de6bf3106506424f9ea0 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h @@ -23,15 +23,10 @@ #pragma once -// STD/STL -#include <memory> -#include <string> -#include <unordered_map> - -// Base class #include "SerializerBase.h" -// ArmarX +#include <string> + namespace armarx::aron::cppserializer::detail { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h index 4b2dd5f8918bf0859b9e577d58dcd357a2fe7e37..92fde748539283fa35cb3ab858155d3e4f88d154 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h @@ -23,15 +23,11 @@ #pragma once -// STD/STL +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/Serializer.h> + #include <memory> #include <string> -#include <unordered_map> - -// Base class -#include "../Serializer.h" -// ArmarX namespace armarx::aron::cppserializer::detail { @@ -44,7 +40,11 @@ namespace armarx::aron::cppserializer::detail using TypenavigatorType = TypenavigatorT; public: - SerializerBase(const std::string& cppName, const std::string& aronDataTypename, const std::string& aronTypeTypename, const typename TypenavigatorType::PointerType& t) : + SerializerBase( + const std::string& cppName, + const std::string& aronDataTypename, + const std::string& aronTypeTypename, + const typename TypenavigatorType::PointerType& t) : Serializer(cppName, aronDataTypename, aronTypeTypename), typenavigator(t) { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.cpp index 2ae444db3f04f48865dc7e9842d5ae521e17cd0b..dc00ff9b0271b310b91be4656721eb6ed98039b1 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.cpp @@ -24,13 +24,18 @@ // Header #include "IntEnum.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors IntEnumSerializer::IntEnumSerializer(const typenavigator::IntEnumNavigatorPtr& e) : - detail::SerializerBase<typenavigator::IntEnumNavigator, IntEnumSerializer>(e->getEnumName(), - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronIntEnum)), e) + detail::SerializerBase<typenavigator::IntEnumNavigator, IntEnumSerializer>( + e->getEnumName(), + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronIntEnum>(), + e) { } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.h index af290bfe03f46cd5faa5cad4e218a6e3f5bd9e65..ce5feac09dcd1c2d802b176cb2d553d48adf7170 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/enum/IntEnum.h @@ -23,15 +23,11 @@ #pragma once -// STD/STL -#include <string> -#include <map> - -// Base Class -#include "../detail/SerializerBase.h" +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/enum/IntEnum.h> -// ArmarX -#include "../../../../../navigator/type/enum/IntEnum.h" +#include <map> +#include <string> namespace armarx::aron::cppserializer::serializer diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.cpp index c59e70d713528f0db11d4bf0d2212f3f3b53de77..54a4668819869c3305d79a98531cd8cdd348bf14 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.cpp @@ -24,6 +24,9 @@ // Header #include "EigenMatrix.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { @@ -40,13 +43,27 @@ namespace armarx::aron::cppserializer::serializer // constructors EigenMatrixSerializer::EigenMatrixSerializer(const typenavigator::EigenMatrixNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::EigenMatrixNavigator, EigenMatrixSerializer>("Eigen::Matrix<" + ACCEPTED_TYPES.at(n->getTypename()).first + ", " + std::to_string(n->getRows()) + ", " + std::to_string(n->getCols()) + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronEigenMatrix)), n) + detail::NDArraySerializerBase<typenavigator::EigenMatrixNavigator, EigenMatrixSerializer>( + "Eigen::Matrix<" + ACCEPTED_TYPES.at(n->getTypename()).first + ", " + std::to_string(n->getRows()) + ", " + std::to_string(n->getCols()) + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronEigenMatrix>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } + CppBlockPtr EigenMatrixSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + block->addLine(accessor + ".setZero();"); + return this->ResolveMaybeResetHardBlock(accessor, block, this->typenavigator); + } + + CppBlockPtr EigenMatrixSerializer::getResetSoftBlock(const std::string& accessor) const + { + return getResetHardBlock(accessor); + } + CppBlockPtr EigenMatrixSerializer::getWriteTypeBlock(const std::string& accessor) const { CppBlockPtr b = CppBlockPtr(new CppBlock()); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.h index 13e435bfeed1161f6a349eae2507828b6a39a31c..1885efb76b1b53ab533d83fd4b071592fa040aeb 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenMatrix.h @@ -23,20 +23,14 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/EigenMatrix.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <map> -// ArmarX -#include "../../../../../navigator/type/ndarray/EigenMatrix.h" namespace armarx::aron::cppserializer::serializer { - class EigenMatrixSerializer; - typedef std::shared_ptr<EigenMatrixSerializer> EigenMatrixSerializerPtr; class EigenMatrixSerializer : virtual public detail::NDArraySerializerBase<typenavigator::EigenMatrixNavigator, EigenMatrixSerializer> @@ -46,6 +40,8 @@ namespace armarx::aron::cppserializer::serializer EigenMatrixSerializer(const typenavigator::EigenMatrixNavigatorPtr&); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string&) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string&) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; virtual CppBlockPtr getReadBlock(const std::string&) const override; diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.cpp index 6594fd20bc9d0915cfb95ed45a1fe821f44a58eb..41e3faf1bd3797cc721b27bfa49e0b70740c76b2 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.cpp @@ -24,6 +24,9 @@ // Header #include "EigenQuaternion.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { @@ -35,13 +38,27 @@ namespace armarx::aron::cppserializer::serializer // constructors EigenQuaternionSerializer::EigenQuaternionSerializer(const typenavigator::EigenQuaternionNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::EigenQuaternionNavigator, EigenQuaternionSerializer>("Eigen::Quaternion<" + ACCEPTED_TYPES.at(n->getTypename()).first + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronEigenQuaternion)), n) + detail::NDArraySerializerBase<typenavigator::EigenQuaternionNavigator, EigenQuaternionSerializer>( + "Eigen::Quaternion<" + ACCEPTED_TYPES.at(n->getTypename()).first + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronEigenQuaternion>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } + CppBlockPtr EigenQuaternionSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + block->addLine(accessor + ".setIdentity();"); + return this->ResolveMaybeResetHardBlock(accessor, block, this->typenavigator); + } + + CppBlockPtr EigenQuaternionSerializer::getResetSoftBlock(const std::string& accessor) const + { + return getResetHardBlock(accessor); + } + CppBlockPtr EigenQuaternionSerializer::getWriteTypeBlock(const std::string& accessor) const { CppBlockPtr b = CppBlockPtr(new CppBlock()); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.h index 9a42c8cf67b3c67f9cb5664bd69a8ae2fc8d24dd..8f471d8f3e2570d51fac512d14b1b06bbbed692d 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/EigenQuaternion.h @@ -23,33 +23,29 @@ #pragma once -// STD/STL -#include <string> -#include <map> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/EigenQuaternion.h> + +#include <map> -// ArmarX -#include "../../../../../navigator/type/ndarray/EigenQuaternion.h" namespace armarx::aron::cppserializer::serializer { - class EigenQuaternionSerializer; - typedef std::shared_ptr<EigenQuaternionSerializer> EigenQuaternionSerializerPtr; - class EigenQuaternionSerializer : virtual public detail::NDArraySerializerBase<typenavigator::EigenQuaternionNavigator, EigenQuaternionSerializer> { public: - using PointerType = EigenQuaternionSerializerPtr; + using PointerType = std::shared_ptr<EigenQuaternionSerializer>; public: // constructors EigenQuaternionSerializer(const typenavigator::EigenQuaternionNavigatorPtr&); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string&) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string&) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; virtual CppBlockPtr getReadBlock(const std::string&) const override; diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.cpp index 4a986761bd57f9b7b2a2810fab8c19e5ffb43067..94e7bfe85af077cfaa9c69aa5b8a51869f7b5c60 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.cpp @@ -24,6 +24,9 @@ // Header #include "IVTCByteImage.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { @@ -36,9 +39,11 @@ namespace armarx::aron::cppserializer::serializer // constructors IVTCByteImageSerializer::IVTCByteImageSerializer(const typenavigator::IVTCByteImageNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::IVTCByteImageNavigator, IVTCByteImageSerializer>("CByteImage", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronIVTCByteImage)), n) + detail::NDArraySerializerBase<typenavigator::IVTCByteImageNavigator, IVTCByteImageSerializer>( + "CByteImage", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronIVTCByteImage>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); if (typenavigator->getMaybe() == type::Maybe::eNone or typenavigator->getMaybe() == type::Maybe::eOptional) diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.h index 1be69bdef6815d3c09f7d0cf16a06d2dda5cd81e..3e978ca5f69441e960e2b221f3a06779d0f1d7b7 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/IVTCByteImage.h @@ -23,15 +23,11 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/IVTCByteImage.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <map> -// ArmarX -#include "../../../../../navigator/type/ndarray/IVTCByteImage.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.cpp new file mode 100644 index 0000000000000000000000000000000000000000..771ffb4f301fb705b19474f5a9c28ef8da5e3395 --- /dev/null +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.cpp @@ -0,0 +1,261 @@ +/* + * This file is part of ArmarX. + * + * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), + * Karlsruhe Institute of Technology (KIT), all rights reserved. + * + * ArmarX is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * ArmarX is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + * @author Rainer Kartmann (rainer dot kartmann at kit dot edu) + * @copyright http://www.gnu.org/licenses/gpl-2.0.txt + * GNU General Public License + */ + +// Header +#include "Image.h" + +#include <SimoxUtility/meta/type_name.h> + + +namespace armarx::aron::cppserializer::serializer +{ + + const std::map<typenavigator::ImagePixelType, std::string> + ImageSerializer::pixelTypeMap = + { + { typenavigator::ImagePixelType::Rgb24, "CV_8UC3" }, + { typenavigator::ImagePixelType::Depth32, "CV_32FC1"}, + }; + + + // constructors + ImageSerializer::ImageSerializer(const typenavigator::ImageNavigatorPtr& n) : + detail::NDArraySerializerBase<typenavigator::ImageNavigator, ImageSerializer>( + "cv::Mat", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronImage>(), + n) + { + ARMARX_CHECK_NOT_NULL(typenavigator); + } + + + CppBlockPtr ImageSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); + + std::string typeConstant; + { + if (auto it = pixelTypeMap.find(typenavigator->getPixelType()); it != pixelTypeMap.end()) + { + typeConstant = it->second; + } + else + { + std::stringstream ss; + ss << "Pixel type '" << static_cast<int>(typenavigator->getPixelType()) << "' " + << "is not mapped to an OpenCV pixel type."; + throw error::AronException("ImageSerializer", __FUNCTION__, ss.str()); + } + } + + block_if_data->addLine(accessor + ".create(0, 0, " + typeConstant + ");"); + return this->ResolveMaybeResetHardBlock(accessor, block_if_data, this->typenavigator); + } + + + CppBlockPtr ImageSerializer::getResetSoftBlock(const std::string& accessor) const + { + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); + + block_if_data->addLine(accessor + " = 0;"); + + return ResolveMaybeResetSoftBlock(accessor, block_if_data, typenavigator); + } + + + CppBlockPtr ImageSerializer::getWriteTypeBlock(const std::string& accessor) const + { + CppBlockPtr b = std::make_shared<CppBlock>(); + + std::string typeName; + switch (typenavigator->getPixelType()) + { +#define CASE( typeConstant ) \ +case typeConstant : \ + typeName = "::armarx::aron::typenavigator::ImageNavigator::pixelTypeToName( " #typeConstant " )"; \ + break; + + CASE(::armarx::aron::typenavigator::ImagePixelType::Rgb24) + CASE(::armarx::aron::typenavigator::ImagePixelType::Depth32) + +#undef CASE + } + + b->addLine("w.writeImage({" + typeName + ", " + MAYBE_TO_STRING(typenavigator->getMaybe()) + "}); // of " + accessor); + return b; + } + + + CppBlockPtr ImageSerializer::getWriteBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + + std::string escaped_accessor = EscapeAccessor(accessor); + std::string accessor_shape = "shape"; + + block->addLine("std::vector<int> " + accessor_shape + "(" + accessor + ".size.p, " + accessor + ".size.p + " + accessor + ".dims);"); + block->addLine(accessor_shape + ".push_back(" + accessor + nextEl() + "elemSize());"); + + +#if 0 // Target code: + std::string type; + switch (the_depth32_image.type()) + { + case CV_8UC3: + type = ::armarx::aron::typenavigator::ImageNavigator::pixelTypeToName(::armarx::aron::typenavigator::ImagePixelType::RGB24); + break; + case CV_32FC1: + type = ::armarx::aron::typenavigator::ImageNavigator::pixelTypeToName(::armarx::aron::typenavigator::ImagePixelType::DEPTH32); + break; + default: + { + std::stringstream ss; + ss << "OpenCV image type " << the_depth32_image.type() << " cannot be serialized."; + throw ::armarx::aron::error::AronException("ImageTest", __FUNCTION__, ss.str()); + } + } +#endif + + block->addLine("std::string arrayType;"); + block->addLine("switch (" + accessor + ".type())"); + { + CppBlockPtr block_switch = std::make_shared<CppBlock>(); + +#define CASE( typeConstant ) \ + block_switch->addLine("case " + pixelTypeMap.at(typeConstant) + ":"); \ + block_switch->addLine("arrayType = ::armarx::aron::typenavigator::ImageNavigator::pixelTypeToName(" #typeConstant ");"); \ + block_switch->addLine("break;") + + CASE(::armarx::aron::typenavigator::ImagePixelType::Rgb24); + CASE(::armarx::aron::typenavigator::ImagePixelType::Depth32); + +#undef CASE + + block_switch->addLine("default:"); + { + CppBlockPtr block_default = std::make_shared<CppBlock>(); + block_default->addLine("std::stringstream ss;"); + block_default->addLine("ss << \"OpenCV image type \" << " + accessor + ".type() << \" cannot be serialized.\";"); + block_default->addLine("throw ::armarx::aron::error::AronException(\"" + typenavigator->getName() + "\", __FUNCTION__, ss.str());"); + + block_switch->addBlock(block_default); + } + block->addBlock(block_switch); + } + + + block->addLine("w.writeNDArray(" + accessor_shape + ", arrayType, reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "data)); // of " + accessor); + + return ResolveMaybeWriteBlock(accessor, block, typenavigator); + } + + + CppBlockPtr ImageSerializer::getReadBlock(const std::string& accessor) const + { + const std::string escaped_accessor = EscapeAccessor(accessor); + const std::string read_start_result_accessor = escaped_accessor + READ_START_RETURN_TYPE_ACCESSOR; + +#if 0 // Target code + auto the_rgb24_image_return_type = r.readStartNDArray(); // of the_rgb24_image + + if (!the_rgb24_image_return_type.dims.empty()) + { + std::vector<int> shape{the_rgb24_image_return_type.dims.begin(), std::prev(the_rgb24_image_return_type.dims.end())}; + + ::armarx::aron::typenavigator::ImagePixelType pixelType = ::armarx::aron::typenavigator::ImageNavigator::pixelTypeFromName(the_rgb24_image_return_type.type); + int cvMatType = 0; + switch (pixelType) + { + case ::armarx::aron::typenavigator::ImagePixelType::RGB24: + cvMatType = CV_8UC3; + case ::armarx::aron::typenavigator::ImagePixelType::DEPTH32: + cvMatType = CV_32FC1; + default: + { + std::stringstream ss; + ss << "NDArray Type '" << the_rgb24_image_return_type.type << "' cannot be deserialized as image."; + throw ::armarx::aron::error::AronException("AronImageType", __FUNCTION__, ss.str()); + } + } + + the_rgb24_image.create(shape, cvMatType); + r.readEndNDArray(reinterpret_cast<unsigned char*>(the_rgb24_image.data)); // of the_rgb24_image + } +#endif + + CppBlockPtr block = std::make_shared<CppBlock>(); + + block->addLine("if (!" + read_start_result_accessor + ".dims.empty())"); + { + CppBlockPtr block_if = std::make_shared<CppBlock>(); + + block_if->addLine("std::vector<int> shape{" + read_start_result_accessor + ".dims.begin(), std::prev(" + read_start_result_accessor + ".dims.end())};"); + + block_if->addLine("::armarx::aron::typenavigator::ImagePixelType pixelType = ::armarx::aron::typenavigator::ImageNavigator::pixelTypeFromName(" + read_start_result_accessor + ".type);"); + block_if->addLine("int cvMatType = 0;"); + block_if->addLine("switch (pixelType)"); + { + CppBlockPtr block_switch = std::make_shared<CppBlock>(); + +#define CASE( typeConstant ) \ + block_switch->addLine("case " #typeConstant ":"); \ + block_switch->addLine("cvMatType = " + pixelTypeMap.at(typeConstant) + ";"); \ + block_switch->addLine("break;") + + CASE(::armarx::aron::typenavigator::ImagePixelType::Rgb24); + CASE(::armarx::aron::typenavigator::ImagePixelType::Depth32); + +#undef CASE + + block_switch->addLine("default:"); + { + CppBlockPtr block_default = std::make_shared<CppBlock>(); + block_default->addLine("std::stringstream ss;"); + block_default->addLine("ss << \"NdArray Type '\" << " + read_start_result_accessor + ".type << \"' cannot be deserialized as image.\";"); + block_default->addLine("throw ::armarx::aron::error::AronException(\"AronImageType\", __FUNCTION__, ss.str());"); + + block_switch->addBlock(block_default); + } + block_if->addBlock(block_switch); + } + + block_if->addLine(accessor + ".create(shape, cvMatType);"); + block_if->addLine("r.readEndNDArray(reinterpret_cast<unsigned char*>(" + accessor + nextEl() + "data)); // of " + accessor); + block->addBlock(block_if); + } + + return ResolveMaybeReadBlock(accessor, "r.readStartNDArray()", block, typenavigator, true); + } + + + CppBlockPtr ImageSerializer::getEqualsBlock(const std::string& accessor, const std::string& otherInstanceAccessor) const + { + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); + block_if_data->addLine("if (cv::countNonZero(" + accessor + " != " + otherInstanceAccessor + ") != 0)"); + block_if_data->addLineAsBlock("return false;"); + return ResolveMaybeEqualsBlock(accessor, otherInstanceAccessor, block_if_data, typenavigator); + } +} + + diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.h new file mode 100644 index 0000000000000000000000000000000000000000..a44cafbe199c352576c1307d6cdcd20debb3f871 --- /dev/null +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Image.h @@ -0,0 +1,67 @@ +/* + * This file is part of ArmarX. + * + * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), + * Karlsruhe Institute of Technology (KIT), all rights reserved. + * + * ArmarX is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * ArmarX is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + * @author Rainer Kartmann (rainer dot kartmann at kit dot edu) + * @copyright http://www.gnu.org/licenses/gpl-2.0.txt + * GNU General Public License + */ + +#pragma once + +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.h> + +#include <map> +#include <memory> +#include <string> + + +namespace armarx::aron::cppserializer::serializer +{ + + class ImageSerializer : + virtual public detail::NDArraySerializerBase<typenavigator::ImageNavigator, ImageSerializer> + { + public: + using PointerType = std::shared_ptr<ImageSerializer>; + + public: + + ImageSerializer(const typenavigator::ImageNavigatorPtr& n); + + // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string& accessor) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string& accessor) const override; + virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; + virtual CppBlockPtr getWriteBlock(const std::string&) const override; + virtual CppBlockPtr getReadBlock(const std::string&) const override; + virtual CppBlockPtr getEqualsBlock(const std::string&, const std::string&) const override; + + + private: + + static constexpr const char* ITERATOR_ACCESSOR = "_iterator"; + static constexpr const char* SHAPE_ACCESSOR = "_shape"; + static constexpr const char* NDIM_ACCESSOR = "_ndim"; + + /// Maps ARON pixel types to OpenCV image type constants. + static const std::map<typenavigator::ImagePixelType, std::string> pixelTypeMap; + + }; + +} diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.cpp index dfd9e90c390c358aa1aba0fa6af2c3f843f6013a..f9597ff4540e02bb7aba3e7ecf990467d88ae8be 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.cpp @@ -24,13 +24,18 @@ // Header #include "NDArray.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors NDArraySerializer::NDArraySerializer(const typenavigator::NDArrayNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::NDArrayNavigator, NDArraySerializer>("NDArray", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronNDArray)), n) + detail::NDArraySerializerBase<typenavigator::NDArrayNavigator, NDArraySerializer>( + "NDArray", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronNDArray>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.h index 540b38d930ec9a2911c8bb058b856031cc430683..6e6a72f01b84db55c6b059a74c16eb59aaa27b2d 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/NDArray.h @@ -23,15 +23,11 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/NDArray.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <string> -// ArmarX -#include "../../../../../navigator/type/ndarray/NDArray.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.cpp index 37de66674278dc5a8439a2b06d3e634dab7e42ba..0528b58b4efd7a05484c376c6dc85d722f536459 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.cpp @@ -24,54 +24,86 @@ // Header #include "OpenCVMat.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { const std::map<std::string, std::pair<std::string, int>> OpenCVMatSerializer::ACCEPTED_TYPES = { - {"CV_8U", {"CV_8U", 1}}, - {"CV_8S", {"CV_8S", 1}}, - {"CV_16U", {"CV_16U", 2}}, - {"CV_16S", {"CV_16S", 2}}, - {"CV_32S", {"CV_32S", 4}}, - {"CV_32F", {"CV_32F", 4}}, - {"CV_64F", {"CV_64F", 8}}, + { "8u", {"CV_8U", 1}}, + { "8s", {"CV_8S", 1}}, + {"16u", {"CV_16U", 2}}, + {"16s", {"CV_16S", 2}}, + {"32s", {"CV_32S", 4}}, + {"32f", {"CV_32F", 4}}, + {"64f", {"CV_64F", 8}}, }; // constructors OpenCVMatSerializer::OpenCVMatSerializer(const typenavigator::OpenCVMatNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::OpenCVMatNavigator, OpenCVMatSerializer>("cv::Mat", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronOpenCVMat)), n) + detail::NDArraySerializerBase<typenavigator::OpenCVMatNavigator, OpenCVMatSerializer>( + "cv::Mat", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronOpenCVMat>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } - std::pair<CppBlockPtr, std::string> OpenCVMatSerializer::getDimensionsFromAccessor(const std::string& accessor) const + std::pair<CppBlockPtr, std::string> OpenCVMatSerializer::getShapeFromAccessor(const std::string& accessor) const { CppBlockPtr b = CppBlockPtr(new CppBlock()); std::string escaped_accessor = EscapeAccessor(accessor); - std::string accessor_dimensions = escaped_accessor + DIMENSION_ACCESSOR; + std::string accessor_shape = escaped_accessor + SHAPE_ACCESSOR; std::string accessor_iterator = escaped_accessor + ITERATOR_ACCESSOR; - b->addLine("std::vector<int> " + accessor_dimensions + ";"); + b->addLine("std::vector<int> " + accessor_shape + ";"); b->addLine("for (int " + accessor_iterator + " = 0; " + accessor_iterator + " < " + accessor + nextEl() + "dims; ++" + accessor_iterator + ")"); CppBlockPtr b2 = CppBlockPtr(new CppBlock()); - b2->addLine(accessor_dimensions + ".push_back(" + accessor + nextEl() + "size[" + accessor_iterator + "]);"); + b2->addLine(accessor_shape + ".push_back(" + accessor + nextEl() + "size[" + accessor_iterator + "]);"); b->addBlock(b2); - return {b, accessor_dimensions}; + return {b, accessor_shape}; } + + CppBlockPtr OpenCVMatSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + + std::string sizes; + { + const std::vector<int> shape = typenavigator->getShape(); + sizes = simox::alg::join(simox::alg::multi_to_string(shape), ", "); + sizes = "std::vector<int>{ " + sizes + " }"; + } + std::string type = typenavigator->getTypeName(); + { + type = simox::alg::to_lower(type); + type = simox::alg::remove_prefix(type, "cv_"); + if (auto it = ACCEPTED_TYPES.find(type); it != ACCEPTED_TYPES.end()) + { + type = it->second.first; + } + } + + block_if_data->addLine(accessor + " = " + this->getFullTypenameGenerator() + + "(" + sizes + ", " + type + ");"); + return this->ResolveMaybeResetHardBlock(accessor, block_if_data, this->typenavigator); + } + + CppBlockPtr OpenCVMatSerializer::getResetSoftBlock(const std::string& accessor) const { CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); - auto [get_dim_block, accessor_dimensions] = getDimensionsFromAccessor(accessor); + auto [get_dim_block, accessor_shape] = getShapeFromAccessor(accessor); block_if_data->appendBlock(get_dim_block); - block_if_data->addLine("if (!" + accessor_dimensions + ".empty())"); + block_if_data->addLine("if (!" + accessor_shape + ".empty())"); CppBlockPtr b2 = CppBlockPtr(new CppBlock()); - b2->addLine(accessor + " = " + getFullCppTypename() + "(" + accessor_dimensions + ", " + accessor + nextEl() + "type());"); + b2->addLine(accessor + " = " + getFullCppTypename() + "(" + accessor_shape + ", " + accessor + nextEl() + "type());"); block_if_data->addBlock(b2); return ResolveMaybeResetSoftBlock(accessor, block_if_data, typenavigator); @@ -90,10 +122,10 @@ namespace armarx::aron::cppserializer::serializer std::string escaped_accessor = EscapeAccessor(accessor); - auto [get_dim_block, accessor_dimensions] = getDimensionsFromAccessor(accessor); + auto [get_dim_block, accessor_shape] = getShapeFromAccessor(accessor); block_if_data->appendBlock(get_dim_block); - block_if_data->addLine(accessor_dimensions + ".push_back(" + accessor + nextEl() + "elemSize());"); - block_if_data->addLine("w.writeNDArray(" + accessor_dimensions + ", std::to_string(" + accessor + nextEl() + "type()), reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "data)); // of " + accessor); + block_if_data->addLine(accessor_shape + ".push_back(" + accessor + nextEl() + "elemSize());"); + block_if_data->addLine("w.writeNDArray(" + accessor_shape + ", std::to_string(" + accessor + nextEl() + "type()), reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "data)); // of " + accessor); return ResolveMaybeWriteBlock(accessor, block_if_data, typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.h index 27ec677b25d20dab8d2e966ac6e0065ad1db98dd..08aacde0f0d11e47cd8cca3ae17057928bf2daf3 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/OpenCVMat.h @@ -23,33 +23,30 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <map> +#include <memory> +#include <string> +#include <utility> // std::pair -// ArmarX -#include "../../../../../navigator/type/ndarray/OpenCVMat.h" namespace armarx::aron::cppserializer::serializer { - class OpenCVMatSerializer; - typedef std::shared_ptr<OpenCVMatSerializer> AronOpenCVMatTypeCppSerializerPtr; - class OpenCVMatSerializer : virtual public detail::NDArraySerializerBase<typenavigator::OpenCVMatNavigator, OpenCVMatSerializer> { public: - using PointerType = AronOpenCVMatTypeCppSerializerPtr; + using PointerType = std::shared_ptr<OpenCVMatSerializer>; public: // constructors OpenCVMatSerializer(const typenavigator::OpenCVMatNavigatorPtr& n); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string& accessor) const override; virtual CppBlockPtr getResetSoftBlock(const std::string& accessor) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; @@ -57,13 +54,14 @@ namespace armarx::aron::cppserializer::serializer virtual CppBlockPtr getEqualsBlock(const std::string&, const std::string&) const override; private: - std::pair<CppBlockPtr, std::string> getDimensionsFromAccessor(const std::string& accessor) const; + std::pair<CppBlockPtr, std::string> getShapeFromAccessor(const std::string& accessor) const; private: // members static const std::map<std::string, std::pair<std::string, int>> ACCEPTED_TYPES; static constexpr const char* ITERATOR_ACCESSOR = "_iterator"; - static constexpr const char* DIMENSION_ACCESSOR = "_dimensions"; - static constexpr const char* NUM_DIMENSION_ACCESSOR = "_num_dimensions"; + static constexpr const char* SHAPE_ACCESSOR = "_shape"; + static constexpr const char* NDIM_ACCESSOR = "_ndim"; }; + } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.cpp index c908a0c44a8b0d1d940b9a64be5e79558b1dc949..1bd39c73c977b6cf4da7a7de01b3346083c7c742 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.cpp @@ -24,27 +24,44 @@ // Header #include "Orientation.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors OrientationSerializer::OrientationSerializer(const typenavigator::OrientationNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::OrientationNavigator, OrientationSerializer>("Eigen::Quaternion<" + n->ACCEPTED_TYPE + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronOrientation)), n) + detail::NDArraySerializerBase<typenavigator::OrientationNavigator, OrientationSerializer>( + "Eigen::Quaternion<" + n->ACCEPTED_TYPE + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronOrientation>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } + CppBlockPtr OrientationSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + block->addLine(accessor + ".setIdentity();"); + return this->ResolveMaybeResetHardBlock(accessor, block, this->typenavigator); + } + + CppBlockPtr OrientationSerializer::getResetSoftBlock(const std::string& accessor) const + { + return getResetHardBlock(accessor); + } + CppBlockPtr OrientationSerializer::getWriteTypeBlock(const std::string& accessor) const { - CppBlockPtr b = CppBlockPtr(new CppBlock()); + CppBlockPtr b = std::make_shared<CppBlock>(); b->addLine("w.writeOrientation({" + MAYBE_TO_STRING(typenavigator->getMaybe()) + "}); // of " + accessor); return b; } CppBlockPtr OrientationSerializer::getWriteBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("w.writeNDArray({" + simox::alg::to_string(typenavigator->ACCEPTED_DIMENSION, ", ") + ", 4}, \"" + typenavigator->ACCEPTED_TYPE + "\", reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "coeffs().data())); // of " + accessor); return ResolveMaybeWriteBlock(accessor, block_if_data, typenavigator); @@ -52,14 +69,14 @@ namespace armarx::aron::cppserializer::serializer CppBlockPtr OrientationSerializer::getReadBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("r.readEndNDArray(reinterpret_cast<unsigned char*>(" + accessor + nextEl() + "coeffs().data())); // of " + accessor); return ResolveMaybeReadBlock(accessor, "r.readStartNDArray()", block_if_data, typenavigator); } CppBlockPtr OrientationSerializer::getEqualsBlock(const std::string& accessor, const std::string& otherInstanceAccessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("if (not (" + accessor + nextEl() + "isApprox(" + otherInstanceAccessor + ")))"); block_if_data->addLineAsBlock("return false;"); return ResolveMaybeEqualsBlock(accessor, otherInstanceAccessor, block_if_data, typenavigator); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.h index ece7bb620a16d40184518585ed0b0592a8264639..b4851e4bc6806fc60b157302a7bfc53adc6a110a 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Orientation.h @@ -23,39 +23,32 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/Orientation.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/ndarray/Orientation.h" namespace armarx::aron::cppserializer::serializer { - class OrientationSerializer; - typedef std::shared_ptr<OrientationSerializer> AronOrientationTypeCppSerializerPtr; class OrientationSerializer : virtual public detail::NDArraySerializerBase<typenavigator::OrientationNavigator, OrientationSerializer> { public: - using PointerType = AronOrientationTypeCppSerializerPtr; + using PointerType = std::shared_ptr<class OrientationSerializer>; public: + // constructors OrientationSerializer(const typenavigator::OrientationNavigatorPtr&); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string&) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string&) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; virtual CppBlockPtr getReadBlock(const std::string&) const override; virtual CppBlockPtr getEqualsBlock(const std::string&, const std::string&) const override; - private: - static constexpr const char* DIMENSION_ACCESSOR = "_dimensions"; - static constexpr const char* TYPE_ACCESSOR = "_type"; }; + } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.cpp index 5a6155b230e3fd5267ef30dcf665ca60df97ab1f..2e0234f3aff59d141988304448c128717bd9476d 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.cpp @@ -24,6 +24,9 @@ // Header #include "PCLPointCloud.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { @@ -41,9 +44,11 @@ namespace armarx::aron::cppserializer::serializer // constructors PCLPointCloudSerializer::PCLPointCloudSerializer(const typenavigator::PCLPointCloudNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::PCLPointCloudNavigator, PCLPointCloudSerializer>("pcl::PointCloud<" + ACCEPTED_TYPES.at(n->getTypename()).first + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronPCLPointCloud)), n) + detail::NDArraySerializerBase<typenavigator::PCLPointCloudNavigator, PCLPointCloudSerializer>( + "pcl::PointCloud<" + ACCEPTED_TYPES.at(n->getTypename()).first + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronPCLPointCloud>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.h index 3f182f4e24f775166a4e64d12f8933fffa771fc6..a0692c64ef06e92875ad66079f871fecc211d0fe 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/PCLPointCloud.h @@ -23,15 +23,11 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/PCLPointCloud.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" +#include <map> -// ArmarX -#include "../../../../../navigator/type/ndarray/PCLPointCloud.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.cpp index eccbbca04eeeced4c106707d5963222f0250db54..b6be09e9f94b972f23e226a6dc8cbd64e11c6040 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.cpp @@ -24,27 +24,44 @@ // Header #include "Pose.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors PoseSerializer::PoseSerializer(const typenavigator::PoseNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::PoseNavigator, PoseSerializer>("Eigen::Matrix<" + n->ACCEPTED_TYPE + ", " + simox::alg::to_string(n->ACCEPTED_DIMENSION, ", ") + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronPose)), n) + detail::NDArraySerializerBase<typenavigator::PoseNavigator, PoseSerializer>( + "Eigen::Matrix<" + n->ACCEPTED_TYPE + ", " + simox::alg::to_string(n->ACCEPTED_DIMENSION, ", ") + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronPose>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } + CppBlockPtr PoseSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + block->addLine(accessor + ".setIdentity();"); + return this->ResolveMaybeResetHardBlock(accessor, block, this->typenavigator); + } + + CppBlockPtr PoseSerializer::getResetSoftBlock(const std::string& accessor) const + { + return getResetHardBlock(accessor); + } + CppBlockPtr PoseSerializer::getWriteTypeBlock(const std::string& accessor) const { - CppBlockPtr b = CppBlockPtr(new CppBlock()); + CppBlockPtr b = std::make_shared<CppBlock>(); b->addLine("w.writePose({" + MAYBE_TO_STRING(typenavigator->getMaybe()) + "}); // of " + accessor); return b; } CppBlockPtr PoseSerializer::getWriteBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("w.writeNDArray({" + simox::alg::to_string(typenavigator->ACCEPTED_DIMENSION, ", ") + ", 4}, \"" + typenavigator->ACCEPTED_TYPE + "\", reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "data())); // of " + accessor); return ResolveMaybeWriteBlock(accessor, block_if_data, typenavigator); @@ -52,14 +69,14 @@ namespace armarx::aron::cppserializer::serializer CppBlockPtr PoseSerializer::getReadBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("r.readEndNDArray(reinterpret_cast<unsigned char*>(" + accessor + nextEl() + "data())); // of " + accessor); return ResolveMaybeReadBlock(accessor, "r.readStartNDArray()", block_if_data, typenavigator); } CppBlockPtr PoseSerializer::getEqualsBlock(const std::string& accessor, const std::string& otherInstanceAccessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("if (not (" + accessor + nextEl() + "isApprox(" + otherInstanceAccessor + ")))"); block_if_data->addLineAsBlock("return false;"); return ResolveMaybeEqualsBlock(accessor, otherInstanceAccessor, block_if_data, typenavigator); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.h index 45b8eb78c64e62a2ea7713ac977c9fb3e675de05..195a04015ea58ae14b419dcda0bf163981cecff6 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Pose.h @@ -23,39 +23,29 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/Pose.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/ndarray/Pose.h" namespace armarx::aron::cppserializer::serializer { - class PoseSerializer; - typedef std::shared_ptr<PoseSerializer> AronPoseTypeCppSerializerPtr; - class PoseSerializer : virtual public detail::NDArraySerializerBase<typenavigator::PoseNavigator, PoseSerializer> { public: - using PointerType = AronPoseTypeCppSerializerPtr; + using PointerType = std::shared_ptr<PoseSerializer>; public: // constructors PoseSerializer(const typenavigator::PoseNavigatorPtr&); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string&) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string&) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; virtual CppBlockPtr getReadBlock(const std::string&) const override; virtual CppBlockPtr getEqualsBlock(const std::string&, const std::string&) const override; - private: - static constexpr const char* DIMENSION_ACCESSOR = "_dimensions"; - static constexpr const char* TYPE_ACCESSOR = "_type"; }; } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.cpp index 199c7e3053af9cc84016d14a320092667ce87c71..6c9e54ecd0a074cc1c56a63f090fc56c06152004 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.cpp @@ -24,27 +24,44 @@ // Header #include "Position.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors PositionSerializer::PositionSerializer(const typenavigator::PositionNavigatorPtr& n) : - detail::NDArraySerializerBase<typenavigator::PositionNavigator, PositionSerializer>("Eigen::Matrix<" + n->ACCEPTED_TYPE + ", " + simox::alg::to_string(n->ACCEPTED_DIMENSION, ", ") + ">", - simox::meta::get_type_name(typeid(data::AronNDArray)), - simox::meta::get_type_name(typeid(type::AronPosition)), n) + detail::NDArraySerializerBase<typenavigator::PositionNavigator, PositionSerializer>( + "Eigen::Matrix<" + n->ACCEPTED_TYPE + ", " + simox::alg::to_string(n->ACCEPTED_DIMENSION, ", ") + ">", + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronPosition>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); } + CppBlockPtr PositionSerializer::getResetHardBlock(const std::string& accessor) const + { + CppBlockPtr block = std::make_shared<CppBlock>(); + block->addLine(accessor + ".setZero();"); + return this->ResolveMaybeResetHardBlock(accessor, block, this->typenavigator); + } + + CppBlockPtr PositionSerializer::getResetSoftBlock(const std::string& accessor) const + { + return getResetHardBlock(accessor); + } + CppBlockPtr PositionSerializer::getWriteTypeBlock(const std::string& accessor) const { - CppBlockPtr b = CppBlockPtr(new CppBlock()); + CppBlockPtr b = std::make_shared<CppBlock>(); b->addLine("w.writePosition({" + MAYBE_TO_STRING(typenavigator->getMaybe()) + "}); // of " + accessor); return b; } CppBlockPtr PositionSerializer::getWriteBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("w.writeNDArray({" + simox::alg::to_string(typenavigator->ACCEPTED_DIMENSION, ", ") + ", 4}, \"" + typenavigator->ACCEPTED_TYPE + "\", reinterpret_cast<const unsigned char*>(" + accessor + nextEl() + "data())); // of " + accessor); return ResolveMaybeWriteBlock(accessor, block_if_data, typenavigator); @@ -52,14 +69,14 @@ namespace armarx::aron::cppserializer::serializer CppBlockPtr PositionSerializer::getReadBlock(const std::string& accessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("r.readEndNDArray(reinterpret_cast<unsigned char*>(" + accessor + nextEl() + "data())); // of " + accessor); return ResolveMaybeReadBlock(accessor, "r.readStartNDArray()", block_if_data, typenavigator); } CppBlockPtr PositionSerializer::getEqualsBlock(const std::string& accessor, const std::string& otherInstanceAccessor) const { - CppBlockPtr block_if_data = CppBlockPtr(new CppBlock()); + CppBlockPtr block_if_data = std::make_shared<CppBlock>(); block_if_data->addLine("if (not (" + accessor + nextEl() + "isApprox(" + otherInstanceAccessor + ")))"); block_if_data->addLineAsBlock("return false;"); return ResolveMaybeEqualsBlock(accessor, otherInstanceAccessor, block_if_data, typenavigator); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.h index acb8f9912f8169b161ccd5b6d80c30e546b7ec75..61026f4617401bdc64393c4e813c3fd535dce301 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/ndarray/Position.h @@ -23,39 +23,30 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/NDArraySerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/ndarray/Position.h> -// Base Class -#include "../detail/NDArraySerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/ndarray/Position.h" namespace armarx::aron::cppserializer::serializer { - class PositionSerializer; - typedef std::shared_ptr<PositionSerializer> AronPositionTypeCppSerializerPtr; class PositionSerializer : virtual public detail::NDArraySerializerBase<typenavigator::PositionNavigator, PositionSerializer> { public: - using PointerType = AronPositionTypeCppSerializerPtr; + using PointerType = std::shared_ptr<PositionSerializer>; public: // constructors PositionSerializer(const typenavigator::PositionNavigatorPtr&); // virtual implementations + virtual CppBlockPtr getResetHardBlock(const std::string&) const override; + virtual CppBlockPtr getResetSoftBlock(const std::string&) const override; virtual CppBlockPtr getWriteTypeBlock(const std::string&) const override; virtual CppBlockPtr getWriteBlock(const std::string&) const override; virtual CppBlockPtr getReadBlock(const std::string&) const override; virtual CppBlockPtr getEqualsBlock(const std::string&, const std::string&) const override; - private: - static constexpr const char* DIMENSION_ACCESSOR = "_dimensions"; - static constexpr const char* TYPE_ACCESSOR = "_type"; }; } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.cpp index c0bb65832b4bda3aaea920efd48fc19b98d752f3..33283bde524169ec20e01bd659de94547b662212 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Bool.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Bool.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ BoolSerializer::BoolSerializer(const typenavigator::BoolNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::BoolNavigator, BoolSerializer>("bool", simox::meta::get_type_name(typeid(data::AronBool)), simox::meta::get_type_name(typeid(type::AronBool)), e) + detail::PrimitiveSerializerBase<typenavigator::BoolNavigator, BoolSerializer>( + "bool", + simox::meta::get_type_name<data::AronBool>(), + simox::meta::get_type_name<type::AronBool>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.h index ba1dd70de0220840e9feda9d18304d631142ae06..688aeb2d365a5e785e575050f8e01983b3211e9e 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Bool.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Bool.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Bool.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.cpp index 62a47a280f4bfea571384b30d9674fa08d8aa801..c7bbce2eebe2367b83ce5d63a4b7b77b1da7acc6 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Double.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Double.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ DoubleSerializer::DoubleSerializer(const typenavigator::DoubleNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::DoubleNavigator, DoubleSerializer>("double", simox::meta::get_type_name(typeid(data::AronDouble)), simox::meta::get_type_name(typeid(type::AronDouble)), e) + detail::PrimitiveSerializerBase<typenavigator::DoubleNavigator, DoubleSerializer>( + "double", + simox::meta::get_type_name<data::AronDouble>(), + simox::meta::get_type_name<type::AronDouble>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.h index 6a965e2034d3924b842634d7dbb8219467a17294..b8258a0b028ac020c61af412d402599367587e6a 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Double.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Double.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Double.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.cpp index 06cbd8c1a4304f095fc85887060f696335b05f55..34593db2f5b0b7fd7113395d79233b2a9c93b6d4 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Float.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Float.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ FloatSerializer::FloatSerializer(const typenavigator::FloatNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::FloatNavigator, FloatSerializer>("float", simox::meta::get_type_name(typeid(data::AronFloat)), simox::meta::get_type_name(typeid(type::AronFloat)), e) + detail::PrimitiveSerializerBase<typenavigator::FloatNavigator, FloatSerializer>( + "float", + simox::meta::get_type_name<data::AronFloat>(), + simox::meta::get_type_name<type::AronFloat>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.h index b2139ed2a368912adba187220a84fb6565b760ee..835ebc61264b9dbb636e12a9469a0deff0bf1e90 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Float.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Float.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Float.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.cpp index 7458faa2858bd545c77d9c7014556632bdc0c196..84299f5843002d822eae0845f748a9ecf4e491f9 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Int.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Int.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ IntSerializer::IntSerializer(const typenavigator::IntNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::IntNavigator, IntSerializer>("int", simox::meta::get_type_name(typeid(data::AronInt)), simox::meta::get_type_name(typeid(type::AronInt)), e) + detail::PrimitiveSerializerBase<typenavigator::IntNavigator, IntSerializer>( + "int", + simox::meta::get_type_name<data::AronInt>(), + simox::meta::get_type_name<type::AronInt>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.h index 7bb6311bdd60de2374a11b37741070da3e8c737a..6d26dc8e63f6372a2e0210816f9addb394af0294 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Int.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Int.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Int.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.cpp index 754f4818ddd5f08dc224a62ebfbb95cf89e1673a..2d6f466342a6747688180245f2892284ea956196 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Long.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Long.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ LongSerializer::LongSerializer(const typenavigator::LongNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::LongNavigator, LongSerializer>("long", simox::meta::get_type_name(typeid(data::AronLong)), simox::meta::get_type_name(typeid(type::AronLong)), e) + detail::PrimitiveSerializerBase<typenavigator::LongNavigator, LongSerializer>( + "long", + simox::meta::get_type_name<data::AronLong>(), + simox::meta::get_type_name<type::AronLong>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.h index 5d0d0948ee029b6d5718f9ee740f7ae2b0d99533..227c91bfded830f5744c35ddd3ab39ad79897775 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Long.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Long.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Long.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.cpp index 89e3603ee8afcb7ca786097d391c21e4478b3bb3..4246e1157739f62934d58f1037dcc4098aa52fdc 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "String.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "String.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ StringSerializer::StringSerializer(const typenavigator::StringNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::StringNavigator, StringSerializer>("std::string", simox::meta::get_type_name(typeid(data::AronString)), simox::meta::get_type_name(typeid(type::AronString)), e) + detail::PrimitiveSerializerBase<typenavigator::StringNavigator, StringSerializer>( + "std::string", + simox::meta::get_type_name<data::AronString>(), + simox::meta::get_type_name<type::AronString>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.h index d6bc43272efabf2b93a55bce3eec77e68274afd4..59bf310ccdac6edc8a14fe2fd4e07d9fa610f371 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/String.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/String.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/String.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.cpp index e76d5e1ba97eea373fa1eb9af90ec1f3dc5838cf..a44838e4a29a2705cf4ddf16da1b479827f5ad46 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.cpp @@ -21,19 +21,20 @@ * GNU General Public License */ +#include "Time.h" -// STD/STL -#include <string> -#include <map> +#include <SimoxUtility/meta/type_name.h> -// Header -#include "Time.h" namespace armarx::aron::cppserializer::serializer { /* constructors */ TimeSerializer::TimeSerializer(const typenavigator::TimeNavigatorPtr& e) : - detail::PrimitiveSerializerBase<typenavigator::TimeNavigator, TimeSerializer>("IceUtil::Time", simox::meta::get_type_name(typeid(data::AronLong)), simox::meta::get_type_name(typeid(type::AronTime)), e) + detail::PrimitiveSerializerBase<typenavigator::TimeNavigator, TimeSerializer>( + "IceUtil::Time", + simox::meta::get_type_name<data::AronLong>(), + simox::meta::get_type_name<type::AronTime>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); } diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.h index ff06aff3e934bd23aa52d6b86bf3f45a403bf1ef..96b0322c0ab8a1b45d74a1560ec08ba5d3c9db14 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/primitive/Time.h @@ -23,14 +23,9 @@ #pragma once -// STD/STL -#include <string> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/PrimitiveSerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/primitive/Time.h> -// Base Class -#include "../detail/PrimitiveSerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/primitive/Time.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.cpp index 39f178fd00661fe78478ee3e74fe0872b2e762a5..0db5f2d68e1de29da18c9327a5b25ee5bd834bc5 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.cpp @@ -24,11 +24,18 @@ // Header #include "IntEnumClass.h" +#include <SimoxUtility/meta/type_name.h> + + namespace armarx::aron::cppserializer::serializer { // constructors IntEnumClassSerializer::IntEnumClassSerializer(const typenavigator::IntEnumNavigatorPtr& n) : - detail::SerializerBase<typenavigator::IntEnumNavigator, IntEnumClassSerializer>(n->getEnumName(), simox::meta::get_type_name(typeid(data::AronNDArray)), simox::meta::get_type_name(typeid(type::AronIntEnum)), n) + detail::SerializerBase<typenavigator::IntEnumNavigator, IntEnumClassSerializer>( + n->getEnumName(), + simox::meta::get_type_name<data::AronNDArray>(), + simox::meta::get_type_name<type::AronIntEnum>(), + n) { ARMARX_CHECK_NOT_NULL(typenavigator); if (typenavigator->getMaybe() != type::Maybe::eNone) diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.h index 8bc3ce9e21e220fc34c710b7bb5a7da59521dd60..bd4a0f8128b19bbe28b388e3fa97faddf8f743b1 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/IntEnumClass.h @@ -23,15 +23,12 @@ #pragma once -// STD/STL -#include <string> -#include <map> +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/enum/IntEnum.h> -// Base Class -#include "../detail/SerializerBase.h" +#include <map> +#include <utility> // std::pair -// ArmarX -#include "../../../../../navigator/type/enum/IntEnum.h" namespace armarx::aron::cppserializer::serializer { diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.cpp index 7653acba47e178b6337f8fbc9602037070b76836..f5f62b9215ebd3904405184605d6d5df9fc1298e 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.cpp @@ -24,12 +24,18 @@ // Header #include "ObjectClass.h" +#include <SimoxUtility/meta/type_name.h> + namespace armarx::aron::cppserializer::serializer { // constructors ObjectClassSerializer::ObjectClassSerializer(const typenavigator::ObjectNavigatorPtr& e) : - detail::SerializerBase<typenavigator::ObjectNavigator, ObjectClassSerializer>(e->getObjectName(), simox::meta::get_type_name(typeid(data::AronDict)), simox::meta::get_type_name(typeid(type::AronObject)), e) + detail::SerializerBase<typenavigator::ObjectNavigator, ObjectClassSerializer>( + e->getObjectName(), + simox::meta::get_type_name<data::AronDict>(), + simox::meta::get_type_name<type::AronObject>(), + e) { ARMARX_CHECK_NOT_NULL(typenavigator); if (typenavigator->getMaybe() != type::Maybe::eNone) @@ -143,7 +149,8 @@ namespace armarx::aron::cppserializer::serializer child_b->addLine("w.writeKey(\"" + key + "\");"); child_b->appendBlock(child_s->getWriteBlock(key)); - block_if_data->appendBlock(child_b); + block_if_data->addBlock(child_b); + block_if_data->addLine(""); } block_if_data->addLine("if (!__aronExtends)"); @@ -167,7 +174,7 @@ namespace armarx::aron::cppserializer::serializer { const auto child_s = FromAronTypeNaviagtorPtr(child); block_if_data->addLine("r.loadMember(\"" + key + "\");"); - block_if_data->appendBlock(child_s->getReadBlock(key)); + block_if_data->addBlock(child_s->getReadBlock(key)); } block_if_data->addLine("r.readEndDict(); // of top level object " + getCoreCppTypename()); return ResolveMaybeReadBlock(accessor, "", block_if_data, typenavigator); diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.h b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.h index 03f8817a5c4e64dfbf15e9a54e8e0f6ae88f4ff3..3a7a314aa14113990d9d4aad5303b21f153c674c 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/toplevel/ObjectClass.h @@ -23,15 +23,8 @@ #pragma once -// STD/STL -#include <string> -#include <map> - -// Base Class -#include "../detail/SerializerBase.h" - -// ArmarX -#include "../../../../../navigator/type/container/Object.h" +#include <RobotAPI/libraries/aron/core/codegenerator/codeWriter/cpp/serializer/detail/SerializerBase.h> +#include <RobotAPI/libraries/aron/core/navigator/type/container/Object.h> namespace armarx::aron::cppserializer::serializer diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/Data.h b/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/Data.h index 695050d69d765585b3192e9a2874c721afe8693c..c67f5c1b4845bdc838c33300c92722343f831bba 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/Data.h +++ b/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/Data.h @@ -74,6 +74,7 @@ namespace armarx::aron::xmltypereader static constexpr const char* ROWS_ATTRIBUTE_NAME = "rows"; static constexpr const char* COLS_ATTRIBUTE_NAME = "cols"; static constexpr const char* DIMENSIONS_ATTRIBUTE_NAME = "dimensions"; + static constexpr const char* SHAPE_ATTRIBUTE_NAME = "shape"; static constexpr const char* OPTIONAL_NAME = "optional"; static constexpr const char* RAW_PTR_NAME = "raw_ptr"; static constexpr const char* SHARED_PTR_NAME = "shared_ptr"; diff --git a/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/ReaderFactory.cpp b/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/ReaderFactory.cpp index 42c4ae9eea4efcd7dc3688164aec22bb49507959..e9795175ad11e15872b4f40594b328e50d5b99b1 100644 --- a/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/ReaderFactory.cpp +++ b/source/RobotAPI/libraries/aron/core/codegenerator/typeReader/xml/ReaderFactory.cpp @@ -289,15 +289,6 @@ namespace armarx::aron::xmltypereader { return nullptr; } - - // Complex type (IVTCByteImage) - typenavigator::NavigatorPtr IVTCByteImageReaderFactory::createSpecific(const RapidXmlReaderNode& node, const Path& path) const - { - Data::EnforceTagName(node, Data::GENERATE_IVT_CBYTE_IMAGE_MEMBER_TAG); - typenavigator::IVTCByteImageNavigatorPtr complex(new typenavigator::IVTCByteImageNavigator(path)); - return complex; - } - // Complex type (EigenMatrix) typenavigator::NavigatorPtr EigenMatrixReaderFactory::createSpecific(const RapidXmlReaderNode& node, const Path& path) const { @@ -328,12 +319,52 @@ namespace armarx::aron::xmltypereader return complex; } + + typenavigator::NavigatorPtr ImageReaderFactory::createSpecific(const RapidXmlReaderNode& node, const Path& path) const + { + Data::EnforceTagName(node, Data::GENERATE_IMAGE_MEMBER_TAG); + + typenavigator::ImageNavigatorPtr complex = std::make_shared<typenavigator::ImageNavigator>(path); + complex->setPixelType(node.attribute_value("pixelType")); + + return complex; + } + + // Complex type (IVTCByteImage) + typenavigator::NavigatorPtr IVTCByteImageReaderFactory::createSpecific(const RapidXmlReaderNode& node, const Path& path) const + { + Data::EnforceTagName(node, Data::GENERATE_IVT_CBYTE_IMAGE_MEMBER_TAG); + typenavigator::IVTCByteImageNavigatorPtr complex(new typenavigator::IVTCByteImageNavigator(path)); + return complex; + } + + + // Complex type (OpenCVMat) typenavigator::NavigatorPtr OpenCVMatReaderFactory::createSpecific(const RapidXmlReaderNode& node, const Path& path) const { Data::EnforceTagName(node, Data::GENERATE_OPENCV_MAT_MEMBER_TAG); typenavigator::OpenCVMatNavigatorPtr complex(new typenavigator::OpenCVMatNavigator(path)); + + std::vector<int> shape; + { + std::string shapeStr = node.attribute_value(Data::SHAPE_ATTRIBUTE_NAME); + const bool trim = true, removeEmpty = false; + std::vector<std::string> split = simox::alg::split(shapeStr, ",", trim, removeEmpty); + shape.reserve(split.size()); + for (const std::string& entry : split) + { + // What happens if this throws an error? + int size = std::stoi(entry); + shape.push_back(size); + } + } + complex->setShape(shape); + + std::string typeName = node.attribute_value(Data::TYPE_ATTRIBUTE_NAME); + complex->setTypeName(typeName); + return complex; } @@ -342,7 +373,7 @@ namespace armarx::aron::xmltypereader { Data::EnforceTagName(node, Data::GENERATE_PCL_POINTCLOUD_MEMBER_TAG); Data::EnforceAttribute(node, Data::TYPE_ATTRIBUTE_NAME); - std::string type = node.attribute_value(Data::TYPE_ATTRIBUTE_NAME);; + std::string type = node.attribute_value(Data::TYPE_ATTRIBUTE_NAME); typenavigator::PCLPointCloudNavigatorPtr complex(new typenavigator::PCLPointCloudNavigator(path)); complex->setTypename(type); diff --git a/source/RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.cpp b/source/RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.cpp index 6c95ec35b8eb3c7ce42bf6cbc74c0c56adc68829..d5e2ebe0fe9eb12a834bef86cd673faa41369912 100644 --- a/source/RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.cpp +++ b/source/RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.cpp @@ -161,7 +161,8 @@ namespace armarx::aron::dataIO::reader auto casted = datanavigator::NDArrayNavigator::DynamicCastAndCheck(current_nav); std::vector<int> dims = casted->getDimensions(); - memcpy(data, casted->getData(), std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>())); + int size = std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()); + std::memcpy(data, casted->getData(), static_cast<size_t>(size)); } // Read primitives diff --git a/source/RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.cpp b/source/RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.cpp index 8777b5d0c9691d75a6dce7c780c4e3f6c5c6ce04..b1c25a788a0c1380ef2f8e0f4aa2d9f2acf967b6 100644 --- a/source/RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.cpp +++ b/source/RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.cpp @@ -96,7 +96,8 @@ namespace armarx::aron::dataIO::writer datanavigator::NDArrayNavigatorPtr aron(new datanavigator::NDArrayNavigator(path)); aron->setDimensions(dims); aron->setType(t); - aron->setData(std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()), data); + int size = std::accumulate(std::begin(dims), std::end(dims), 1, std::multiplies<int>()); + aron->setData(static_cast<unsigned int>(size), data); token->addElement(aron); } diff --git a/source/RobotAPI/libraries/aron/core/io/typeIO/Writer.h b/source/RobotAPI/libraries/aron/core/io/typeIO/Writer.h index db7b4ed1adc62ea9962bd14ce9993be51bb0cbec..0790dacbc1e0a83e497253fc9e4ee6d17c2da9c2 100644 --- a/source/RobotAPI/libraries/aron/core/io/typeIO/Writer.h +++ b/source/RobotAPI/libraries/aron/core/io/typeIO/Writer.h @@ -30,7 +30,6 @@ #include <RobotAPI/libraries/aron/core/Config.h> - namespace armarx::aron::typeIO { class WriterInterface; @@ -91,6 +90,13 @@ namespace armarx::aron::typeIO }; virtual void writeEigenQuaternion(const WriteEigenQuaternionInput&) = 0; + struct WriteImageInput + { + std::string pixelType; + type::Maybe maybe; + }; + virtual void writeImage(const WriteImageInput&) = 0; + struct WriteIVTCByteImageInput { type::Maybe maybe; diff --git a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.cpp b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.cpp index 6a23d549a4ea915cfecc8e7645c88c7945355797..96290019ed99cb9ee80b489d6668cdb54769e38d 100644 --- a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.cpp +++ b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.cpp @@ -18,17 +18,15 @@ * GNU General Public License */ -// STD/STL -#include <memory> -#include <numeric> - -// Header #include "NavigatorWriter.h" -// ArmarX #include <RobotAPI/libraries/aron/core/navigator/data/AllNavigators.h> #include <RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h> +#include <memory> +#include <numeric> + + namespace armarx::aron::typeIO::writer { // generate Path info @@ -154,144 +152,111 @@ namespace armarx::aron::typeIO::writer } } - void NavigatorWriter::writeEigenMatrix(const WriteEigenMatrixInput& o) + + template <class ElementT, class InputT> + std::shared_ptr<ElementT> + NavigatorWriter::writeElement(const InputT& input) { Path path = generatePath(); NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::EigenMatrixNavigator>(path); + auto type = std::make_shared<ElementT>(path); + type->setMaybe(input.maybe); + token->addElement(type); + + return type; + } + + + void NavigatorWriter::writeEigenMatrix(const WriteEigenMatrixInput& o) + { + auto type = writeElement<typenavigator::EigenMatrixNavigator>(o); + type->setRows(o.rows); type->setCols(o.cols); type->setTypename(o.type); - type->setMaybe(o.maybe); - token->addElement(type); } void NavigatorWriter::writeEigenQuaternion(const WriteEigenQuaternionInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::EigenQuaternionNavigator>(path); + auto type = writeElement<typenavigator::EigenQuaternionNavigator>(o); + type->setTypename(o.type); - type->setMaybe(o.maybe); - token->addElement(type); } + + void NavigatorWriter::writeImage(const WriteImageInput& o) + { + auto type = writeElement<typenavigator::ImageNavigator>(o); + + type->setPixelType(o.pixelType); + } + + void NavigatorWriter::writeIVTCByteImage(const WriteIVTCByteImageInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::IVTCByteImageNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::IVTCByteImageNavigator>(o); } void NavigatorWriter::writeOpenCVMat(const WriteOpenCVMatInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::OpenCVMatNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::OpenCVMatNavigator>(o); } void NavigatorWriter::writePCLPointCloud(const WritePCLPointCloudInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::PCLPointCloudNavigator>(path); + auto type = writeElement<typenavigator::PCLPointCloudNavigator>(o); + type->setTypename(o.type); - type->setMaybe(o.maybe); - token->addElement(type); } void NavigatorWriter::writePosition(const WritePositionInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::PositionNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::PositionNavigator>(o); } void NavigatorWriter::writeOrientation(const WriteOrientationInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::OrientationNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::OrientationNavigator>(o); } void NavigatorWriter::writePose(const WritePoseInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::PoseNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::PoseNavigator>(o); } void NavigatorWriter::writeInt(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::IntNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::IntNavigator>(o); } void NavigatorWriter::writeLong(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::LongNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::LongNavigator>(o); } void NavigatorWriter::writeFloat(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::FloatNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::FloatNavigator>(o); } void NavigatorWriter::writeDouble(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::DoubleNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::DoubleNavigator>(o); } void NavigatorWriter::writeString(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::StringNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::StringNavigator>(o); } void NavigatorWriter::writeBool(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::BoolNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::BoolNavigator>(o); } void NavigatorWriter::writeTime(const WritePrimitiveInput& o) { - Path path = generatePath(); - NavigatorWriterTokenPtr token = stack.top(); - auto type = std::make_shared<typenavigator::TimeNavigator>(path); - type->setMaybe(o.maybe); - token->addElement(type); + writeElement<typenavigator::TimeNavigator>(o); } void NavigatorWriter::writeKey(const std::string& k) diff --git a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h index 2586935e519799b7f7dd9c3f971a45bc4ab45d8f..80ca17960f4a454bf7c431ad64ce429835797403 100644 --- a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h +++ b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h @@ -20,17 +20,14 @@ #pragma once -// STD/STL -#include <memory> -#include <stack> - -// BaseClass +#include <RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriterToken.h> #include <RobotAPI/libraries/aron/core/io/typeIO/Writer.h> - -// ArmarX #include <RobotAPI/libraries/aron/core/Concepts.h> #include <RobotAPI/libraries/aron/core/navigator/type/Navigator.h> -#include <RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriterToken.h> + +#include <memory> +#include <stack> + namespace armarx::aron::typeIO::writer { @@ -56,6 +53,7 @@ namespace armarx::aron::typeIO::writer virtual void writeEigenMatrix(const WriteEigenMatrixInput&) override; virtual void writeEigenQuaternion(const WriteEigenQuaternionInput&) override; + virtual void writeImage(const WriteImageInput&) override; virtual void writeIVTCByteImage(const WriteIVTCByteImageInput&) override; virtual void writeOpenCVMat(const WriteOpenCVMatInput&) override; virtual void writePCLPointCloud(const WritePCLPointCloudInput&) override; @@ -80,10 +78,16 @@ namespace armarx::aron::typeIO::writer } private: + + Path generatePath(); + + template <class ElementT, class InputT> + std::shared_ptr<ElementT> writeElement(const InputT&); + + bool wroteInitialStartObject = false; NavigatorWriterTokenPtr lastRemovedToken = nullptr; std::stack<NavigatorWriterTokenPtr> stack = {}; - Path generatePath(); }; } diff --git a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.cpp b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.cpp index 7a4359559aaf5169ef1bdac195937d540e8b3646..aaafe280661a87ad411ab072a3dca5eed0fd7d53 100644 --- a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.cpp +++ b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.cpp @@ -148,6 +148,18 @@ namespace armarx::aron::typeIO::writer token->addElement(j); } + + void NlohmannJSONWriter::writeImage(const WriteImageInput& o) + { + auto token = stack.top(); + nlohmann::json j; + j[io::Data::READER_WRITER_MAYBE_SLUG] = o.maybe; + j[io::Data::READER_WRITER_NDARRAY_NAME_SLUG] = "Image"; + j["pixelType"] = o.pixelType; + token->addElement(j); + } + + void NlohmannJSONWriter::writeIVTCByteImage(const WriteIVTCByteImageInput& o) { auto token = stack.top(); diff --git a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h index 055a493c878fbb76b4fed7dc41d08e680a71d976..b1a9b65483db764f7fa576c9f626a0e5b70477ca 100644 --- a/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h +++ b/source/RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h @@ -53,6 +53,7 @@ namespace armarx::aron::typeIO::writer virtual void writeEigenMatrix(const WriteEigenMatrixInput&) override; virtual void writeEigenQuaternion(const WriteEigenQuaternionInput&) override; + virtual void writeImage(const WriteImageInput&) override; virtual void writeIVTCByteImage(const WriteIVTCByteImageInput&) override; virtual void writeOpenCVMat(const WriteOpenCVMatInput&) override; virtual void writePCLPointCloud(const WritePCLPointCloudInput&) override; diff --git a/source/RobotAPI/libraries/aron/core/navigator/data/complex/NDArray.cpp b/source/RobotAPI/libraries/aron/core/navigator/data/complex/NDArray.cpp index eb1a486374c836d8156d8055e543379de9840a47..cf568cef484224a6b24e5d292cfa910dee0b8994 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/data/complex/NDArray.cpp +++ b/source/RobotAPI/libraries/aron/core/navigator/data/complex/NDArray.cpp @@ -115,7 +115,7 @@ namespace armarx::aron::datanavigator void NDArrayNavigator::setData(unsigned int elements, const unsigned char* src) { aron->data = std::vector<unsigned char>(elements); - memcpy(aron->data.data(), src, elements); + std::memcpy(aron->data.data(), src, elements); } std::vector<int> NDArrayNavigator::getDimensions() const diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h b/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h index 82702de998bb7e6b0972afd9e96ae027b433eae3..3a09c0a35f884d02f904eeaceee9dbd8b7a0c3c4 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h +++ b/source/RobotAPI/libraries/aron/core/navigator/type/AllNavigators.h @@ -8,6 +8,7 @@ #include "ndarray/NDArray.h" #include "ndarray/EigenMatrix.h" #include "ndarray/EigenQuaternion.h" +#include "ndarray/Image.h" #include "ndarray/IVTCByteImage.h" #include "ndarray/OpenCVMat.h" #include "ndarray/Orientation.h" diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h b/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h index af5d62e7c0decbc296cea942fa1983b0e0cb5924..e735771a906f47337a2db04a71448c8932a40b28 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h +++ b/source/RobotAPI/libraries/aron/core/navigator/type/forward_declarations.h @@ -15,6 +15,7 @@ namespace armarx::aron::typenavigator using NDArrayNavigatorPtr = std::shared_ptr<class NDArrayNavigator>; using EigenMatrixNavigatorPtr = std::shared_ptr<class EigenMatrixNavigator>; using EigenQuaternionNavigatorPtr = std::shared_ptr<class EigenQuaternionNavigator>; + using ImageNavigatorPtr = std::shared_ptr<class ImageNavigator>; using IVTCByteImageNavigatorPtr = std::shared_ptr<class IVTCByteImageNavigator>; using OpenCVMatNavigatorPtr = std::shared_ptr<class OpenCVMatNavigator>; using OrientationNavigatorPtr = std::shared_ptr<class OrientationNavigator>; diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.cpp b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.cpp new file mode 100644 index 0000000000000000000000000000000000000000..dec13ece6cd10683ac5ffd6ac0f16af9c5a7e1a9 --- /dev/null +++ b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.cpp @@ -0,0 +1,130 @@ +/* + * This file is part of ArmarX. + * + * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), + * Karlsruhe Institute of Technology (KIT), all rights reserved. + * + * ArmarX is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * ArmarX is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + * @author Rainer Kartmann (rainer dot kartmann at kit dot edu) + * @copyright http://www.gnu.org/licenses/gpl-2.0.txt + * GNU General Public License + */ + +#include "Image.h" + +#include <RobotAPI/libraries/aron/core/Exception.h> + +#include <SimoxUtility/algorithm/string.h> +#include <SimoxUtility/meta/EnumNames.hpp> + + +namespace armarx::aron::typenavigator +{ + + static const simox::meta::EnumNames<ImagePixelType> ImagePixelTypeNames + { + { ImagePixelType::Rgb24, "rgb24" }, + { ImagePixelType::Depth32, "depth32" }, + }; + + + // constructors + ImageNavigator::ImageNavigator(const Path& path) : + aron::Navigator<type::Descriptor, type::AronType>::Navigator(type::Descriptor::eImage, path) + { + } + + + ImageNavigator::ImageNavigator(const type::AronImagePtr& o, const Path& path) : + aron::Navigator<type::Descriptor, type::AronType>::Navigator(type::Descriptor::eImage, path), + detail::NavigatorBase<type::AronImage, ImageNavigator>(o) + { + } + + + type::AronImagePtr ImageNavigator::toAronImagePtr() const + { + return this->aron; + } + + + ImagePixelType ImageNavigator::getPixelType() const + { + return pixelTypeFromName(this->aron->pixelType); + } + + void ImageNavigator::setPixelType(const ImagePixelType& pixelType) const + { + this->aron->pixelType = pixelTypeToName(pixelType); + } + + void ImageNavigator::setPixelType(const std::string& typeName) const + { + // Try a lookup, which throws when failing. + pixelTypeFromName(typeName); + this->aron->pixelType = typeName; + } + + + // virtual implementations + std::string ImageNavigator::getName() const + { + return "AronImageType"; + } + + + bool ImageNavigator::operator==(const ImageNavigator& other) const + { + return *this->aron == *other.aron; + } + + + std::string ImageNavigator::pixelTypeToName(ImagePixelType type) + { + try + { + return ImagePixelTypeNames.to_name(type); + } + catch (const simox::meta::error::UnknownEnumValue& e) + { + throw aron::error::AronException("ImageNavigator", __FUNCTION__, e.what()); + } + } + + + ImagePixelType ImageNavigator::pixelTypeFromName(const std::string& name) + { + try + { + return ImagePixelTypeNames.from_name(simox::alg::to_lower(name)); + } + catch (const simox::meta::error::UnknownEnumValue& e) + { + throw aron::error::AronException("ImageNavigator", __FUNCTION__, e.what()); + } + } + + + std::set<ImagePixelType> ImageNavigator::pixelTypes() + { + return ImagePixelTypeNames.values(); + } + + std::set<std::string> ImageNavigator::pixelTypeNames() + { + return ImagePixelTypeNames.names(); + } + +} + diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.h b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.h new file mode 100644 index 0000000000000000000000000000000000000000..a725dfd161c9534902e10acd4c4a20e8183320ca --- /dev/null +++ b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/Image.h @@ -0,0 +1,79 @@ +/* + * This file is part of ArmarX. + * + * Copyright (C) 2012-2016, High Performance Humanoid Technologies (H2T), + * Karlsruhe Institute of Technology (KIT), all rights reserved. + * + * ArmarX is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License version 2 as + * published by the Free Software Foundation. + * + * ArmarX is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see <http://www.gnu.org/licenses/>. + * + * @author Rainer Kartmann (rainer dot kartmann at kit dot edu) + * @copyright http://www.gnu.org/licenses/gpl-2.0.txt + * GNU General Public License + */ + +#pragma once + +#include <RobotAPI/libraries/aron/core/navigator/type/detail/NDArrayNavigatorBase.h> + +#include <memory> +#include <string> + + +namespace armarx::aron::typenavigator +{ + enum class ImagePixelType + { + /// 3 (8-bit) byte channels for R, G, and B. + Rgb24, // ==> CV_8UC1 + /// 1 (32-bit) float channel for depth. + Depth32, // ==> CV_32FC1 + }; + + + class ImageNavigator : + virtual public detail::NDArrayNavigatorBase<type::AronImage, ImageNavigator> + { + public: + + ImageNavigator(const Path& path = {}); + ImageNavigator(const type::AronImagePtr&, const Path& path); + + + type::AronImagePtr toAronImagePtr() const; + + /// Get the pixel type. + ImagePixelType getPixelType() const; + void setPixelType(const ImagePixelType& type) const; + void setPixelType(const std::string& typeName) const; + + + // virtual implementations + virtual std::string getName() const override; + + + // operators + virtual bool operator==(const ImageNavigator&) const override; + + + public: + + static std::string pixelTypeToName(ImagePixelType type); + static ImagePixelType pixelTypeFromName(const std::string& name); + static std::set<ImagePixelType> pixelTypes(); + static std::set<std::string> pixelTypeNames(); + + }; + + using ImageNavigatorPtr = std::shared_ptr<ImageNavigator>; + +} diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.cpp b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.cpp index 2d41e10ab7c13af0fbfcba8d59919830ce37dd1a..bf805025d848c2d405c359d595edd7d4e7a94adc 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.cpp +++ b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.cpp @@ -26,18 +26,21 @@ namespace armarx::aron::typenavigator { + // constructors OpenCVMatNavigator::OpenCVMatNavigator(const Path& path) : aron::Navigator<type::Descriptor, type::AronType>::Navigator(type::Descriptor::eOpenCVMat, path) { } + OpenCVMatNavigator::OpenCVMatNavigator(const type::AronOpenCVMatPtr& o, const Path& path) : aron::Navigator<type::Descriptor, type::AronType>::Navigator(type::Descriptor::eOpenCVMat, path), detail::NavigatorBase<type::AronOpenCVMat, OpenCVMatNavigator>(o) { } + // operators bool OpenCVMatNavigator::operator==(const OpenCVMatNavigator& other) const { @@ -48,15 +51,42 @@ namespace armarx::aron::typenavigator return true; } + type::AronOpenCVMatPtr OpenCVMatNavigator::toAronOpenCVMatPtr() const { return this->aron; } + + std::vector<int> OpenCVMatNavigator::getShape() const + { + return this->aron->shape; + } + + + void OpenCVMatNavigator::setShape(const std::vector<int>& shape) const + { + this->aron->shape = shape; + } + + + std::string OpenCVMatNavigator::getTypeName() const + { + return this->aron->typeName; + } + + + void OpenCVMatNavigator::setTypeName(const std::string& typeName) + { + this->aron->typeName = typeName; + } + + // virtual implementations std::string OpenCVMatNavigator::getName() const { return "AronOpenCVMatType"; } + } diff --git a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.h b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.h index 74e4e285540a66823409c8272b707d825e78ba40..46c62277da75e4c785137aa948b5388fefb8035e 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.h +++ b/source/RobotAPI/libraries/aron/core/navigator/type/ndarray/OpenCVMat.h @@ -30,6 +30,7 @@ // Base class #include "../detail/NDArrayNavigatorBase.h" + namespace armarx::aron::typenavigator { class OpenCVMatNavigator; @@ -49,9 +50,16 @@ namespace armarx::aron::typenavigator // public member functions type::AronOpenCVMatPtr toAronOpenCVMatPtr() const; + std::vector<int> getShape() const; + void setShape(const std::vector<int>& shape) const; + + std::string getTypeName() const; + void setTypeName(const std::string& typeName); + // virtual implementations virtual std::string getName() const override; + public: const std::map<std::string, std::vector<std::string>> ACCEPTED_TYPES = { diff --git a/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.cpp b/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.cpp index e99a7f91658f88611d9884d9795fb8e36b2a8485..fe98e3abe1d839928f9e3a78c2e52cb0e0717a20 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.cpp +++ b/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.cpp @@ -155,6 +155,10 @@ namespace armarx::aron::visitor { return visit(*t, key, dynamic_cast<NDArrayDataNavigator&>(data)); } + else if (auto t = dynamic_cast<ImageNavigator*>(&type)) + { + return visit(*t, key, dynamic_cast<NDArrayDataNavigator&>(data)); + } else if (auto t = dynamic_cast<IVTCByteImageTypeNavigator*>(&type)) { return visit(*t, key, dynamic_cast<NDArrayDataNavigator&>(data)); diff --git a/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.h b/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.h index f577903a4524da4ce220d6d402e9719f1afdac7a..b2efdaa79f0a8813c0a753822851789378ce73c7 100644 --- a/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.h +++ b/source/RobotAPI/libraries/aron/core/navigator/visitors/TypedDataVisitor.h @@ -79,6 +79,7 @@ namespace armarx::aron::visitor // Array-valued using EigenMatrixTypeNavigator = typenavigator::EigenMatrixNavigator; using EigenQuaternionTypeNavigator = typenavigator::EigenQuaternionNavigator; + using ImageNavigator = typenavigator::ImageNavigator; using IVTCByteImageTypeNavigator = typenavigator::IVTCByteImageNavigator; using OpenCVMatTypeNavigator = typenavigator::OpenCVMatNavigator; using PCLPointCloudTypeNavigator = typenavigator::PCLPointCloudNavigator; @@ -193,6 +194,11 @@ namespace armarx::aron::visitor (void) type, (void) data; return true; } + virtual bool visit(ImageNavigator& type, NDArrayDataNavigator& data) + { + (void) type, (void) data; + return true; + } virtual bool visit(IVTCByteImageTypeNavigator& type, NDArrayDataNavigator& data) { (void) type, (void) data; @@ -323,6 +329,11 @@ namespace armarx::aron::visitor (void) type, (void) key; return visit(type, data); } + virtual bool visit(ImageNavigator& type, const std::string& key, NDArrayDataNavigator& data) + { + (void) type, (void) key; + return visit(type, data); + } virtual bool visit(IVTCByteImageTypeNavigator& type, const std::string& key, NDArrayDataNavigator& data) { (void) type, (void) key; diff --git a/source/RobotAPI/libraries/aron/core/test/CMakeLists.txt b/source/RobotAPI/libraries/aron/core/test/CMakeLists.txt index 9ea4438bbe3381ee9c92ae3cd4d6c656606e916c..4bc9abcc6c2e42529d3c80a5036a5af1a8e4f100 100644 --- a/source/RobotAPI/libraries/aron/core/test/CMakeLists.txt +++ b/source/RobotAPI/libraries/aron/core/test/CMakeLists.txt @@ -49,6 +49,7 @@ armarx_add_test( aron/EigenQuaternionTest.xml aron/EnumTest.xml aron/HumanPoseTest.xml + aron/ImageTest.xml aron/IVTCByteImageTest.xml aron/ListTest.xml aron/NaturalIKTest.xml diff --git a/source/RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.xml b/source/RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.xml index a5760ba3b259ab6824f8a9bcb1fb9c5cd5855f53..cc175020464ffa683fe102c0fc93a7c27011c34a 100644 --- a/source/RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.xml +++ b/source/RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.xml @@ -2,19 +2,23 @@ <?xml version="1.0" encoding="UTF-8" ?> <AronTypeDefinition> <CodeIncludes> - <Include include="<Eigen/Core>" /> <Include include="<Eigen/Geometry>" /> </CodeIncludes> <AronIncludes> </AronIncludes> <GenerateTypes> + <Object name='armarx::EigenQuaternionTest'> - <ObjectChild key='the_float_eigen_matrix'> + + <ObjectChild key='the_float_quaternion'> <EigenQuaternion type="float" /> </ObjectChild> - <ObjectChild key='the_double_eigen_matrix'> + + <ObjectChild key='the_double_quaternion'> <EigenQuaternion type="double" /> </ObjectChild> + </Object> + </GenerateTypes> </AronTypeDefinition> diff --git a/source/RobotAPI/libraries/aron/core/test/aron/ImageTest.xml b/source/RobotAPI/libraries/aron/core/test/aron/ImageTest.xml new file mode 100644 index 0000000000000000000000000000000000000000..ab88fd71efc2e0e654296c734fdcb07d0eef7b12 --- /dev/null +++ b/source/RobotAPI/libraries/aron/core/test/aron/ImageTest.xml @@ -0,0 +1,20 @@ +<!-- An RGB and a depth image. --> +<?xml version="1.0" encoding="UTF-8" ?> +<AronTypeDefinition> + <CodeIncludes> + <Include include="<opencv2/core/core.hpp>" /> + </CodeIncludes> + <GenerateTypes> + <Object name='armarx::ImageTest'> + + <ObjectChild key='the_rgb24_image'> + <Image pixelType="rgb24" /> + </ObjectChild> + + <ObjectChild key='the_depth32_image'> + <Image pixelType="depth32" /> + </ObjectChild> + + </Object> + </GenerateTypes> +</AronTypeDefinition> diff --git a/source/RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.xml b/source/RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.xml index f4179798c6ed36ee9f48373ebe57c921bfcf448d..1eb67f338db680eb65aa3e8c2bf25e9229f4b0fa 100644 --- a/source/RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.xml +++ b/source/RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.xml @@ -6,18 +6,27 @@ </CodeIncludes> <GenerateTypes> <Object name='armarx::OpenCVMatTest'> - <ObjectChild key='the_2d_opencv_matrix'> - <OpenCVMat dimensions="25, 25" type="64F" /> + + <ObjectChild key='the_rgb24_image'> + <Image pixelType="rgb24" /> + </ObjectChild> + + <ObjectChild key='the_depth32_image'> + <Image pixelType="depth32" /> + </ObjectChild> + + <!--ObjectChild key='the_2d_opencv_matrix'> + <OpenCVMat shape="25, 25" type="64F" /> </ObjectChild> <ObjectChild key='the_3d_opencv_matrix'> - <OpenCVMat dimensions="25, 25, 25" type="CV_32F" /> + <OpenCVMat shape="25, 25, 25" type="CV_32F" /> </ObjectChild> <ObjectChild key='the_4d_opencv_matrix'> - <OpenCVMat dimensions="25, 25, 25, 25" type="CV_32S" /> + <OpenCVMat shape="25, 25, 25, 25" type="CV_32S" /> </ObjectChild> <ObjectChild key='the_5d_opencv_matrix'> - <OpenCVMat dimensions="25, 25, 25, 25, 25" type="16U" /> - </ObjectChild> + <OpenCVMat shape="25, 25, 25, 25, 25" type="16U" /> + </ObjectChild--> </Object> </GenerateTypes> </AronTypeDefinition> diff --git a/source/RobotAPI/libraries/aron/core/test/aronCodeGenerationTest.cpp b/source/RobotAPI/libraries/aron/core/test/aronCodeGenerationTest.cpp index f2867d76e57bc81c17e00eeb56caf14a8a558743..44bbb19a9bad2cb37d6ba4fc9305a0f4bb05f979 100644 --- a/source/RobotAPI/libraries/aron/core/test/aronCodeGenerationTest.cpp +++ b/source/RobotAPI/libraries/aron/core/test/aronCodeGenerationTest.cpp @@ -47,6 +47,7 @@ #include <RobotAPI/libraries/aron/core/test/aron/DictTest.aron.generated.h> #include <RobotAPI/libraries/aron/core/test/aron/PrimitiveTest.aron.generated.h> #include <RobotAPI/libraries/aron/core/test/aron/ObjectTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/ImageTest.aron.generated.h> #include <RobotAPI/libraries/aron/core/test/aron/IVTCByteImageTest.aron.generated.h> #include <RobotAPI/libraries/aron/core/test/aron/EigenMatrixTest.aron.generated.h> #include <RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.aron.generated.h> diff --git a/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp b/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp index 395de492cc22ef4e80665f4477e648046d329cf8..4ff0724c95ca3c0cbc31dd051b6ba3afdff37fe9 100644 --- a/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp +++ b/source/RobotAPI/libraries/aron/core/test/aronRandomizedTest.cpp @@ -24,11 +24,46 @@ #define ARMARX_BOOST_TEST -// STD/STL -#include <iostream> -#include <cstdlib> -#include <ctime> -#include <numeric> + +// Generated File - include them first to check whether their includes are complete. +#include <RobotAPI/libraries/aron/core/test/aron/ListTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/DictTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/PrimitiveTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/ObjectTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/ImageTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/IVTCByteImageTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/EigenMatrixTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/PCLPointCloudTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/PositionTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/OrientationTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/PoseTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/EnumTest.aron.generated.h> +#include <RobotAPI/libraries/aron/core/test/aron/OptionalTest.aron.generated.h> + +// Aron +#include <RobotAPI/libraries/aron/core/Debug.h> +#include <RobotAPI/libraries/aron/core/Randomizer.h> + +#include <RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.h> +#include <RobotAPI/libraries/aron/core/io/dataIO/reader/nlohmannJSON/NlohmannJSONReader.h> + +#include <RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.h> +#include <RobotAPI/libraries/aron/core/io/dataIO/writer/nlohmannJSON/NlohmannJSONWriter.h> + +#include <RobotAPI/libraries/aron/core/io/typeIO/reader/navigator/NavigatorReader.h> +#include <RobotAPI/libraries/aron/core/io/typeIO/reader/nlohmannJSON/NlohmannJSONReader.h> + +#include <RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h> +#include <RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h> + + +// ArmarX +#include <ArmarXCore/libraries/cppgen/CppMethod.h> +#include <ArmarXCore/libraries/cppgen/CppClass.h> +#include <RobotAPI/libraries/aron/core/Exception.h> + // IVT #include <Image/ByteImage.h> @@ -43,226 +78,201 @@ #include <pcl/point_cloud.h> #include <pcl/point_types.h> -// Test -#include <RobotAPI/Test.h> - -// ArmarX -#include <ArmarXCore/libraries/cppgen/CppMethod.h> -#include <ArmarXCore/libraries/cppgen/CppClass.h> -#include <RobotAPI/libraries/aron/core/Exception.h> - -// Aron -#include <RobotAPI/libraries/aron/core/Debug.h> -#include <RobotAPI/libraries/aron/core/Randomizer.h> -#include <RobotAPI/libraries/aron/core/io/dataIO/reader/navigator/NavigatorReader.h> -#include <RobotAPI/libraries/aron/core/io/dataIO/reader/nlohmannJSON/NlohmannJSONReader.h> +// STD/STL +#include <iostream> +#include <cstdlib> +#include <ctime> +#include <numeric> -#include <RobotAPI/libraries/aron/core/io/dataIO/writer/navigator/NavigatorWriter.h> -#include <RobotAPI/libraries/aron/core/io/dataIO/writer/nlohmannJSON/NlohmannJSONWriter.h> -#include <RobotAPI/libraries/aron/core/io/typeIO/reader/navigator/NavigatorReader.h> -#include <RobotAPI/libraries/aron/core/io/typeIO/reader/nlohmannJSON/NlohmannJSONReader.h> +// Test +#include <RobotAPI/Test.h> -#include <RobotAPI/libraries/aron/core/io/typeIO/writer/navigator/NavigatorWriter.h> -#include <RobotAPI/libraries/aron/core/io/typeIO/writer/nlohmannJSON/NlohmannJSONWriter.h> // Files without code generation //#include "aronDataWithoutCodeGeneration.h" -// Generated File -#include <RobotAPI/libraries/aron/core/test/aron/ListTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/DictTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/PrimitiveTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/ObjectTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/IVTCByteImageTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/EigenMatrixTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/EigenQuaternionTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/OpenCVMatTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/PCLPointCloudTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/PositionTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/OrientationTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/PoseTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/EnumTest.aron.generated.h> -#include <RobotAPI/libraries/aron/core/test/aron/OptionalTest.aron.generated.h> using namespace armarx; using namespace aron; + template <typename T> -void runTestWithInstances(T& k1, T& k2) +void test_toAronType(T& in, T& out) { - // assumes not nullptrs as k1 and k2. If you have a maybe type then make sure that it is set properly + nlohmann::json in_type_json; + nlohmann::json out_type_json; - int echo_debug_lv = 1; + BOOST_TEST_CONTEXT("getting in type") + { + typenavigator::ObjectNavigatorPtr in_type_nav = in.toAronType(); - Randomizer r; + type::AronObjectPtr in_type = in_type_nav->toAronObjectPtr(); + BOOST_CHECK(in_type); + + armarx::aron::typeIO::writer::NlohmannJSONWriter json_writer_in; + in.writeType(json_writer_in); + in_type_json = json_writer_in.getResult(); + BOOST_CHECK(in_type_json.is_object()); + } + BOOST_TEST_CONTEXT("getting out type") { - if (echo_debug_lv) - { - std::cout << "\t getting type 1" << std::endl; - } - typenavigator::ObjectNavigatorPtr k1_type_nav = k1.toAronType(); - type::AronObjectPtr k1_type = k1_type_nav->toAronObjectPtr(); - BOOST_CHECK_EQUAL((bool) k1_type, true); + typenavigator::ObjectNavigatorPtr out_type_nav = out.toAronType(); - armarx::aron::typeIO::writer::NlohmannJSONWriter json_writer_k1; - k1.writeType(json_writer_k1); - nlohmann::json k1_type_json = json_writer_k1.getResult(); - BOOST_CHECK_EQUAL(k1_type_json.is_object(), true); + type::AronObjectPtr out_type = out_type_nav->toAronObjectPtr(); + BOOST_CHECK(out_type); - if (echo_debug_lv) - { - std::cout << "\t getting type 2" << std::endl; - } - typenavigator::ObjectNavigatorPtr k2_type_nav = k2.toAronType(); - type::AronObjectPtr k2_type = k2_type_nav->toAronObjectPtr(); - BOOST_CHECK_EQUAL((bool) k2_type, true); - - armarx::aron::typeIO::writer::NlohmannJSONWriter json_writer_k2; - k2.writeType(json_writer_k2); - nlohmann::json k2_type_json = json_writer_k2.getResult(); - BOOST_CHECK_EQUAL(k2_type_json.is_object(), true); - BOOST_CHECK_EQUAL(k1_type_json.dump(2), k2_type_json.dump(2)); + armarx::aron::typeIO::writer::NlohmannJSONWriter json_writer_out; + out.writeType(json_writer_out); + out_type_json = json_writer_out.getResult(); + BOOST_CHECK(out_type_json.is_object()); } - { - typenavigator::ObjectNavigatorPtr k1_type_nav = k1.toAronType(); - datanavigator::DictNavigatorPtr k1_aron_nav = k1.toAron(); + BOOST_CHECK_EQUAL(out_type_json.dump(2), in_type_json.dump(2)); +} - if (echo_debug_lv) - { - std::cout << "\t initialize aron 1 randomly" << std::endl; - } - r.initializeRandomly(k1_aron_nav, k1_type_nav); - if (echo_debug_lv) - { - std::cout << "\t getting aron 1" << std::endl; - } - data::AronDictPtr k1_aron = k1_aron_nav->toAronDictPtr(); - BOOST_CHECK_EQUAL((bool) k1_aron, true); - if (echo_debug_lv >= 2) - { - std::cout << "K1 Aron:" << std::endl; - std::cout << armarx::aron::Debug::AronDataPtrToString(k1_aron) << std::endl; - std::cout << "K2 Aron:" << std::endl; - std::cout << armarx::aron::Debug::AronDataPtrToString(k2.toAron()->toAronDictPtr()) << std::endl; - } - if (echo_debug_lv) - { - std::cout << "\t setting aron 2 from aron 1" << std::endl; - } - k2.fromAron(k1_aron); +template <typename T> +void test_toAron(T& in, T& out) +{ + datanavigator::DictNavigatorPtr in_aron_nav = in.toAron(); + Randomizer r; - if (echo_debug_lv) - { - std::cout << "\t getting aron 2" << std::endl; - } - datanavigator::DictNavigatorPtr k2_aron_nav = k2.toAron(); - BOOST_CHECK_EQUAL((*k1_aron_nav == *k2_aron_nav), true); + BOOST_TEST_CONTEXT("initialize in aron randomly") + { + typenavigator::ObjectNavigatorPtr in_type_nav = in.toAronType(); + r.initializeRandomly(in_aron_nav, in_type_nav); + } - data::AronDictPtr k2_aron = k2_aron_nav->toAronDictPtr(); - BOOST_CHECK_EQUAL((bool) k2_aron, true); + BOOST_TEST_INFO("getting in aron"); + data::AronDictPtr in_aron = in_aron_nav->toAronDictPtr(); + BOOST_CHECK(in_aron); - if (echo_debug_lv) - { - std::cout << "\t setting aron 1 from aron 2 and check for equality" << std::endl; - } - k1.fromAron(k2_aron_nav); + BOOST_TEST_MESSAGE("in aron: \n" << armarx::aron::Debug::AronDataPtrToString(in_aron)); + BOOST_TEST_MESSAGE("out aron: \n" << armarx::aron::Debug::AronDataPtrToString(out.toAron()->toAronDictPtr())); - if (echo_debug_lv >= 2) - { - std::cout << "K1 Aron:" << std::endl; - std::cout << armarx::aron::Debug::AronDataPtrToString(k1.toAron()->toAronDictPtr()) << std::endl; - std::cout << "K2 Aron:" << std::endl; - std::cout << armarx::aron::Debug::AronDataPtrToString(k2.toAron()->toAronDictPtr()) << std::endl; - } - BOOST_CHECK_EQUAL((k1 == k2), true); + datanavigator::DictNavigatorPtr out_aron_nav; + BOOST_TEST_CONTEXT("setting out aron from in aron") + { + out.fromAron(in_aron); - datanavigator::DictNavigatorPtr k1_aron_nav_again = k1.toAron(); - BOOST_CHECK_EQUAL((*k1_aron_nav == *k1_aron_nav_again), true); + BOOST_TEST_INFO("getting out aron"); + out_aron_nav = out.toAron(); + BOOST_CHECK(*in_aron_nav == *out_aron_nav); + + data::AronDictPtr out_aron = out_aron_nav->toAronDictPtr(); + BOOST_CHECK(out_aron); } + BOOST_TEST_CONTEXT("setting in aron from out aron and check for equality") { - typenavigator::ObjectNavigatorPtr k1_type_nav = k1.toAronType(); - datanavigator::DictNavigatorPtr k1_aron_nav = k1.toAron(); + in.fromAron(out_aron_nav); - r.initializeRandomly(k1_aron_nav, k1_type_nav); + BOOST_TEST_MESSAGE("in Aron: \n" << armarx::aron::Debug::AronDataPtrToString(in.toAron()->toAronDictPtr())); + BOOST_TEST_MESSAGE("out Aron: \n" << armarx::aron::Debug::AronDataPtrToString(out.toAron()->toAronDictPtr())); + BOOST_CHECK(in == out); - data::AronDictPtr k1_aron = k1_aron_nav->toAronDictPtr(); - k1.fromAron(k1_aron); + datanavigator::DictNavigatorPtr in_aron_nav_again = in.toAron(); + BOOST_CHECK(*in_aron_nav == *in_aron_nav_again); + } +} - if (echo_debug_lv) - { - std::cout << "\t check JSON export of k and k2 for equality" << std::endl; - } - armarx::aron::dataIO::writer::NlohmannJSONWriter json_writer_for_k1; - armarx::aron::dataIO::writer::NlohmannJSONWriter json_writer_for_k2; - k1.write(json_writer_for_k1); - nlohmann::json k1_aron_json = json_writer_for_k1.getResult(); - std::string k1_aron_json_str = k1_aron_json.dump(4); +template <typename T> +void test_toJson(T& in, T& out) +{ + datanavigator::DictNavigatorPtr in_aron_nav = in.toAron(); - armarx::aron::dataIO::writer::NlohmannJSONWriter direct_json_writer_for_k1; - armarx::aron::dataIO::Visitor::VisitAndSetup(direct_json_writer_for_k1, k1_aron); - nlohmann::json direct_k1_aron_json = direct_json_writer_for_k1.getResult(); - std::string direct_k1_aron_json_str = direct_k1_aron_json.dump(4); + Randomizer r; + { + typenavigator::ObjectNavigatorPtr in_type_nav = in.toAronType(); + r.initializeRandomly(in_aron_nav, in_type_nav); + } - if (echo_debug_lv >= 2) - { - std::cout << "\t K1 as json: " << std::endl << k1_aron_json_str << std::endl; - std::cout << "\t K1 as direct json: " << std::endl << direct_k1_aron_json_str << std::endl; - } - BOOST_CHECK_EQUAL((k1_aron_json_str == direct_k1_aron_json_str), true); + data::AronDictPtr in_aron = in_aron_nav->toAronDictPtr(); + in.fromAron(in_aron); - armarx::aron::dataIO::reader::NlohmannJSONReader json_reader_for_k2(k1_aron_json); + armarx::aron::dataIO::writer::NlohmannJSONWriter json_writer_for_in; + armarx::aron::dataIO::writer::NlohmannJSONWriter json_writer_for_out; - k2.read(json_reader_for_k2); - k2.write(json_writer_for_k2); + nlohmann::json in_aron_json; + std::string in_aron_json_str; + BOOST_TEST_CONTEXT("check JSON export of k and out for equality") + { + in.write(json_writer_for_in); + in_aron_json = json_writer_for_in.getResult(); + in_aron_json_str = in_aron_json.dump(4); - nlohmann::json k2_aron_json = json_writer_for_k2.getResult(); - std::string k2_aron_json_str = k2_aron_json.dump(4); + armarx::aron::dataIO::writer::NlohmannJSONWriter direct_json_writer_for_in; + armarx::aron::dataIO::Visitor::VisitAndSetup(direct_json_writer_for_in, in_aron); + nlohmann::json direct_in_aron_json = direct_json_writer_for_in.getResult(); + std::string direct_in_aron_json_str = direct_in_aron_json.dump(4); - if (echo_debug_lv >= 2) + BOOST_TEST_CONTEXT( "\n> in as json: \n" << in_aron_json_str + << "\n> n as direct json: \n" << direct_in_aron_json_str) { - std::cout << "\t K1 as json: " << std::endl << k1_aron_json_str << std::endl; - std::cout << "\t K2 as json: " << std::endl << k2_aron_json_str << std::endl; + BOOST_CHECK(in_aron_json_str == direct_in_aron_json_str); } - BOOST_CHECK_EQUAL((k1_aron_json_str == k2_aron_json_str), true); + } + + armarx::aron::dataIO::reader::NlohmannJSONReader json_reader_for_out(in_aron_json); + + out.read(json_reader_for_out); + out.write(json_writer_for_out); + + nlohmann::json out_aron_json = json_writer_for_out.getResult(); + std::string out_aron_json_str = out_aron_json.dump(4); + + BOOST_TEST_CONTEXT( "\n> in as json: \n" << in_aron_json_str + << "\n> out as json: \n" << out_aron_json_str) + { + BOOST_CHECK(in_aron_json_str == out_aron_json_str); } } -BOOST_AUTO_TEST_CASE(AronListTest) + +template <typename T> +void runTestWithInstances(T& in, T& out) +{ + // assumes not nullptrs as in and out. If you have a maybe type then make sure that it is set properly + + test_toAronType(in, out); + test_toAron(in, out); + test_toJson(in, out); +} + + +BOOST_AUTO_TEST_CASE(test_List) { - std::cout << "Running List test" << std::endl; + BOOST_TEST_MESSAGE("Running List test"); ListTest l; ListTest l2; runTestWithInstances<ListTest>(l, l2); } -BOOST_AUTO_TEST_CASE(AronDictTest) +BOOST_AUTO_TEST_CASE(test_Dict) { - std::cout << "Running Dict test" << std::endl; + BOOST_TEST_MESSAGE("Running Dict test"); DictTest d; DictTest d2; runTestWithInstances<DictTest>(d, d2); } -BOOST_AUTO_TEST_CASE(AronPrimitiveTest) +BOOST_AUTO_TEST_CASE(test_Primitive) { - std::cout << "Running Primitive test" << std::endl; + BOOST_TEST_MESSAGE("Running Primitive test"); PrimitiveTest p; PrimitiveTest p2; runTestWithInstances<PrimitiveTest>(p, p2); } -BOOST_AUTO_TEST_CASE(AronObjectTest) +BOOST_AUTO_TEST_CASE(test_Object) { - std::cout << "Running Object test" << std::endl; + BOOST_TEST_MESSAGE("Running Object test"); ObjectTest1 o1; ObjectTest1 o12; runTestWithInstances<ObjectTest1>(o1, o12); @@ -272,9 +282,9 @@ BOOST_AUTO_TEST_CASE(AronObjectTest) runTestWithInstances<ObjectTest2>(o2, o22); } -BOOST_AUTO_TEST_CASE(AronImageTest) +BOOST_AUTO_TEST_CASE(test_IVTCByteImage) { - std::cout << "Running Image test" << std::endl; + BOOST_TEST_MESSAGE("Running Image test"); IVTCByteImageTest ii; IVTCByteImageTest ii2; @@ -293,32 +303,36 @@ BOOST_AUTO_TEST_CASE(AronImageTest) runTestWithInstances<IVTCByteImageTest>(ii, ii2); } -BOOST_AUTO_TEST_CASE(AronEigenMatrixTest) +BOOST_AUTO_TEST_CASE(test_EigenMatrix) { // Eigen may cause problems with dimensions > 145 - std::cout << "Running EigenMatrix test" << std::endl; + BOOST_TEST_MESSAGE("Running EigenMatrix test"); EigenMatrixTest em; EigenMatrixTest em2; runTestWithInstances<EigenMatrixTest>(em, em2); } -BOOST_AUTO_TEST_CASE(AronOpenCVTest) +BOOST_AUTO_TEST_CASE(test_Image) { - std::cout << "Running OpenCVMat test" << std::endl; - OpenCVMatTest ocv; - OpenCVMatTest ocv2; - - ocv.the_2d_opencv_matrix = cv::Mat(2, 2, CV_64F); - ocv.the_3d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2}), CV_32F); - ocv.the_4d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2, 2}), CV_16S); - ocv.the_5d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2, 2, 2}), CV_8U); - - runTestWithInstances<OpenCVMatTest>(ocv, ocv2); + BOOST_TEST_MESSAGE("Running Image test"); + ImageTest image; + ImageTest image2; + + image.the_rgb24_image.create(3, 4, image.the_rgb24_image.type()); + image.the_depth32_image.create(3, 4, image.the_depth32_image.type()); + + /* Could be used for ndarray test + image.the_2d_opencv_matrix = cv::Mat(2, 2, CV_64F); + image.the_3d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2}), CV_32F); + image.the_4d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2, 2}), CV_16S); + image.the_5d_opencv_matrix = cv::Mat(std::vector<int>({2, 2, 2, 2, 2}), CV_8U); + */ + runTestWithInstances<ImageTest>(image, image2); } -BOOST_AUTO_TEST_CASE(AronPCLPointCloudTest) +BOOST_AUTO_TEST_CASE(test_PCLPointCloud) { - std::cout << "Running PCLPointCloud test" << std::endl; + BOOST_TEST_MESSAGE("Running PCLPointCloud test"); PointCloudTest pc; PointCloudTest pc2; @@ -331,41 +345,41 @@ BOOST_AUTO_TEST_CASE(AronPCLPointCloudTest) runTestWithInstances<PointCloudTest>(pc, pc2); } -BOOST_AUTO_TEST_CASE(AronEigenQuaternionTest) +BOOST_AUTO_TEST_CASE(test_EigenQuaternion) { - std::cout << "Running EigenQuaternion test" << std::endl; + BOOST_TEST_MESSAGE("Running EigenQuaternion test"); EigenQuaternionTest eq; EigenQuaternionTest eq2; runTestWithInstances<EigenQuaternionTest>(eq, eq2); } -BOOST_AUTO_TEST_CASE(AronPositionTest) +BOOST_AUTO_TEST_CASE(test_Position) { - std::cout << "Running Position test" << std::endl; + BOOST_TEST_MESSAGE("Running Position test"); PositionTest pc; PositionTest pc2; runTestWithInstances<PositionTest>(pc, pc2); } -BOOST_AUTO_TEST_CASE(AronOrientationTest) +BOOST_AUTO_TEST_CASE(test_Orientation) { - std::cout << "Running Orientation test" << std::endl; + BOOST_TEST_MESSAGE("Running Orientation test"); OrientationTest pc; OrientationTest pc2; runTestWithInstances<OrientationTest>(pc, pc2); } -BOOST_AUTO_TEST_CASE(AronPoseTest) +BOOST_AUTO_TEST_CASE(test_Pose) { - std::cout << "Running Pose test" << std::endl; + BOOST_TEST_MESSAGE("Running Pose test"); PoseTest pc; PoseTest pc2; runTestWithInstances<PoseTest>(pc, pc2); } -BOOST_AUTO_TEST_CASE(AronOptionalTest) +BOOST_AUTO_TEST_CASE(test_Optional) { - std::cout << "Running Optional test" << std::endl; + BOOST_TEST_MESSAGE("Running Optional test"); OptionalTest pc; OptionalTest pc2; runTestWithInstances<OptionalTest>(pc, pc2); diff --git a/source/RobotAPI/libraries/core/CMakeLists.txt b/source/RobotAPI/libraries/core/CMakeLists.txt index 319a2e230228e944d2d443133d4664531f29b298..1e4b08820998f187015b03173f5e38c6fee21a14 100644 --- a/source/RobotAPI/libraries/core/CMakeLists.txt +++ b/source/RobotAPI/libraries/core/CMakeLists.txt @@ -31,7 +31,9 @@ set(LIB_FILES RobotStatechartContext.cpp RobotPool.cpp checks/ConditionCheckMagnitudeChecks.cpp + observerfilters/OffsetFilter.cpp observerfilters/PoseAverageFilter.cpp + observerfilters/PoseMedianFilter.cpp observerfilters/PoseMedianOffsetFilter.cpp observerfilters/MedianDerivativeFilterV3.cpp RobotAPIObjectFactories.cpp diff --git a/source/RobotAPI/libraries/core/FramedPose.cpp b/source/RobotAPI/libraries/core/FramedPose.cpp index 12bf1e91699c7e891d6cdce1a1fd4f38e96f0993..852477268e44969670b78789e31f1aae57848fac 100644 --- a/source/RobotAPI/libraries/core/FramedPose.cpp +++ b/source/RobotAPI/libraries/core/FramedPose.cpp @@ -33,6 +33,7 @@ #include <VirtualRobot/VirtualRobot.h> #include <VirtualRobot/RobotConfig.h> + using namespace Eigen; template class ::IceInternal::Handle<::armarx::FramedPose>; diff --git a/source/RobotAPI/libraries/core/LinkedPose.cpp b/source/RobotAPI/libraries/core/LinkedPose.cpp index 00391df0cba8d2a9b94cb368cdf16738c7e4c2c8..10b93907b5873f521378987329895c1a7033a960 100644 --- a/source/RobotAPI/libraries/core/LinkedPose.cpp +++ b/source/RobotAPI/libraries/core/LinkedPose.cpp @@ -290,4 +290,10 @@ namespace armarx } + void VariantType::suppressWarningUnusedVariableForLinkedPoseAndDirection() + { + ARMARX_DEBUG_S << VAROUT(LinkedPose); + ARMARX_DEBUG_S << VAROUT(LinkedDirection); + } + } diff --git a/source/RobotAPI/libraries/core/LinkedPose.h b/source/RobotAPI/libraries/core/LinkedPose.h index ffdc675d3b44eea2496d0e71ea121324b4b743f3..71a4240c81060d86e75cbf204ef3de726bd685a3 100644 --- a/source/RobotAPI/libraries/core/LinkedPose.h +++ b/source/RobotAPI/libraries/core/LinkedPose.h @@ -42,6 +42,8 @@ namespace armarx::VariantType // variant types const VariantTypeId LinkedPose = Variant::addTypeName("::armarx::LinkedPoseBase"); const VariantTypeId LinkedDirection = Variant::addTypeName("::armarx::LinkedDirectionBase"); + + void suppressWarningUnusedVariableForLinkedPoseAndDirection(); } namespace armarx diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp index 4232b3c8dcf97dfe7ce3ad70987c36c558561fa5..9f1ee0943cdbc899358d2f074bac5151932e3703 100644 --- a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp +++ b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.cpp @@ -25,6 +25,7 @@ #include <ArmarXCore/core/util/StringHelpers.h> + namespace armarx { diff --git a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h index 21670bd3c0716322f2bbd1f3da133bae10f41754..6c936c777acfbdd0b1d066ca0f5b2fcbbfef4072 100644 --- a/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h +++ b/source/RobotAPI/libraries/core/checks/ConditionCheckMagnitudeChecks.h @@ -29,6 +29,7 @@ #include <ArmarXCore/observers/ConditionCheck.h> #include <ArmarXCore/core/logging/Logging.h> + namespace armarx { diff --git a/source/RobotAPI/libraries/core/observerfilters/MedianDerivativeFilterV3.cpp b/source/RobotAPI/libraries/core/observerfilters/MedianDerivativeFilterV3.cpp index cf84ea731b2c0f4949295dfea5c8e0e069b49146..699dc495760c1fb1862fe4eb0a28986361448ce8 100644 --- a/source/RobotAPI/libraries/core/observerfilters/MedianDerivativeFilterV3.cpp +++ b/source/RobotAPI/libraries/core/observerfilters/MedianDerivativeFilterV3.cpp @@ -26,6 +26,7 @@ #include <ArmarXCore/core/logging/Logging.h> + using namespace armarx; using namespace filters; diff --git a/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.cpp b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..d8a3246de16fa15282559204e96f45f516567d7c --- /dev/null +++ b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.cpp @@ -0,0 +1,109 @@ +#include "OffsetFilter.h" + +#include <RobotAPI/libraries/core/FramedPose.h> + +#include <ArmarXCore/core/logging/Logging.h> +#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h> + + +namespace armarx::filters +{ + + OffsetFilter::OffsetFilter() + { + firstRun = true; + windowFilterSize = 1; + } + + + VariantBasePtr OffsetFilter::calculate(const Ice::Current&) const + { + std::unique_lock lock(historyMutex); + + VariantPtr newVariant; + + if (initialValue && dataHistory.size() > 0) + { + VariantTypeId type = dataHistory.begin()->second->getType(); + VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second); + + if (currentValue->getType() != initialValue->getType()) + { + ARMARX_ERROR_S << "Types in OffsetFilter are different: " << Variant::typeToString(currentValue->getType()) << " and " << Variant::typeToString(initialValue->getType()); + return nullptr; + } + + if (type == VariantType::Int) + { + int newValue = dataHistory.rbegin()->second->getInt() - initialValue->getInt(); + newVariant = new Variant(newValue); + } + else if (type == VariantType::Float) + { + float newValue = dataHistory.rbegin()->second->getFloat() - initialValue->getFloat(); + newVariant = new Variant(newValue); + } + else if (type == VariantType::Double) + { + double newValue = dataHistory.rbegin()->second->getDouble() - initialValue->getDouble(); + newVariant = new Variant(newValue); + } + else if (type == VariantType::FramedDirection) + { + FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(currentValue->get<FramedDirection>()); + FramedDirectionPtr intialVec = FramedDirectionPtr::dynamicCast(initialValue->get<FramedDirection>()); + Eigen::Vector3f newValue = vec->toEigen() - intialVec->toEigen(); + + newVariant = new Variant(new FramedDirection(newValue, vec->frame, vec->agent)); + } + else if (type == VariantType::FramedPosition) + { + FramedPositionPtr pos = FramedPositionPtr::dynamicCast(currentValue->get<FramedPosition>()); + FramedPositionPtr intialPos = FramedPositionPtr::dynamicCast(initialValue->get<FramedPosition>()); + Eigen::Vector3f newValue = pos->toEigen() - intialPos->toEigen(); + newVariant = new Variant(new FramedPosition(newValue, pos->frame, pos->agent)); + } + else if (type == VariantType::MatrixFloat) + { + MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>()); + MatrixFloatPtr initialMatrix = MatrixFloatPtr::dynamicCast(initialValue->get<MatrixFloat>()); + Eigen::MatrixXf newMatrix = matrix->toEigen() - initialMatrix->toEigen(); + newVariant = new Variant(new MatrixFloat(newMatrix)); + } + } + + return newVariant; + + } + + ParameterTypeList OffsetFilter::getSupportedTypes(const Ice::Current&) const + { + ParameterTypeList result; + result.push_back(VariantType::Int); + result.push_back(VariantType::Float); + result.push_back(VariantType::Double); + result.push_back(VariantType::FramedDirection); + result.push_back(VariantType::FramedPosition); + result.push_back(VariantType::MatrixFloat); + return result; + } + + void OffsetFilter::update(Ice::Long timestamp, const VariantBasePtr& value, const Ice::Current& c) + { + DatafieldFilter::update(timestamp, value, c); + + if (firstRun) + { + std::unique_lock lock(historyMutex); + + if (dataHistory.size() == 0) + { + return; + } + + initialValue = VariantPtr::dynamicCast(dataHistory.begin()->second); + firstRun = false; + } + } + +} diff --git a/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h index 1f4cfc17ca851f86e04c6e37c2ebc80d7da4b95d..4af1082d7fb7ac6fb8aeea67f1491d7f94d2f39d 100644 --- a/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h +++ b/source/RobotAPI/libraries/core/observerfilters/OffsetFilter.h @@ -23,10 +23,9 @@ #pragma once #include <RobotAPI/interface/observers/ObserverFilters.h> + #include <ArmarXCore/observers/filters/DatafieldFilter.h> -#include <RobotAPI/libraries/core/FramedPose.h> -#include <ArmarXCore/util/variants/eigen3/MatrixVariant.h> -#include <ArmarXCore/core/logging/Logging.h> + namespace armarx::filters { @@ -44,109 +43,27 @@ namespace armarx::filters public DatafieldFilter { public: - OffsetFilter() - { - firstRun = true; - windowFilterSize = 1; - } + + OffsetFilter(); // DatafieldFilterBase interface public: - VariantBasePtr calculate(const Ice::Current& c = Ice::emptyCurrent) const override - { - - std::unique_lock lock(historyMutex); - - VariantPtr newVariant; - - if (initialValue && dataHistory.size() > 0) - { - VariantTypeId type = dataHistory.begin()->second->getType(); - VariantPtr currentValue = VariantPtr::dynamicCast(dataHistory.rbegin()->second); - - if (currentValue->getType() != initialValue->getType()) - { - ARMARX_ERROR_S << "Types in OffsetFilter are different: " << Variant::typeToString(currentValue->getType()) << " and " << Variant::typeToString(initialValue->getType()); - return NULL; - } - - if (type == VariantType::Int) - { - int newValue = dataHistory.rbegin()->second->getInt() - initialValue->getInt(); - newVariant = new Variant(newValue); - } - else if (type == VariantType::Float) - { - float newValue = dataHistory.rbegin()->second->getFloat() - initialValue->getFloat(); - newVariant = new Variant(newValue); - } - else if (type == VariantType::Double) - { - double newValue = dataHistory.rbegin()->second->getDouble() - initialValue->getDouble(); - newVariant = new Variant(newValue); - } - else if (type == VariantType::FramedDirection) - { - FramedDirectionPtr vec = FramedDirectionPtr::dynamicCast(currentValue->get<FramedDirection>()); - FramedDirectionPtr intialVec = FramedDirectionPtr::dynamicCast(initialValue->get<FramedDirection>()); - Eigen::Vector3f newValue = vec->toEigen() - intialVec->toEigen(); - - newVariant = new Variant(new FramedDirection(newValue, vec->frame, vec->agent)); - } - else if (type == VariantType::FramedPosition) - { - FramedPositionPtr pos = FramedPositionPtr::dynamicCast(currentValue->get<FramedPosition>()); - FramedPositionPtr intialPos = FramedPositionPtr::dynamicCast(initialValue->get<FramedPosition>()); - Eigen::Vector3f newValue = pos->toEigen() - intialPos->toEigen(); - newVariant = new Variant(new FramedPosition(newValue, pos->frame, pos->agent)); - } - else if (type == VariantType::MatrixFloat) - { - MatrixFloatPtr matrix = MatrixFloatPtr::dynamicCast(currentValue->get<MatrixFloat>()); - MatrixFloatPtr initialMatrix = MatrixFloatPtr::dynamicCast(initialValue->get<MatrixFloat>()); - Eigen::MatrixXf newMatrix = matrix->toEigen() - initialMatrix->toEigen(); - newVariant = new Variant(new MatrixFloat(newMatrix)); - } - } - - return newVariant; - - } - ParameterTypeList getSupportedTypes(const Ice::Current&) const override - { - ParameterTypeList result; - result.push_back(VariantType::Int); - result.push_back(VariantType::Float); - result.push_back(VariantType::Double); - result.push_back(VariantType::FramedDirection); - result.push_back(VariantType::FramedPosition); - result.push_back(VariantType::MatrixFloat); - return result; - } + + VariantBasePtr calculate(const Ice::Current& = Ice::emptyCurrent) const override; + + ParameterTypeList getSupportedTypes(const Ice::Current&) const override; + + private: bool firstRun; VariantPtr initialValue; + // DatafieldFilterBase interface public: - void update(Ice::Long timestamp, const VariantBasePtr& value, const Ice::Current& c) override - { - DatafieldFilter::update(timestamp, value, c); - - if (firstRun) - { - std::unique_lock lock(historyMutex); - - if (dataHistory.size() == 0) - { - return; - } - - initialValue = VariantPtr::dynamicCast(dataHistory.begin()->second); - firstRun = false; - } - } + void update(Ice::Long timestamp, const VariantBasePtr& value, const Ice::Current& c) override; + }; } diff --git a/source/RobotAPI/libraries/core/observerfilters/PoseAverageFilter.cpp b/source/RobotAPI/libraries/core/observerfilters/PoseAverageFilter.cpp index 25657e38b27bfb63cd6d9de48514ec0f00c2497e..e0d61134cfb5e85319d9a45af55418cf9f1a9a07 100644 --- a/source/RobotAPI/libraries/core/observerfilters/PoseAverageFilter.cpp +++ b/source/RobotAPI/libraries/core/observerfilters/PoseAverageFilter.cpp @@ -25,6 +25,7 @@ #include <ArmarXCore/core/logging/Logging.h> + namespace armarx::filters { diff --git a/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.cpp b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.cpp new file mode 100644 index 0000000000000000000000000000000000000000..72c6e8e8e798c43046f14c3dbcabc73233ab9a0d --- /dev/null +++ b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.cpp @@ -0,0 +1,112 @@ +#include "PoseMedianFilter.h" + +#include <RobotAPI/libraries/core/FramedPose.h> +#include <RobotAPI/interface/core/PoseBase.h> + +#include <ArmarXCore/core/logging/Logging.h> + + +namespace armarx::filters +{ + + PoseMedianFilter::PoseMedianFilter(int windowSize) + { + this->windowFilterSize = windowSize; + } + + + VariantBasePtr PoseMedianFilter::calculate(const Ice::Current& c) const + { + std::unique_lock lock(historyMutex); + + if (dataHistory.size() == 0) + { + return nullptr; + } + + VariantTypeId type = dataHistory.begin()->second->getType(); + + if (type == VariantType::Vector3 + or type == VariantType::FramedDirection + or type == VariantType::FramedPosition) + { + Eigen::Vector3f vec; + vec.setZero(); + std::string frame = ""; + std::string agent = ""; + VariantPtr var = VariantPtr::dynamicCast(dataHistory.begin()->second); + + if (type == VariantType::FramedDirection) + { + FramedDirectionPtr p = var->get<FramedDirection>(); + frame = p->frame; + agent = p->agent; + } + else if (type == VariantType::FramedPosition) + { + FramedPositionPtr p = var->get<FramedPosition>(); + frame = p->frame; + agent = p->agent; + } + + for (int i = 0; i < 3; ++i) + { + std::vector<double> values; + + for (auto v : dataHistory) + { + VariantPtr v2 = VariantPtr::dynamicCast(v.second); + values.push_back(v2->get<Vector3>()->toEigen()[i]); + } + + std::sort(values.begin(), values.end()); + vec[i] = values.at(values.size() / 2); + } + + if (type == VariantType::Vector3) + { + Vector3Ptr vecVar = new Vector3(vec); + return new Variant(vecVar); + } + else if (type == VariantType::FramedDirection) + { + + FramedDirectionPtr vecVar = new FramedDirection(vec, frame, agent); + return new Variant(vecVar); + } + else if (type == VariantType::FramedPosition) + { + FramedPositionPtr vecVar = new FramedPosition(vec, frame, agent); + return new Variant(vecVar); + } + else + { + ARMARX_WARNING_S << "Implementation missing here"; + return nullptr; + } + } + else if (type == VariantType::Double) + { + // auto values = SortVariants<double>(dataHistory); + // return new Variant(values.at(values.size()/2)); + } + else if (type == VariantType::Int) + { + // auto values = SortVariants<int>(dataHistory); + // return new Variant(values.at(values.size()/2)); + } + + return MedianFilter::calculate(c); + } + + + ParameterTypeList PoseMedianFilter::getSupportedTypes(const Ice::Current& c) const + { + ParameterTypeList result = MedianFilter::getSupportedTypes(c); + result.push_back(VariantType::Vector3); + result.push_back(VariantType::FramedDirection); + result.push_back(VariantType::FramedPosition); + return result; + } + +} diff --git a/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h index b43ffe9c90c1ee499eeb79713743f0db06b7a588..bc03128714c8685f07b45b09e1e41996437e697f 100644 --- a/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h +++ b/source/RobotAPI/libraries/core/observerfilters/PoseMedianFilter.h @@ -23,11 +23,10 @@ */ #pragma once -#include <RobotAPI/libraries/core/FramedPose.h> -#include <RobotAPI/interface/core/PoseBase.h> +#include <RobotAPI/interface/core/FramedPoseBase.h> #include <ArmarXCore/observers/filters/MedianFilter.h> -#include <ArmarXCore/core/logging/Logging.h> + namespace armarx::filters { @@ -43,108 +42,17 @@ namespace armarx::filters public MedianFilter { public: - PoseMedianFilter(int windowSize = 11) - { - this->windowFilterSize = windowSize; - } + PoseMedianFilter(int windowSize = 11); // DatafieldFilterBase interface public: - VariantBasePtr calculate(const Ice::Current& c) const override - { - std::unique_lock lock(historyMutex); - - if (dataHistory.size() == 0) - { - return NULL; - } - - VariantTypeId type = dataHistory.begin()->second->getType(); - - if ((type == VariantType::Vector3) || (type == VariantType::FramedDirection) || (type == VariantType::FramedPosition)) - { - - Eigen::Vector3f vec; - vec.setZero(); - std::string frame = ""; - std::string agent = ""; - VariantPtr var = VariantPtr::dynamicCast(dataHistory.begin()->second); - - if (type == VariantType::FramedDirection) - { - FramedDirectionPtr p = var->get<FramedDirection>(); - frame = p->frame; - agent = p->agent; - } - else if (type == VariantType::FramedPosition) - { - FramedPositionPtr p = var->get<FramedPosition>(); - frame = p->frame; - agent = p->agent; - } - - for (int i = 0; i < 3; ++i) - { - std::vector<double> values; - - for (auto v : dataHistory) - { - VariantPtr v2 = VariantPtr::dynamicCast(v.second); - values.push_back(v2->get<Vector3>()->toEigen()[i]); - } - - std::sort(values.begin(), values.end()); - vec[i] = values.at(values.size() / 2); - } - - if (type == VariantType::Vector3) - { - Vector3Ptr vecVar = new Vector3(vec); - return new Variant(vecVar); - } - else if (type == VariantType::FramedDirection) - { - - FramedDirectionPtr vecVar = new FramedDirection(vec, frame, agent); - return new Variant(vecVar); - } - else if (type == VariantType::FramedPosition) - { - FramedPositionPtr vecVar = new FramedPosition(vec, frame, agent); - return new Variant(vecVar); - } - else - { - ARMARX_WARNING_S << "Implementation missing here"; - return NULL; - } - } - else if (type == VariantType::Double) - { - // auto values = SortVariants<double>(dataHistory); - // return new Variant(values.at(values.size()/2)); - } - else if (type == VariantType::Int) - { - // auto values = SortVariants<int>(dataHistory); - // return new Variant(values.at(values.size()/2)); - } - - return MedianFilter::calculate(c); - } + VariantBasePtr calculate(const Ice::Current& c) const override; /** * @brief This filter supports: Vector3, FramedDirection, FramedPosition * @return List of VariantTypes */ - ParameterTypeList getSupportedTypes(const Ice::Current& c) const override - { - ParameterTypeList result = MedianFilter::getSupportedTypes(c); - result.push_back(VariantType::Vector3); - result.push_back(VariantType::FramedDirection); - result.push_back(VariantType::FramedPosition); - return result; - } + ParameterTypeList getSupportedTypes(const Ice::Current& c) const override; }; diff --git a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp index a509af7464f2e77346c9e2e90bdc7d4361b7e090..e6cc65c23c13e154382042424db8483d879a89b4 100644 --- a/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp +++ b/source/RobotAPI/libraries/core/remoterobot/RemoteRobotNode.cpp @@ -25,11 +25,13 @@ #include <RobotAPI/libraries/core/FramedPose.h> +#include <ArmarXCore/core/logging/Logging.h> #include <ArmarXCore/interface/core/BasicTypes.h> #include <ArmarXCore/core/logging/Logging.h> #include <VirtualRobot/VirtualRobot.h> + namespace armarx {