From 9fcb3bd9318db8343b5bd77c4cb585d23a428f88 Mon Sep 17 00:00:00 2001 From: Rainer Kartmann <rainer.kartmann@kit.edu> Date: Fri, 23 Apr 2021 17:04:39 +0200 Subject: [PATCH] Move non-object related aron types to aron/common --- .../libraries/ArmarXObjects/CMakeLists.txt | 6 +- .../ArmarXObjects/aron/ObjectPose.xml | 4 +- .../ArmarXObjects/aron_conversions.h | 1 - .../ArmarXObjects/aron_conversions/armarx.cpp | 11 - .../ArmarXObjects/aron_conversions/armarx.h | 8 +- .../aron_conversions/objpose.cpp | 1 + .../ArmarXObjects/aron_conversions/objpose.h | 3 +- .../libraries/armem_objects/CMakeLists.txt | 2 - .../armem_objects/aron/ObjectClass.xml | 12 +- .../armem_objects/server/class/Segment.cpp | 4 + .../server/class/SegmentAdapter.cpp | 501 ------------------ .../server/class/SegmentAdapter.h | 171 ------ source/RobotAPI/libraries/aron/CMakeLists.txt | 1 + .../libraries/aron/common/CMakeLists.txt | 36 ++ .../common}/aron/AxisAlignedBoundingBox.xml | 0 .../common}/aron/OrientedBox.xml | 0 .../common}/aron/PackagePath.xml | 0 .../libraries/aron/common/aron_conversions.h | 4 + .../aron/common/aron_conversions/armarx.cpp | 14 + .../aron/common/aron_conversions/armarx.h | 11 + .../aron/common/aron_conversions/objpose.cpp | 137 +++++ .../aron/common/aron_conversions/objpose.h | 19 + .../common}/aron_conversions/simox.cpp | 0 .../common}/aron_conversions/simox.h | 6 +- 24 files changed, 243 insertions(+), 709 deletions(-) delete mode 100644 source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.cpp delete mode 100644 source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.h create mode 100644 source/RobotAPI/libraries/aron/common/CMakeLists.txt rename source/RobotAPI/libraries/{ArmarXObjects => aron/common}/aron/AxisAlignedBoundingBox.xml (100%) rename source/RobotAPI/libraries/{ArmarXObjects => aron/common}/aron/OrientedBox.xml (100%) rename source/RobotAPI/libraries/{ArmarXObjects => aron/common}/aron/PackagePath.xml (100%) create mode 100644 source/RobotAPI/libraries/aron/common/aron_conversions.h create mode 100644 source/RobotAPI/libraries/aron/common/aron_conversions/armarx.cpp create mode 100644 source/RobotAPI/libraries/aron/common/aron_conversions/armarx.h create mode 100644 source/RobotAPI/libraries/aron/common/aron_conversions/objpose.cpp create mode 100644 source/RobotAPI/libraries/aron/common/aron_conversions/objpose.h rename source/RobotAPI/libraries/{ArmarXObjects => aron/common}/aron_conversions/simox.cpp (100%) rename source/RobotAPI/libraries/{ArmarXObjects => aron/common}/aron_conversions/simox.h (73%) diff --git a/source/RobotAPI/libraries/ArmarXObjects/CMakeLists.txt b/source/RobotAPI/libraries/ArmarXObjects/CMakeLists.txt index 61a8e3c90..31fd00c7e 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/CMakeLists.txt +++ b/source/RobotAPI/libraries/ArmarXObjects/CMakeLists.txt @@ -8,6 +8,7 @@ set(LIBS RemoteGui # RobotAPI RobotAPI::Core + aroncommon ) set(LIB_FILES @@ -20,7 +21,6 @@ set(LIB_FILES ice_conversions.cpp aron_conversions/armarx.cpp aron_conversions/objpose.cpp - aron_conversions/simox.cpp plugins/ObjectPoseProviderPlugin.cpp plugins/ObjectPoseClientPlugin.cpp @@ -40,7 +40,6 @@ set(LIB_HEADERS aron_conversions.h aron_conversions/armarx.h aron_conversions/objpose.h - aron_conversions/simox.h plugins/ObjectPoseProviderPlugin.h plugins/ObjectPoseClientPlugin.h @@ -56,13 +55,10 @@ armarx_enable_aron_file_generation_for_target( TARGET_NAME "${LIB_NAME}" ARON_FILES - aron/AxisAlignedBoundingBox.xml aron/ObjectID.xml aron/ObjectNames.xml aron/ObjectPose.xml aron/ObjectType.xml - aron/OrientedBox.xml - aron/PackagePath.xml ) diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.xml b/source/RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.xml index 32c794cbc..e9701dc24 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.xml +++ b/source/RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.xml @@ -7,12 +7,12 @@ ARON DTO of armarx::objpose::ObjectPose. <Include include="<Eigen/Core>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectID.aron.generated.h>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectType.aron.generated.h>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.aron.generated.h>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/OrientedBox.aron.generated.h>" /> </CodeIncludes> <AronIncludes> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectID.xml>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectType.xml>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.xml>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/OrientedBox.xml>" /> </AronIncludes> <GenerateTypes> diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions.h b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions.h index ff33149c1..f9862b6bb 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions.h +++ b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions.h @@ -2,4 +2,3 @@ #include "aron_conversions/armarx.h" #include "aron_conversions/objpose.h" -#include "aron_conversions/simox.h" diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.cpp b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.cpp index 5bbe2856e..fd081a063 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.cpp +++ b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.cpp @@ -13,17 +13,6 @@ void armarx::toAron(arondto::ObjectID& dto, const ObjectID& bo) } -void armarx::fromAron(const armarx::arondto::PackagePath& dto, armarx::PackagePath& bo) -{ - bo = { dto.package, dto.path }; -} -void armarx::toAron(armarx::arondto::PackagePath& dto, const armarx::PackagePath& bo) -{ - const armarx::data::PackagePath icedto = bo.serialize(); - dto.package = icedto.package; - dto.path = icedto.path; -} - void armarx::fromAron(const armarx::arondto::PackagePath& dto, armarx::PackageFileLocation& bo) { bo.package = dto.package; diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.h b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.h index a611b948f..08c60f45a 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.h +++ b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/armarx.h @@ -1,18 +1,14 @@ #pragma once -#include <ArmarXCore/core/PackagePath.h> -#include <RobotAPI/libraries/ArmarXObjects/aron/PackagePath.aron.generated.h> +#include <RobotAPI/libraries/ArmarXObjects/ObjectInfo.h> // For PackageFileLocation +#include <RobotAPI/libraries/aron/common/aron/PackagePath.aron.generated.h> #include <RobotAPI/libraries/ArmarXObjects/ObjectID.h> -#include <RobotAPI/libraries/ArmarXObjects/ObjectInfo.h> #include <RobotAPI/libraries/ArmarXObjects/aron/ObjectID.aron.generated.h> namespace armarx { - void fromAron(const arondto::PackagePath& dto, PackagePath& bo); - void toAron(arondto::PackagePath& dto, const PackagePath& bo); - void fromAron(const arondto::PackagePath& dto, PackageFileLocation& bo); void toAron(arondto::PackagePath& dto, const PackageFileLocation& bo); diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.cpp b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.cpp index 2e96fdbd8..2de8a3da0 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.cpp +++ b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.cpp @@ -2,6 +2,7 @@ #include <ArmarXCore/core/exceptions/local/UnexpectedEnumValueException.h> +#include <RobotAPI/libraries/aron/common/aron_conversions.h> #include <RobotAPI/libraries/ArmarXObjects/aron_conversions.h> diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.h b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.h index 87239deff..afe31e500 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.h +++ b/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/objpose.h @@ -1,8 +1,9 @@ #pragma once #include <RobotAPI/libraries/ArmarXObjects/ObjectPose.h> - #include <RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.aron.generated.h> + +#include <RobotAPI/interface/objectpose/object_pose_types.h> #include <RobotAPI/libraries/ArmarXObjects/aron/ObjectType.aron.generated.h> diff --git a/source/RobotAPI/libraries/armem_objects/CMakeLists.txt b/source/RobotAPI/libraries/armem_objects/CMakeLists.txt index 887faff06..114f2b794 100644 --- a/source/RobotAPI/libraries/armem_objects/CMakeLists.txt +++ b/source/RobotAPI/libraries/armem_objects/CMakeLists.txt @@ -19,7 +19,6 @@ armarx_add_library( aron_conversions.h server/class/Segment.h - server/class/SegmentAdapter.h server/instance/Segment.h server/instance/SegmentAdapter.h @@ -30,7 +29,6 @@ armarx_add_library( aron_conversions.cpp server/class/Segment.cpp - server/class/SegmentAdapter.cpp server/instance/Segment.cpp server/instance/SegmentAdapter.cpp diff --git a/source/RobotAPI/libraries/armem_objects/aron/ObjectClass.xml b/source/RobotAPI/libraries/armem_objects/aron/ObjectClass.xml index eb98a430a..650082eb4 100644 --- a/source/RobotAPI/libraries/armem_objects/aron/ObjectClass.xml +++ b/source/RobotAPI/libraries/armem_objects/aron/ObjectClass.xml @@ -4,19 +4,19 @@ Core segment type of Object/Class. <?xml version="1.0" encoding="UTF-8" ?> <AronTypeDefinition> <CodeIncludes> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/AxisAlignedBoundingBox.aron.generated.h>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/AxisAlignedBoundingBox.aron.generated.h>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/OrientedBox.aron.generated.h>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/PackagePath.aron.generated.h>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectID.aron.generated.h>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectNames.aron.generated.h>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.aron.generated.h>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/PackagePath.aron.generated.h>" /> <Include include="<RobotAPI/libraries/armem/aron/MemoryID.aron.generated.h>" /> </CodeIncludes> <AronIncludes> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/AxisAlignedBoundingBox.xml>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/AxisAlignedBoundingBox.xml>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/OrientedBox.xml>" /> + <Include include="<RobotAPI/libraries/aron/common/aron/PackagePath.xml>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectID.xml>" /> <Include include="<RobotAPI/libraries/ArmarXObjects/aron/ObjectNames.xml>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.xml>" /> - <Include include="<RobotAPI/libraries/ArmarXObjects/aron/PackagePath.xml>" /> <Include include="<RobotAPI/libraries/armem/aron/MemoryID.xml>" /> </AronIncludes> <GenerateTypes> diff --git a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp index b7f292795..f4fa5e8d1 100644 --- a/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp +++ b/source/RobotAPI/libraries/armem_objects/server/class/Segment.cpp @@ -1,11 +1,15 @@ #include "Segment.h" +#include <RobotAPI/libraries/aron/common/aron_conversions.h> #include <RobotAPI/libraries/ArmarXObjects/aron_conversions.h> #include <RobotAPI/libraries/armem_objects/aron_conversions.h> #include <ArmarXCore/core/Component.h> #include <ArmarXCore/core/time/TimeUtil.h> +#include <SimoxUtility/shapes/AxisAlignedBoundingBox.h> +#include <SimoxUtility/shapes/OrientedBox.h> + #include <filesystem> diff --git a/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.cpp b/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.cpp deleted file mode 100644 index a72bd7cda..000000000 --- a/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.cpp +++ /dev/null @@ -1,501 +0,0 @@ -/* - * This file is part of ArmarX. - * - * 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/>. - * - * @package RobotAPI::armem_objects::SegmentAdapter - * @author Rainer Kartmann ( rainer dot kartmann at kit dot edu ) - * @date 2021 - * @copyright http://www.gnu.org/licenses/gpl-2.0.txt - * GNU General Public License - */ - -#if 0 - -#include "SegmentAdapter.h" - -#include <RobotAPI/libraries/core/remoterobot/RemoteRobot.h> -#include <RobotAPI/libraries/ArmarXObjects/aron_conversions.h> -#include <RobotAPI/libraries/ArmarXObjects/ice_conversions.h> - -#include <ArmarXCore/core/time/CycleUtil.h> -#include <ArmarXCore/observers/variant/Variant.h> - -#include <VirtualRobot/Robot.h> - -#include <SimoxUtility/algorithm/get_map_keys_values.h> - - -namespace armarx::armem::server::obj::clazz -{ - - SegmentAdapter::SegmentAdapter(MemoryToIceAdapter& iceMemory, std::mutex& memoryMutex) : - segment(iceMemory), - memoryMutex(memoryMutex) - { - } - - std::string SegmentAdapter::getName() const - { - return Logging::tag.tagName; - } - - void SegmentAdapter::defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix) - { - calibration.defineProperties(defs, prefix + "calibration."); - segment.defineProperties(defs, prefix); - robotHead.defineProperties(defs, prefix + "head."); - visu.defineProperties(defs, prefix + "visu."); - } - - void SegmentAdapter::init() - { - segment.setTag(getName()); - segment.decay.setTag(getName()); - robotHead.setTag(getName()); - visu.setTag(getName()); - - segment.init(); - } - - void SegmentAdapter::connect( - RobotStateComponentInterfacePrx robotStateComponent, - VirtualRobot::RobotPtr robot, - KinematicUnitObserverInterfacePrx kinematicUnitObserver, - viz::Client arviz, - DebugObserverInterfacePrx debugObserver - ) - { - this->debugObserver = debugObserver; - this->arviz = arviz; - - segment.robot = robot; - segment.robotStateComponent = robotStateComponent; - - robotHead.kinematicUnitObserver = kinematicUnitObserver; - robotHead.debugObserver = debugObserver; - robotHead.fetchDatafields(); - - visu.arviz = arviz; - if (!visu.updateTask) - { - visu.updateTask = new SimpleRunningTask<>([this]() - { - this->visualizeRun(); - }); - visu.updateTask->start(); - } - } - - void SegmentAdapter::reportProviderAvailable(const std::string& providerName, const objpose::ProviderInfo& info, const Ice::Current&) - { - updateProviderInfo(providerName, info); - } - - - void SegmentAdapter::reportObjectPoses( - const std::string& providerName, const objpose::data::ProvidedObjectPoseSeq& providedPoses, const Ice::Current&) - { - ARMARX_VERBOSE << "Received object " << providedPoses.size() << " poses from provider '" << providerName << "'."; - updateObjectPoses(providerName, providedPoses); - } - - - void SegmentAdapter::updateProviderInfo(const std::string& providerName, const objpose::ProviderInfo& info) - { - if (!info.proxy) - { - ARMARX_WARNING << "Received availability signal by provider '" << providerName << "' " - << "with invalid provider proxy.\nIgnoring provider '" << providerName << "'."; - return; - } - { - std::scoped_lock lock(memoryMutex); - std::stringstream ss; - for (const auto& id : info.supportedObjects) - { - ss << "- " << id << "\n"; - } - ARMARX_VERBOSE << "Provider '" << providerName << "' available.\n" - << "Supported objects: \n" << ss.str(); - segment.providers[providerName] = info; - } - } - - - void SegmentAdapter::updateObjectPoses( - const std::string& providerName, - const objpose::data::ProvidedObjectPoseSeq& providedPoses) - { - TIMING_START(tReportObjectPoses); - - RobotHeadMovement::Discard discard; - { - std::scoped_lock lock(robotHeadMutex); - discard = robotHead.getDiscard(); - } - if (debugObserver) - { - StringVariantBaseMap map; - map["Discarding All Updates"] = new Variant(discard.all ? 1.f : 0.f); - if (discard.all) - { - map["Proportion Updated Poses"] = new Variant(0.f); - } - debugObserver->setDebugChannel(getName(), map); - } - - if (discard.all) - { - return; - } - - { - std::scoped_lock lock(memoryMutex); - RemoteRobot::synchronizeLocalClone(segment.robot, segment.robotStateComponent); - - if (segment.robot->hasRobotNode(calibration.robotNode)) - { - VirtualRobot::RobotNodePtr robotNode = segment.robot->getRobotNode(calibration.robotNode); - float value = robotNode->getJointValue(); - robotNode->setJointValue(value + calibration.offset); - } - - TIMING_START(tCommitObjectPoses); - Segment::CommitStats stats = - segment.commitObjectPoses(providerName, providedPoses, discard.updatesUntil); - TIMING_END_STREAM(tCommitObjectPoses, ARMARX_VERBOSE); - - if (debugObserver) - { - debugObserver->setDebugChannel(getName(), - { - { "Discarding All Updates", new Variant(discard.all ? 1 : 0) }, - { "Proportion Updated Poses", new Variant(static_cast<float>(stats.numUpdated) / providedPoses.size()) } - }); - } - - handleProviderUpdate(providerName); - - TIMING_END_STREAM(tReportObjectPoses, ARMARX_VERBOSE); - if (debugObserver) - { - debugObserver->setDebugChannel(getName(), - { - { "t ReportObjectPoses [ms]", new Variant(tReportObjectPoses.toMilliSecondsDouble()) }, - { "t MemorySetObjectPoses [ms]", new Variant(tCommitObjectPoses.toMilliSecondsDouble()) }, - }); - } - } - } - - - void SegmentAdapter::handleProviderUpdate(const std::string& providerName) - { - // Initialized to 0 on first access. - if (segment.providers.count(providerName) == 0) - { - segment.providers[providerName] = objpose::ProviderInfo(); - } - } - - - objpose::data::ObjectPoseSeq SegmentAdapter::getObjectPoses(const Ice::Current&) - { - TIMING_START(tGetObjectPoses); - - TIMING_START(tGetObjectPosesLock); - std::scoped_lock lock(memoryMutex); - TIMING_END_STREAM(tGetObjectPosesLock, ARMARX_VERBOSE); - - const IceUtil::Time now = TimeUtil::GetTime(); - const objpose::data::ObjectPoseSeq result = objpose::toIce(segment.getObjectPoses(now)); - - TIMING_END_STREAM(tGetObjectPoses, ARMARX_VERBOSE); - - if (debugObserver) - { - debugObserver->setDebugChannel(getName(), - { - { "t GetObjectPoses() [ms]", new Variant(tGetObjectPoses.toMilliSecondsDouble()) }, - { "t GetObjectPoses() lock [ms]", new Variant(tGetObjectPosesLock.toMilliSecondsDouble()) } - }); - } - - return result; - } - - objpose::data::ObjectPoseSeq SegmentAdapter::getObjectPosesByProvider(const std::string& providerName, const Ice::Current&) - { - TIMING_START(GetObjectPoses); - - TIMING_START(GetObjectPosesLock); - std::scoped_lock lock(memoryMutex); - TIMING_END_STREAM(GetObjectPosesLock, ARMARX_VERBOSE); - - const IceUtil::Time now = TimeUtil::GetTime(); - const objpose::data::ObjectPoseSeq result = objpose::toIce(segment.getObjectPosesByProvider(providerName, now)); - - TIMING_END_STREAM(GetObjectPoses, ARMARX_VERBOSE); - - if (debugObserver) - { - debugObserver->setDebugChannel(getName(), - { - { "t GetObjectPosesByProvider() [ms]", new Variant(GetObjectPoses.toMilliSecondsDouble()) }, - { "t GetObjectPosesByProvider() lock [ms]", new Variant(GetObjectPosesLock.toMilliSecondsDouble()) } - }); - } - - return result; - } - - - objpose::observer::RequestObjectsOutput SegmentAdapter::requestObjects( - const objpose::observer::RequestObjectsInput& input, const Ice::Current&) - { - std::map<std::string, objpose::provider::RequestObjectsInput> providerRequests; - std::map<std::string, objpose::ObjectPoseProviderPrx> proxies; - - objpose::observer::RequestObjectsOutput output; - - auto updateProxy = [&](const std::string & providerName) - { - if (proxies.count(providerName) == 0) - { - if (auto it = segment.providers.find(providerName); it != segment.providers.end()) - { - proxies[providerName] = it->second.proxy; - } - else - { - ARMARX_ERROR << "No proxy for provider ' " << providerName << "'."; - proxies[providerName] = nullptr; - } - } - }; - - if (input.provider.size() > 0) - { - providerRequests[input.provider] = input.request; - updateProxy(input.provider); - } - else - { - std::scoped_lock lock(memoryMutex); - for (const auto& objectID : input.request.objectIDs) - { - bool found = true; - for (const auto& [providerName, info] : segment.providers) - { - // ToDo: optimize look up. - if (std::find(info.supportedObjects.begin(), info.supportedObjects.end(), objectID) != info.supportedObjects.end()) - { - providerRequests[providerName].objectIDs.push_back(objectID); - updateProxy(providerName); - break; - } - } - if (!found) - { - ARMARX_ERROR << "Did not find a provider for " << objectID << "."; - output.results[objectID].providerName = ""; - } - } - } - - for (const auto& [providerName, request] : providerRequests) - { - if (objpose::ObjectPoseProviderPrx proxy = proxies.at(providerName); proxy) - { - ARMARX_INFO << "Requesting " << request.objectIDs.size() << " objects by provider '" - << providerName << "' for " << request.relativeTimeoutMS << " ms."; - objpose::provider::RequestObjectsOutput providerOutput = proxy->requestObjects(request); - - int successful = 0; - for (const auto& [objectID, result] : providerOutput.results) - { - objpose::observer::ObjectRequestResult& res = output.results[objectID]; - res.providerName = providerName; - res.result = result; - successful += int(result.success); - } - ARMARX_INFO << successful << " of " << request.objectIDs.size() << " object requests successful."; - } - } - return output; - } - - objpose::ProviderInfoMap SegmentAdapter::getAvailableProvidersInfo(const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.providers; - } - - Ice::StringSeq SegmentAdapter::getAvailableProviderNames(const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return simox::alg::get_keys(segment.providers); - } - - objpose::ProviderInfo SegmentAdapter::getProviderInfo(const std::string& providerName, const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.getProviderInfo(providerName); - } - - bool SegmentAdapter::hasProvider(const std::string& providerName, const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.providers.count(providerName) > 0; - } - - - objpose::AttachObjectToRobotNodeOutput SegmentAdapter::attachObjectToRobotNode( - const objpose::AttachObjectToRobotNodeInput& input, const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.attachObjectToRobotNode(input); - } - - objpose::DetachObjectFromRobotNodeOutput SegmentAdapter::detachObjectFromRobotNode( - const objpose::DetachObjectFromRobotNodeInput& input, const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.detachObjectFromRobotNode(input); - } - - objpose::DetachAllObjectsFromRobotNodesOutput SegmentAdapter::detachAllObjectsFromRobotNodes( - const objpose::DetachAllObjectsFromRobotNodesInput& input, const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - return segment.detachAllObjectsFromRobotNodes(input); - } - - - objpose::AgentFramesSeq SegmentAdapter::getAttachableFrames(const Ice::Current&) - { - std::scoped_lock lock(memoryMutex); - - objpose::AgentFramesSeq output; - std::vector<VirtualRobot::RobotPtr> agents = { segment.robot }; - for (VirtualRobot::RobotPtr agent : agents) - { - objpose::AgentFrames& frames = output.emplace_back(); - frames.agent = agent->getName(); - frames.frames = agent->getRobotNodeNames(); - } - return output; - } - - objpose::SignalHeadMovementOutput - SegmentAdapter::signalHeadMovement(const objpose::SignalHeadMovementInput& input, const Ice::Current&) - { - std::scoped_lock lock(robotHeadMutex); - return robotHead.signalHeadMovement(input); - } - - - void SegmentAdapter::visualizeRun() - { - CycleUtil cycle(static_cast<int>(1000 / visu.frequencyHz)); - while (visu.updateTask && !visu.updateTask->isStopped()) - { - { - std::scoped_lock lock(visuMutex); - - if (visu.enabled) - { - TIMING_START(Visu); - - objpose::ObjectPoseSeq objectPoses; - ObjectFinder objectFinder; - visu.minConfidence = -1; - { - std::scoped_lock lock(memoryMutex); - - const IceUtil::Time now = TimeUtil::GetTime(); - objectPoses = segment.getObjectPoses(now); - objectFinder = segment.objectFinder; - if (segment.decay.enabled) - { - visu.minConfidence = segment.decay.removeObjectsBelowConfidence; - } - } - const std::vector<viz::Layer> layers = visu.visualizeCommit(objectPoses, objectFinder); - arviz.commit(layers); - - TIMING_END_STREAM(Visu, ARMARX_VERBOSE); - - if (debugObserver) - { - debugObserver->setDebugChannel(getName(), - { - { "t Visualize [ms]", new Variant(Visu.toMilliSecondsDouble()) }, - }); - } - } - } - cycle.waitForCycleDuration(); - } - } - - - void SegmentAdapter::Calibration::defineProperties(PropertyDefinitionsPtr defs, const std::string& prefix) - { - defs->optional(robotNode, prefix + "robotNode", "Robot node which can be calibrated."); - defs->optional(offset, prefix + "offset", "Offset for the node to be calibrated."); - } - - - - void SegmentAdapter::RemoteGui::setup(const SegmentAdapter& adapter) - { - using namespace armarx::RemoteGui::Client; - - this->visu.setup(adapter.visu); - this->segment.setup(adapter.segment); - this->decay.setup(adapter.segment.decay); - this->robotHead.setup(adapter.robotHead); - - layout = VBoxLayout - { - this->visu.group, this->segment.group, this->decay.group, this->robotHead.group, - VSpacer() - }; - - group.setLabel("clazz"); - group.addChild(layout); - } - - void SegmentAdapter::RemoteGui::update(SegmentAdapter& adapter) - { - // Non-atomic variables need to be guarded by a mutex if accessed by multiple threads - { - std::scoped_lock lock(adapter.visuMutex); - this->visu.update(adapter.visu); - } - { - std::scoped_lock lock(adapter.memoryMutex); - this->segment.update(adapter.segment); - this->decay.update(adapter.segment.decay); - } - { - std::scoped_lock lock(adapter.robotHeadMutex); - this->robotHead.update(adapter.robotHead); - } - } - -} - -#endif diff --git a/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.h b/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.h deleted file mode 100644 index fcb50d7c0..000000000 --- a/source/RobotAPI/libraries/armem_objects/server/class/SegmentAdapter.h +++ /dev/null @@ -1,171 +0,0 @@ -/* - * This file is part of ArmarX. - * - * 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/>. - * - * @package RobotAPI::armem_objects::Adapter - * @author Rainer Kartmann ( rainer dot kartmann at kit dot edu ) - * @date 2021 - * @copyright http://www.gnu.org/licenses/gpl-2.0.txt - * GNU General Public License - */ - -#pragma once - -#if 0 -#include <mutex> - -#include <VirtualRobot/VirtualRobot.h> - -#include <ArmarXGui/libraries/RemoteGui/Client/Widgets.h> - -#include <RobotAPI/interface/armem/server/ObjectMemoryInterface.h> -#include <RobotAPI/interface/core/RobotState.h> - -#include <RobotAPI/components/ArViz/Client/Client.h> - -#include <RobotAPI/libraries/armem/server/MemoryToIceAdapter.h> -#include <RobotAPI/libraries/armem_objects/server/clazz/Segment.h> -#include <RobotAPI/libraries/armem_objects/server/clazz/Decay.h> -#include <RobotAPI/libraries/armem_objects/server/clazz/Visu.h> -#include <RobotAPI/libraries/armem_objects/server/clazz/RobotHeadMovement.h> - - -#define ICE_CURRENT_ARG const Ice::Current& = Ice::emptyCurrent - - -namespace armarx::armem::server::obj::clazz -{ - - /** - * @brief Helps implementing the `armarx::armem::server::ObjectclazzSegmentInterface`. - */ - class SegmentAdapter : - virtual public armarx::Logging - , virtual public armarx::armem::server::ObjectclazzSegmentInterface - { - public: - - SegmentAdapter(MemoryToIceAdapter& iceMemory, std::mutex& memoryMutex); - - std::string getName() const; - void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = ""); - - void init(); - void connect( - RobotStateComponentInterfacePrx robotStateComponent, - VirtualRobot::RobotPtr robot, - KinematicUnitObserverInterfacePrx kinematicUnitObserver, - viz::Client arviz, - DebugObserverInterfacePrx debugObserver - ); - - - // ObjectPoseTopic interface - public: - virtual void reportProviderAvailable(const std::string& providerName, const objpose::ProviderInfo& info, ICE_CURRENT_ARG) override; - virtual void reportObjectPoses(const std::string& providerName, const objpose::data::ProvidedObjectPoseSeq& objectPoses, ICE_CURRENT_ARG) override; - - // ObjectclazzSegmentInterface interface - public: - - // OBJECT POSES - - virtual objpose::data::ObjectPoseSeq getObjectPoses(ICE_CURRENT_ARG) override; - virtual objpose::data::ObjectPoseSeq getObjectPosesByProvider(const std::string& providerName, ICE_CURRENT_ARG) override; - - // PROVIDER INFORMATION - - virtual bool hasProvider(const std::string& providerName, ICE_CURRENT_ARG) override; - virtual objpose::ProviderInfo getProviderInfo(const std::string& providerName, ICE_CURRENT_ARG) override; - virtual Ice::StringSeq getAvailableProviderNames(ICE_CURRENT_ARG) override; - virtual objpose::ProviderInfoMap getAvailableProvidersInfo(ICE_CURRENT_ARG) override; - - - // REQUESTING - - virtual objpose::observer::RequestObjectsOutput requestObjects(const objpose::observer::RequestObjectsInput& input, ICE_CURRENT_ARG) override; - - // ATTACHING - - virtual objpose::AttachObjectToRobotNodeOutput attachObjectToRobotNode(const objpose::AttachObjectToRobotNodeInput& input, ICE_CURRENT_ARG) override; - virtual objpose::DetachObjectFromRobotNodeOutput detachObjectFromRobotNode(const objpose::DetachObjectFromRobotNodeInput& input, ICE_CURRENT_ARG) override; - virtual objpose::DetachAllObjectsFromRobotNodesOutput detachAllObjectsFromRobotNodes(const objpose::DetachAllObjectsFromRobotNodesInput& input, ICE_CURRENT_ARG) override; - - virtual objpose::AgentFramesSeq getAttachableFrames(ICE_CURRENT_ARG) override; - - // HEAD MOVEMENT SIGNALS - - virtual objpose::SignalHeadMovementOutput signalHeadMovement(const objpose::SignalHeadMovementInput& input, ICE_CURRENT_ARG) override; - - - private: - - void updateProviderInfo(const std::string& providerName, const objpose::ProviderInfo& info); - - void updateObjectPoses(const std::string& providerName, const objpose::data::ProvidedObjectPoseSeq& providedPoses); - void handleProviderUpdate(const std::string& providerName); - - - // Visualization - - void visualizeRun(); - - - private: - - viz::Client arviz; - DebugObserverInterfacePrx debugObserver; - - clazz::Segment segment; - std::mutex& memoryMutex; - - clazz::RobotHeadMovement robotHead; - std::mutex robotHeadMutex; - - clazz::Visu visu; - std::mutex visuMutex; - - - struct Calibration - { - std::string robotNode = "Neck_2_Pitch"; - float offset = 0.0f; - - void defineProperties(armarx::PropertyDefinitionsPtr defs, const std::string& prefix = "calibration."); - }; - Calibration calibration; - - - public: - - struct RemoteGui - { - armarx::RemoteGui::Client::GroupBox group; - armarx::RemoteGui::Client::VBoxLayout layout; - - clazz::Visu::RemoteGui visu; - clazz::Segment::RemoteGui segment; - clazz::Decay::RemoteGui decay; - clazz::RobotHeadMovement::RemoteGui robotHead; - - void setup(const SegmentAdapter& adapter); - void update(SegmentAdapter& adapter); - }; - - }; - -} - -#undef ICE_CURRENT_ARG -#endif diff --git a/source/RobotAPI/libraries/aron/CMakeLists.txt b/source/RobotAPI/libraries/aron/CMakeLists.txt index 124be827d..c45ff0856 100644 --- a/source/RobotAPI/libraries/aron/CMakeLists.txt +++ b/source/RobotAPI/libraries/aron/CMakeLists.txt @@ -1,3 +1,4 @@ add_subdirectory(core) add_subdirectory(converter) add_subdirectory(codegenerationhelper) +add_subdirectory(common) diff --git a/source/RobotAPI/libraries/aron/common/CMakeLists.txt b/source/RobotAPI/libraries/aron/common/CMakeLists.txt new file mode 100644 index 000000000..292095e5d --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/CMakeLists.txt @@ -0,0 +1,36 @@ +set(LIB_NAME aroncommon) + +armarx_component_set_name("${LIB_NAME}") +armarx_set_target("Library: ${LIB_NAME}") + + +armarx_add_library( + LIBS + # ArmarXCore + ArmarXCore + # RobotAPI + aron + + HEADERS + aron_conversions.h + aron_conversions/armarx.h + aron_conversions/simox.h + + SOURCES + aron_conversions/armarx.cpp + aron_conversions/simox.cpp +) + + +armarx_enable_aron_file_generation_for_target( + TARGET_NAME + "${LIB_NAME}" + ARON_FILES + aron/AxisAlignedBoundingBox.xml + aron/OrientedBox.xml + aron/PackagePath.xml +) + + +# add unit tests +# add_subdirectory(test) diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron/AxisAlignedBoundingBox.xml b/source/RobotAPI/libraries/aron/common/aron/AxisAlignedBoundingBox.xml similarity index 100% rename from source/RobotAPI/libraries/ArmarXObjects/aron/AxisAlignedBoundingBox.xml rename to source/RobotAPI/libraries/aron/common/aron/AxisAlignedBoundingBox.xml diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.xml b/source/RobotAPI/libraries/aron/common/aron/OrientedBox.xml similarity index 100% rename from source/RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.xml rename to source/RobotAPI/libraries/aron/common/aron/OrientedBox.xml diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron/PackagePath.xml b/source/RobotAPI/libraries/aron/common/aron/PackagePath.xml similarity index 100% rename from source/RobotAPI/libraries/ArmarXObjects/aron/PackagePath.xml rename to source/RobotAPI/libraries/aron/common/aron/PackagePath.xml diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions.h b/source/RobotAPI/libraries/aron/common/aron_conversions.h new file mode 100644 index 000000000..17f784d13 --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/aron_conversions.h @@ -0,0 +1,4 @@ +#pragma once + +#include "aron_conversions/armarx.h" +#include "aron_conversions/simox.h" diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.cpp b/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.cpp new file mode 100644 index 000000000..da205a523 --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.cpp @@ -0,0 +1,14 @@ +#include "armarx.h" + + +void armarx::fromAron(const armarx::arondto::PackagePath& dto, armarx::PackagePath& bo) +{ + bo = { dto.package, dto.path }; +} +void armarx::toAron(armarx::arondto::PackagePath& dto, const armarx::PackagePath& bo) +{ + const armarx::data::PackagePath icedto = bo.serialize(); + dto.package = icedto.package; + dto.path = icedto.path; +} + diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.h b/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.h new file mode 100644 index 000000000..241067b7b --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/aron_conversions/armarx.h @@ -0,0 +1,11 @@ +#pragma once + +#include <ArmarXCore/core/PackagePath.h> +#include <RobotAPI/libraries/aron/common/aron/PackagePath.aron.generated.h> + + +namespace armarx +{ + void fromAron(const arondto::PackagePath& dto, PackagePath& bo); + void toAron(arondto::PackagePath& dto, const PackagePath& bo); +} diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.cpp b/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.cpp new file mode 100644 index 000000000..2e96fdbd8 --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.cpp @@ -0,0 +1,137 @@ +#include "objpose.h" + +#include <ArmarXCore/core/exceptions/local/UnexpectedEnumValueException.h> + +#include <RobotAPI/libraries/ArmarXObjects/aron_conversions.h> + + +void armarx::objpose::fromAron(const arondto::ObjectAttachmentInfo& dto, ObjectAttachmentInfo& bo) +{ + bo.frameName = dto.frameName; + bo.agentName = dto.agentName; + bo.poseInFrame = dto.poseInFrame; +} +void armarx::objpose::toAron(arondto::ObjectAttachmentInfo& dto, const ObjectAttachmentInfo& bo) +{ + dto.frameName = bo.frameName; + dto.agentName = bo.agentName; + dto.poseInFrame = bo.poseInFrame; +} + +void armarx::objpose::fromAron(const arondto::ObjectType& dto, ObjectTypeEnum& bo) +{ + switch (dto.value) + { + case arondto::ObjectType::AnyObject: + bo = ObjectTypeEnum::AnyObject; + return; + case arondto::ObjectType::KnownObject: + bo = ObjectTypeEnum::KnownObject; + return; + case arondto::ObjectType::UnknownObject: + bo = ObjectTypeEnum::UnknownObject; + return; + } + ARMARX_UNEXPECTED_ENUM_VALUE(arondto::ObjectType, dto.value); +} +void armarx::objpose::toAron(arondto::ObjectType& dto, const ObjectTypeEnum& bo) +{ + switch (bo) + { + case ObjectTypeEnum::AnyObject: + dto.value = arondto::ObjectType::AnyObject; + return; + case ObjectTypeEnum::KnownObject: + dto.value = arondto::ObjectType::KnownObject; + return; + case ObjectTypeEnum::UnknownObject: + dto.value = arondto::ObjectType::UnknownObject; + return; + } + ARMARX_UNEXPECTED_ENUM_VALUE(ObjectTypeEnum, bo); +} + + +void armarx::objpose::fromAron(const arondto::ObjectPose& dto, ObjectPose& bo) +{ + bo.providerName = dto.providerName; + + fromAron(dto.objectType, bo.objectType); + fromAron(dto.objectID, bo.objectID); + + bo.objectPoseRobot = dto.objectPoseRobot; + bo.objectPoseGlobal = dto.objectPoseGlobal; + bo.objectPoseOriginal = dto.objectPoseOriginal; + bo.objectPoseOriginalFrame = dto.objectPoseOriginalFrame; + + bo.robotConfig = dto.robotConfig; + bo.robotPose = dto.robotPose; + + if (dto.attachmentValid) + { + bo.attachment = ObjectAttachmentInfo(); + fromAron(dto.attachment, *bo.attachment); + } + else + { + bo.attachment = std::nullopt; + } + + bo.confidence = dto.confidence; + + bo.timestamp = IceUtil::Time::microSeconds(dto.timestamp); + + if (dto.localOOBBValid) + { + bo.localOOBB = simox::OrientedBoxf(); + fromAron(dto.localOOBB, *bo.localOOBB); + } + else + { + bo.localOOBB = std::nullopt; + } +} + + +void armarx::objpose::toAron(arondto::ObjectPose& dto, const ObjectPose& bo) +{ + dto.providerName = bo.providerName; + + toAron(dto.objectType, bo.objectType); + toAron(dto.objectID, bo.objectID); + + dto.objectPoseRobot = bo.objectPoseRobot; + dto.objectPoseGlobal = bo.objectPoseGlobal; + dto.objectPoseOriginal = bo.objectPoseOriginal; + dto.objectPoseOriginalFrame = bo.objectPoseOriginalFrame; + + dto.robotConfig = bo.robotConfig; + dto.robotPose = bo.robotPose; + + if (bo.attachment) + { + dto.attachmentValid = true; + toAron(dto.attachment, *bo.attachment); + } + else + { + dto.attachmentValid = false; + toAron(dto.attachment, ObjectAttachmentInfo()); + } + + dto.confidence = bo.confidence; + + dto.timestamp = bo.timestamp.toMicroSeconds(); + + if (bo.localOOBB) + { + dto.localOOBBValid = true; + toAron(dto.localOOBB, *bo.localOOBB); + } + else + { + dto.localOOBBValid = false; + toAron(dto.localOOBB, simox::OrientedBoxf()); + } +} + diff --git a/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.h b/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.h new file mode 100644 index 000000000..87239deff --- /dev/null +++ b/source/RobotAPI/libraries/aron/common/aron_conversions/objpose.h @@ -0,0 +1,19 @@ +#pragma once + +#include <RobotAPI/libraries/ArmarXObjects/ObjectPose.h> + +#include <RobotAPI/libraries/ArmarXObjects/aron/ObjectPose.aron.generated.h> +#include <RobotAPI/libraries/ArmarXObjects/aron/ObjectType.aron.generated.h> + + +namespace armarx::objpose +{ + void fromAron(const arondto::ObjectAttachmentInfo& dto, ObjectAttachmentInfo& bo); + void toAron(arondto::ObjectAttachmentInfo& dto, const ObjectAttachmentInfo& bo); + + void fromAron(const arondto::ObjectType& dto, ObjectTypeEnum& bo); + void toAron(arondto::ObjectType& dto, const ObjectTypeEnum& bo); + + void fromAron(const arondto::ObjectPose& dto, ObjectPose& bo); + void toAron(arondto::ObjectPose& dto, const ObjectPose& bo); +} diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/simox.cpp b/source/RobotAPI/libraries/aron/common/aron_conversions/simox.cpp similarity index 100% rename from source/RobotAPI/libraries/ArmarXObjects/aron_conversions/simox.cpp rename to source/RobotAPI/libraries/aron/common/aron_conversions/simox.cpp diff --git a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/simox.h b/source/RobotAPI/libraries/aron/common/aron_conversions/simox.h similarity index 73% rename from source/RobotAPI/libraries/ArmarXObjects/aron_conversions/simox.h rename to source/RobotAPI/libraries/aron/common/aron_conversions/simox.h index 1d7b91492..64e847afb 100644 --- a/source/RobotAPI/libraries/ArmarXObjects/aron_conversions/simox.h +++ b/source/RobotAPI/libraries/aron/common/aron_conversions/simox.h @@ -1,10 +1,10 @@ #pragma once #include <SimoxUtility/shapes/AxisAlignedBoundingBox.h> -#include <SimoxUtility/shapes/OrientedBox.h> +#include <RobotAPI/libraries/aron/common/aron/AxisAlignedBoundingBox.aron.generated.h> -#include <RobotAPI/libraries/ArmarXObjects/aron/AxisAlignedBoundingBox.aron.generated.h> -#include <RobotAPI/libraries/ArmarXObjects/aron/OrientedBox.aron.generated.h> +#include <SimoxUtility/shapes/OrientedBox.h> +#include <RobotAPI/libraries/aron/common/aron/OrientedBox.aron.generated.h> namespace simox -- GitLab