diff --git a/scenarios/PlatformNavigation/config/VisionMemory.cfg b/scenarios/PlatformNavigation/config/VisionMemory.cfg index 22e0d3e62dbf7e3c0012b44f0d65e2e7a1fe3f46..1b95447f4edb52efc404a7bd9c2c00ee89ddf608 100644 --- a/scenarios/PlatformNavigation/config/VisionMemory.cfg +++ b/scenarios/PlatformNavigation/config/VisionMemory.cfg @@ -210,21 +210,12 @@ # ArmarX.VisionMemory.mem.MemoryName = Vision -# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq: Frequency to store the buffer to the LTM in Hz. +# ArmarX.VisionMemory.mem.ltm.configuration: # Attributes: -# - Default: 10 +# - Default: {} # - Case sensitivity: yes # - Required: no -# ArmarX.VisionMemory.mem.ltm..buffer.storeFreq = 10 - - -# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled: -# Attributes: -# - Default: true -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.depthImageExtractor.Enabled = true +# ArmarX.VisionMemory.mem.ltm.configuration = {} # ArmarX.VisionMemory.mem.ltm.enabled: @@ -236,100 +227,6 @@ # ArmarX.VisionMemory.mem.ltm.enabled = false -# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled: -# Attributes: -# - Default: true -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.exrConverter.Enabled = true - - -# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled: -# Attributes: -# - Default: true -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.imageExtractor.Enabled = true - - -# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled: -# Attributes: -# - Default: false -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.memFreqFilter.Enabled = false - - -# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime: Waiting time in MS after each LTM update. -# Attributes: -# - Default: -1 -# - Case sensitivity: yes -# - Required: no -# ArmarX.VisionMemory.mem.ltm.memFreqFilter.WaitingTime = -1 - - -# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled: -# Attributes: -# - Default: true -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.pngConverter.Enabled = true - - -# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes: The size in MB to compress away the current export. Exports are numbered (lower number means newer). -# Attributes: -# - Default: 1024 -# - Case sensitivity: yes -# - Required: no -# ArmarX.VisionMemory.mem.ltm.sizeToCompressDataInMegaBytes = 1024 - - -# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled: -# Attributes: -# - Default: false -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.snapEqFilter.Enabled = false - - -# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime: Max Waiting time in MS after each Entity update. -# Attributes: -# - Default: -1 -# - Case sensitivity: yes -# - Required: no -# ArmarX.VisionMemory.mem.ltm.snapEqFilter.MaxWaitingTime = -1 - - -# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled: -# Attributes: -# - Default: false -# - Case sensitivity: yes -# - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.Enabled = false - - -# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime: Waiting time in MS after each Entity update. -# Attributes: -# - Default: -1 -# - Case sensitivity: yes -# - Required: no -# ArmarX.VisionMemory.mem.ltm.snapFreqFilter.WaitingTime = -1 - - -# ArmarX.VisionMemory.mem.ltm.storagepath: The path to the memory storage (the memory will be stored in a seperate subfolder). -# Attributes: -# - Default: Default value not mapped. -# - Case sensitivity: yes -# - Required: no -# ArmarX.VisionMemory.mem.ltm.storagepath = Default value not mapped. - - # ArmarX.VisionMemory.mns.MemoryNameSystemEnabled: Whether to use (and depend on) the Memory Name System (MNS). # Set to false to use this memory as a stand-alone. # Attributes: diff --git a/scenarios/PlatformNavigation/config/navigation_memory.cfg b/scenarios/PlatformNavigation/config/navigation_memory.cfg index f808f7771be10fe6b63eee35db55e0ab5db5f3cf..8945e9ca86ae9055750010e93a7ae1f88e4db55b 100644 --- a/scenarios/PlatformNavigation/config/navigation_memory.cfg +++ b/scenarios/PlatformNavigation/config/navigation_memory.cfg @@ -217,7 +217,7 @@ # - Default: "" # - Case sensitivity: yes # - Required: no -ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/audimax-science-week-opening +ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graphs/R003 # ArmarX.RedirectStdout: Redirect std::cout and std::cerr to ArmarXLog @@ -285,6 +285,6 @@ ArmarX.NavigationMemory.p.snapshotToLoad = ./PriorKnowledgeData/navigation-graph # - Case sensitivity: yes # - Required: no # - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning} -# ArmarX.Verbosity = Info +ArmarX.Verbosity = Verbose diff --git a/scenarios/PlatformNavigation/config/navigator.cfg b/scenarios/PlatformNavigation/config/navigator.cfg index f6a497b25e20ac551dbcc98a5eb5fd28244e68df..c94f448997d4aaf46f433ffd9982765673ed8eb4 100644 --- a/scenarios/PlatformNavigation/config/navigator.cfg +++ b/scenarios/PlatformNavigation/config/navigator.cfg @@ -92,298 +92,323 @@ # ArmarX.LoggingGroup = "" -# ArmarX.Navigator.ArVizStorageName: Name of the ArViz storage +# ArmarX.Navigator.ObjectName: No Description # Attributes: -# - Default: ArVizStorage -# - Case sensitivity: yes +# - Default: navigator +# - Case sensitivity: no # - Required: no -# ArmarX.Navigator.ArVizStorageName = ArVizStorage +ArmarX.Navigator.ObjectName = navigator -# ArmarX.Navigator.ArVizTopicName: Name of the ArViz topic +# ArmarX.Navigator.RobotUnitName: No Description # Attributes: -# - Default: ArVizTopic -# - Case sensitivity: yes +# - Default: Armar6Unit +# - Case sensitivity: no +# - Required: no +ArmarX.Navigator.RobotUnitName = Armar6Unit + + +# ArmarX.Navigator.cmp.PlatformUnit: No Description +# Attributes: +# - Default: Armar6PlatformUnit +# - Case sensitivity: no # - Required: no -# ArmarX.Navigator.ArVizTopicName = ArVizTopic +ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit -# ArmarX.Navigator.EnableProfiling: enable profiler which is used for logging performance events +# ArmarX.Navigator.p.occupancy_grid.occopied_threshold: No Description # Attributes: -# - Default: false +# - Default: 0.8 +# - Case sensitivity: no +# - Required: no +ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8 + + +# ArmarX.RedirectStdout: Redirect std::cout and std::cerr to ArmarXLog +# Attributes: +# - Default: true # - Case sensitivity: yes # - Required: no # - Possible values: {0, 1, false, no, true, yes} -# ArmarX.Navigator.EnableProfiling = false +# ArmarX.RedirectStdout = true -# ArmarX.Navigator.MinimumLoggingLevel: Local logging level only for this component +# ArmarX.RemoteHandlesDeletionTimeout: The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles) # Attributes: -# - Default: Undefined +# - Default: 3000 # - Case sensitivity: yes # - Required: no -# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning} -# ArmarX.Navigator.MinimumLoggingLevel = Undefined +# ArmarX.RemoteHandlesDeletionTimeout = 3000 -# ArmarX.Navigator.ObjectMemoryName: Name of the object memory. +# ArmarX.SecondsStartupDelay: The startup will be delayed by this number of seconds (useful for debugging) # Attributes: -# - Default: ObjectMemory +# - Default: 0 # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.ObjectMemoryName = ObjectMemory +# ArmarX.SecondsStartupDelay = 0 -# ArmarX.Navigator.ObjectName: Name of IceGrid well-known object +# ArmarX.StartDebuggerOnCrash: If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger. # Attributes: -# - Default: "" +# - Default: false # - Case sensitivity: yes # - Required: no -ArmarX.Navigator.ObjectName = navigator +# - Possible values: {0, 1, false, no, true, yes} +# ArmarX.StartDebuggerOnCrash = false -# ArmarX.Navigator.RobotUnitName: Name of the RobotUnit +# ArmarX.ThreadPoolSize: Size of the ArmarX ThreadPool that is always running. # Attributes: +# - Default: 1 # - Case sensitivity: yes -# - Required: yes -ArmarX.Navigator.RobotUnitName = Armar6Unit +# - Required: no +# ArmarX.ThreadPoolSize = 1 -# ArmarX.Navigator.cmp.PlatformUnit: No Description +# ArmarX.TopicSuffix: Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes. # Attributes: -# - Default: Armar6PlatformUnit -# - Case sensitivity: no +# - Default: "" +# - Case sensitivity: yes # - Required: no -ArmarX.Navigator.cmp.PlatformUnit = Armar6PlatformUnit +# ArmarX.TopicSuffix = "" -# ArmarX.Navigator.cmp.RemoteGui: Ice object name of the `RemoteGui` component. +# ArmarX.UseTimeServer: Enable using a global Timeserver (e.g. from ArmarXSimulator) # Attributes: -# - Default: RemoteGuiProvider +# - Default: false # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.cmp.RemoteGui = RemoteGuiProvider +# - Possible values: {0, 1, false, no, true, yes} +# ArmarX.UseTimeServer = false -# ArmarX.Navigator.mem.nav.costmap.CoreSegment: +# ArmarX.Verbosity: Global logging level for whole application # Attributes: -# - Default: Costmap +# - Default: Info # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.costmap.CoreSegment = Costmap +# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning} +ArmarX.Verbosity = Verbose -# ArmarX.Navigator.mem.nav.costmap.Memory: +# ArmarX.navigator.ArVizStorageName: Name of the ArViz storage # Attributes: -# - Default: Navigation +# - Default: ArVizStorage # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.costmap.Memory = Navigation +# ArmarX.navigator.ArVizStorageName = ArVizStorage -# ArmarX.Navigator.mem.nav.costmap.Provider: Name of this provider +# ArmarX.navigator.ArVizTopicName: Name of the ArViz topic # Attributes: -# - Default: "" +# - Default: ArVizTopic # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.costmap.Provider = "" +# ArmarX.navigator.ArVizTopicName = ArVizTopic -# ArmarX.Navigator.mem.nav.events.CoreSegment: +# ArmarX.navigator.EnableProfiling: enable profiler which is used for logging performance events # Attributes: -# - Default: Events +# - Default: false +# - Case sensitivity: yes +# - Required: no +# - Possible values: {0, 1, false, no, true, yes} +# ArmarX.navigator.EnableProfiling = false + + +# ArmarX.navigator.MinimumLoggingLevel: Local logging level only for this component +# Attributes: +# - Default: Undefined # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.events.CoreSegment = Events +# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning} +# ArmarX.navigator.MinimumLoggingLevel = Undefined -# ArmarX.Navigator.mem.nav.events.Memory: +# ArmarX.navigator.ObjectMemoryName: Name of the object memory. # Attributes: -# - Default: Navigation +# - Default: ObjectMemory # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.events.Memory = Navigation +# ArmarX.navigator.ObjectMemoryName = ObjectMemory -# ArmarX.Navigator.mem.nav.events.Provider: Name of this provider +# ArmarX.navigator.ObjectName: Name of IceGrid well-known object # Attributes: # - Default: "" # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.events.Provider = "" +# ArmarX.navigator.ObjectName = "" -# ArmarX.Navigator.mem.nav.graph.CoreSegment: +# ArmarX.navigator.RobotUnitName: Name of the RobotUnit # Attributes: -# - Default: Location # - Case sensitivity: yes -# - Required: no -# ArmarX.Navigator.mem.nav.graph.CoreSegment = Location +# - Required: yes +# ArmarX.navigator.RobotUnitName = ::_NOT_SET_:: -# ArmarX.Navigator.mem.nav.graph.Memory: +# ArmarX.navigator.cmp.RemoteGui: Ice object name of the `RemoteGui` component. # Attributes: -# - Default: Navigation +# - Default: RemoteGuiProvider # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.graph.Memory = Navigation +# ArmarX.navigator.cmp.RemoteGui = RemoteGuiProvider -# ArmarX.Navigator.mem.nav.param.CoreSegment: +# ArmarX.navigator.mem.nav.costmap.CoreSegment: # Attributes: -# - Default: Parameterization +# - Default: Costmap # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.param.CoreSegment = Parameterization +# ArmarX.navigator.mem.nav.costmap.CoreSegment = Costmap -# ArmarX.Navigator.mem.nav.param.Memory: +# ArmarX.navigator.mem.nav.costmap.Memory: # Attributes: # - Default: Navigation # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.param.Memory = Navigation +# ArmarX.navigator.mem.nav.costmap.Memory = Navigation -# ArmarX.Navigator.mem.nav.param.Provider: Name of this provider +# ArmarX.navigator.mem.nav.events.CoreSegment: # Attributes: -# - Default: "" +# - Default: Events # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.param.Provider = "" +# ArmarX.navigator.mem.nav.events.CoreSegment = Events -# ArmarX.Navigator.mem.nav.stack_result.CoreSegment: +# ArmarX.navigator.mem.nav.events.Memory: # Attributes: -# - Default: "" +# - Default: Navigation # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.stack_result.CoreSegment = "" +# ArmarX.navigator.mem.nav.events.Memory = Navigation -# ArmarX.Navigator.mem.nav.stack_result.Memory: +# ArmarX.navigator.mem.nav.events.Provider: Name of this provider # Attributes: -# - Default: Navigation +# - Default: "" # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.stack_result.Memory = Navigation +# ArmarX.navigator.mem.nav.events.Provider = "" -# ArmarX.Navigator.mem.nav.stack_result.Provider: Name of this provider +# ArmarX.navigator.mem.nav.graph.CoreSegment: # Attributes: -# - Default: "" +# - Default: Location # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.nav.stack_result.Provider = "" +# ArmarX.navigator.mem.nav.graph.CoreSegment = Location -# ArmarX.Navigator.mem.robot_state.Memory: +# ArmarX.navigator.mem.nav.graph.Memory: # Attributes: -# - Default: RobotState +# - Default: Navigation # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.robot_state.Memory = RobotState +# ArmarX.navigator.mem.nav.graph.Memory = Navigation -# ArmarX.Navigator.mem.robot_state.localizationSegment: Name of the localization memory core segment to use. +# ArmarX.navigator.mem.nav.param.CoreSegment: # Attributes: -# - Default: Localization +# - Default: Parameterization # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mem.robot_state.localizationSegment = Localization +# ArmarX.navigator.mem.nav.param.CoreSegment = Parameterization -# ArmarX.Navigator.mns.MemoryNameSystemEnabled: Whether to use (and depend on) the Memory Name System (MNS). -# Set to false to use this memory as a stand-alone. +# ArmarX.navigator.mem.nav.param.Memory: # Attributes: -# - Default: true +# - Default: Navigation # - Case sensitivity: yes # - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.Navigator.mns.MemoryNameSystemEnabled = true +# ArmarX.navigator.mem.nav.param.Memory = Navigation -# ArmarX.Navigator.mns.MemoryNameSystemName: Name of the Memory Name System (MNS) component. +# ArmarX.navigator.mem.nav.param.Provider: Name of this provider # Attributes: -# - Default: MemoryNameSystem +# - Default: "" # - Case sensitivity: yes # - Required: no -# ArmarX.Navigator.mns.MemoryNameSystemName = MemoryNameSystem +# ArmarX.navigator.mem.nav.param.Provider = "" -# ArmarX.Navigator.p.occupancy_grid.occopied_threshold: Threshold for each cell to be considered occupied. Increase this value to reduce noise. +# ArmarX.navigator.mem.nav.stack_result.CoreSegment: # Attributes: -# - Default: 0.550000012 +# - Default: "" # - Case sensitivity: yes # - Required: no -ArmarX.Navigator.p.occupancy_grid.occopied_threshold = 0.8 +# ArmarX.navigator.mem.nav.stack_result.CoreSegment = "" -# ArmarX.RedirectStdout: Redirect std::cout and std::cerr to ArmarXLog +# ArmarX.navigator.mem.nav.stack_result.Memory: # Attributes: -# - Default: true +# - Default: Navigation # - Case sensitivity: yes # - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.RedirectStdout = true +# ArmarX.navigator.mem.nav.stack_result.Memory = Navigation -# ArmarX.RemoteHandlesDeletionTimeout: The timeout (in ms) before a remote handle deletes the managed object after the use count reached 0. This time can be used by a client to increment the count again (may be required when transmitting remote handles) +# ArmarX.navigator.mem.nav.stack_result.Provider: Name of this provider # Attributes: -# - Default: 3000 +# - Default: "" # - Case sensitivity: yes # - Required: no -# ArmarX.RemoteHandlesDeletionTimeout = 3000 +# ArmarX.navigator.mem.nav.stack_result.Provider = "" -# ArmarX.SecondsStartupDelay: The startup will be delayed by this number of seconds (useful for debugging) +# ArmarX.navigator.mem.robot_state.Memory: # Attributes: -# - Default: 0 +# - Default: RobotState # - Case sensitivity: yes # - Required: no -# ArmarX.SecondsStartupDelay = 0 +# ArmarX.navigator.mem.robot_state.Memory = RobotState -# ArmarX.StartDebuggerOnCrash: If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger. +# ArmarX.navigator.mem.robot_state.localizationSegment: Name of the localization memory core segment to use. # Attributes: -# - Default: false +# - Default: Localization # - Case sensitivity: yes # - Required: no -# - Possible values: {0, 1, false, no, true, yes} -# ArmarX.StartDebuggerOnCrash = false +# ArmarX.navigator.mem.robot_state.localizationSegment = Localization -# ArmarX.ThreadPoolSize: Size of the ArmarX ThreadPool that is always running. +# ArmarX.navigator.mns.MemoryNameSystemEnabled: Whether to use (and depend on) the Memory Name System (MNS). +# Set to false to use this memory as a stand-alone. # Attributes: -# - Default: 1 +# - Default: true # - Case sensitivity: yes # - Required: no -# ArmarX.ThreadPoolSize = 1 +# - Possible values: {0, 1, false, no, true, yes} +# ArmarX.navigator.mns.MemoryNameSystemEnabled = true -# ArmarX.TopicSuffix: Suffix appended to all topic names for outgoing topics. This is mainly used to direct all topics to another name for TopicReplaying purposes. +# ArmarX.navigator.mns.MemoryNameSystemName: Name of the Memory Name System (MNS) component. # Attributes: -# - Default: "" +# - Default: MemoryNameSystem # - Case sensitivity: yes # - Required: no -# ArmarX.TopicSuffix = "" +# ArmarX.navigator.mns.MemoryNameSystemName = MemoryNameSystem -# ArmarX.UseTimeServer: Enable using a global Timeserver (e.g. from ArmarXSimulator) +# ArmarX.navigator.p.disableExecutor: If the executor is disabled, the navigator will only plan the trajectory but won't execute it. # Attributes: # - Default: false # - Case sensitivity: yes # - Required: no # - Possible values: {0, 1, false, no, true, yes} -# ArmarX.UseTimeServer = false +# ArmarX.navigator.p.disableExecutor = false -# ArmarX.Verbosity: Global logging level for whole application +# ArmarX.navigator.p.occupancy_grid.occopied_threshold: Threshold for each cell to be considered occupied. Increase this value to reduce noise. # Attributes: -# - Default: Info +# - Default: 0.550000012 # - Case sensitivity: yes # - Required: no -# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning} -ArmarX.Verbosity = Verbose +# ArmarX.navigator.p.occupancy_grid.occopied_threshold = 0.550000012 diff --git a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt index 06bd40803f1b508891608aadd055e0e24138d3fe..01196c1455fa9f064d9eaab04f9ec243a0551647 100644 --- a/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt +++ b/source/armarx/navigation/components/NavigationMemory/CMakeLists.txt @@ -1,4 +1,9 @@ armarx_add_component(navigation_memory + ICE_DEPENDENCIES + ArmarXCoreInterfaces + RobotAPIInterfaces + ICE_FILES + ComponentInterface.ice DEPENDENCIES # ArmarXCore ArmarXCore diff --git a/source/armarx/navigation/components/NavigationMemory/ComponentInterface.ice b/source/armarx/navigation/components/NavigationMemory/ComponentInterface.ice new file mode 100644 index 0000000000000000000000000000000000000000..b7c4d6d92b0292d39a0fd5f8b312919c9120b024 --- /dev/null +++ b/source/armarx/navigation/components/NavigationMemory/ComponentInterface.ice @@ -0,0 +1,47 @@ +/** +* 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 as +* published by the Free Software Foundation; either version 2 of +* the License, or (at your option) any later version. +* +* 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 Lesser 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 +* @author Rainer Kartmann +* @copyright 2020 Humanoids Group, H2T, KIT +* @license http://www.gnu.org/licenses/gpl-2.0.txt +* GNU General Public License +*/ + +#pragma once + +#include <RobotAPI/interface/armem/server/MemoryInterface.ice> + +#include <RobotAPI/interface/objectpose/ObjectPoseStorageInterface.ice> +#include <ArmarXCore/interface/core/PackagePath.ice> +// #include <ArmarXCore/interface/core/PackagePath.h> + + +module armarx +{ + module navigation + { + module memory + { + interface NavigationMemoryInterface extends + armarx::armem::server::MemoryInterface + { + bool storeLocationGraph(armarx::data::PackagePath packagePath); + }; + + }; + }; +}; diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp index c3bec2c61a63b1e21b9b9e6114558e9b013074fe..d000113f7d5b064c792c835118f3b580ad97d25c 100644 --- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp +++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.cpp @@ -23,15 +23,24 @@ #include "NavigationMemory.h" // STD / STL +#include <cstddef> #include <filesystem> #include <fstream> #include <iostream> +#include <iterator> +#include <SimoxUtility/json/json.hpp> + +#include "ArmarXCore/core/PackagePath.h" +#include "ArmarXCore/core/logging/Logging.h" #include <ArmarXCore/core/system/ArmarXDataPath.h> #include <ArmarXCore/core/time/CycleUtil.h> #include <ArmarXCore/libraries/DecoupledSingleComponent/Decoupled.h> +#include "RobotAPI/libraries/armem/core/MemoryID.h" +#include "RobotAPI/libraries/armem/core/wm/aron_conversions.h" #include <RobotAPI/libraries/armem/client/query.h> +#include <RobotAPI/libraries/armem/core/aron_conversions.h> #include <RobotAPI/libraries/armem/core/operations.h> #include <RobotAPI/libraries/armem/server/ltm/disk/Memory.h> #include <RobotAPI/libraries/armem/server/wm/memory_definitions.h> @@ -39,7 +48,6 @@ #include "Visu.h" #include <armarx/navigation/algorithms/Costmap.h> -#include <armarx/navigation/memory/constants.h> #include <armarx/navigation/algorithms/aron/Costmap.aron.generated.h> #include <armarx/navigation/core/Graph.h> #include <armarx/navigation/core/aron/Graph.aron.generated.h> @@ -48,7 +56,7 @@ #include <armarx/navigation/core/aron/Twist.aron.generated.h> #include <armarx/navigation/graph/constants.h> #include <armarx/navigation/location/constants.h> - +#include <armarx/navigation/memory/constants.h> namespace armarx::navigation { @@ -135,7 +143,8 @@ namespace armarx::navigation // This section loads the snapshot specified by the scenario parameters // resolve the paths for the locations and graphs const std::filesystem::path graph = snapshotToLoadPath / "Graph"; - const std::filesystem::path location = snapshotToLoadPath / "Location"; + const std::filesystem::path locationsFilename = + snapshotToLoadPath / "locations.json"; // remove date from folder name (if present) // Sometimes, we use the date before the snapshotname and use a symlink to the real data (e.g. R003 and 2022-03-01_R003) @@ -145,62 +154,63 @@ namespace armarx::navigation // This if statement loads the location. Each location is a single file (without extension). The filename is the name of the location. // The file contains json with the globalRobotPose (4x4 matrix) and relativeToObject information - if (std::filesystem::is_directory(location)) + if (std::filesystem::is_regular_file(locationsFilename)) { armem::Commit c; armem::MemoryID providerID = workingMemory().id(); providerID.coreSegmentName = "Location"; providerID.providerSegmentName = providerName; - for (const auto& subdir : std::filesystem::directory_iterator( - location)) // iterate over all files in folder (the locations) + + const auto now = armem::Time::Now(); + { - const std::filesystem::path location = subdir.path(); if (std::filesystem::is_regular_file( - location)) // check if its a file (otherwise skip) + locationsFilename)) // check if its a file (otherwise skip) { - std::ifstream ifs(location); + ARMARX_VERBOSE << "Loading " << locationsFilename; + std::ifstream ifs(locationsFilename); const std::string content((std::istreambuf_iterator<char>(ifs)), (std::istreambuf_iterator<char>())); // parse location as json. All files in Location folder must be valid json objects! - nlohmann::json j = nlohmann::json::parse(content); + nlohmann::json js = nlohmann::json::parse(content); - if (j.find("globalRobotPose") == j.end()) + for (const auto& [locationMemoryIdStr, j] : + js["locations"].get<std::map<std::string, nlohmann::json>>()) { - ARMARX_WARNING - << "The file '" << location.string() - << "' has no 'globalRobotPose' member. Skipping this file."; - continue; - } - - if (j.find("relativeToObject") == j.end()) - { - ARMARX_WARNING - << "The file '" << location.string() - << "' has no 'relativeToObject' member. Skipping this file."; - continue; - } - - std::vector<float> p = j.at("globalRobotPose"); - ARMARX_CHECK_EQUAL(p.size(), 16); - - navigation::location::arondto::Location loc; - loc.globalRobotPose << p[0], p[1], p[2], p[3], p[4], p[5], p[6], p[7], - p[8], p[9], p[10], p[11], p[12], p[13], p[14], - p[15]; // load the 4x4 matrix + if (j.find("globalRobotPose") == j.end()) + { + ARMARX_WARNING << "The element '" << locationMemoryIdStr + << "' has no 'globalRobotPose' member. Skipping " + "this entity."; + continue; + } - // TODO: All location I have seen were null. - // I don't know how this member should look like (von @Fabian Peller to @Fabian Reister) - loc.relativeToObject = std::nullopt; + if (j.find("relativeToObject") == j.end()) + { + ARMARX_WARNING << "The element '" << locationMemoryIdStr + << "' has no 'relativeToObject' member. " + "Skipping this entity."; + continue; + } - // send commit to memory - auto& up = c.add(); - up.confidence = 1.0; - up.timeCreated = armem::Time::Now(); - up.timeSent = armem::Time::Now(); - up.timeArrived = armem::Time::Now(); - up.entityID = providerID.withEntityName(location.filename().string()); - up.instancesData = {loc.toAron()}; + navigation::location::arondto::Location loc; + j.at("globalRobotPose") + .get_to(loc.globalRobotPose); // load the 4x4 matrix + + // TODO: All location I have seen were null. + // I don't know how this member should look like (von @Fabian Peller to @Fabian Reister) + loc.relativeToObject = std::nullopt; + + // send commit to memory + auto& up = c.add(); + up.confidence = 1.0; + up.timeCreated = now; + up.timeSent = now; + up.timeArrived = now; + up.entityID = armarx::armem::MemoryID(locationMemoryIdStr); + up.instancesData = {loc.toAron()}; + } } } @@ -208,7 +218,9 @@ namespace armarx::navigation iceAdapter().commit(c); } - // Next we load the graphs. The graph folder may contain several graphs, represented by different folders. + const auto now = armem::Time::Now(); + + // Next we load the graphs. The graph folder may contain several graphs, represented by different json files. // Each of those graphs contains a list of files representing the vertices. The filename is the vertice id (ideally starting at 0). // The file contains a json with the corresponding location name (as path) and the adjacent vertives (representing the directed outgoing edges). if (std::filesystem::is_directory(graph)) @@ -219,82 +231,58 @@ namespace armarx::navigation providerID.providerSegmentName = providerName; for (const auto& graphdir : std::filesystem::directory_iterator( - graph)) // iterate over the different graphs (subfolders) + graph)) // iterate over the different graphs (json files) { - const std::filesystem::path singleGraph = graphdir.path(); - if (std::filesystem::is_directory( - singleGraph)) // assure that its a folder. otherwise skip + if (std::filesystem::is_regular_file( + graphdir.path())) // assure that its a json file { + const std::string graphName = graphdir.path().stem(); + navigation::core::arondto::Graph g; - for (const auto& subdir : std::filesystem::directory_iterator( - singleGraph)) // iterate over all files in the graph + ARMARX_VERBOSE << "Loading graph `" << graphName << " `from file `" + << graphdir.path() << "`."; + + std::ifstream ifs(graphdir.path()); + const std::string content((std::istreambuf_iterator<char>(ifs)), + (std::istreambuf_iterator<char>())); + + nlohmann::json j = nlohmann::json::parse(content); + + const auto& jEdges = j.at("edges"); + const auto& jVertices = j.at("vertices"); + + for (const auto& jVertex : jVertices) { - const std::filesystem::path vertice = subdir.path(); - if (std::filesystem::is_regular_file( - vertice)) // assure its a file. otherwise skip - { - std::ifstream ifs(vertice); - const std::string content((std::istreambuf_iterator<char>(ifs)), - (std::istreambuf_iterator<char>())); - - // parse vertice. Each vertice must be a valid json object - nlohmann::json j = nlohmann::json::parse(content); - if (j.find("location") == j.end()) - { - ARMARX_WARNING - << "The file '" << vertice.string() - << "' has no 'location' member. Skipping this file."; - continue; - } - - if (j.find("outgoingEdges") == j.end()) - { - ARMARX_WARNING << "The file '" << vertice.string() - << "' has no 'outgoingEdges' member. " - "Skipping this file."; - continue; - } - - std::string location = j.at("location"); - int id = std::stoi(vertice.filename()); - - auto split = simox::alg::split(location, "/"); - ARMARX_CHECK_EQUAL( - split.size(), - 4); // the location is always a path like Navigation/Location/XXX/YYY - - armarx::navigation::core::arondto::Vertex v; - v.vertexID = id; - v.locationID.memoryName = split[0]; - v.locationID.coreSegmentName = split[1]; - v.locationID.providerSegmentName = split[2]; - v.locationID.entityName = split[3]; - toAron(v.locationID.timestamp, armem::Time::Invalid()); - v.locationID.instanceIndex = 0; - - g.vertices.push_back(v); - - // add edges of this vertice to graph - std::vector<float> edges = j.at("outgoingEdges"); - - for (const auto edge_id : edges) - { - armarx::navigation::core::arondto::Edge e; - e.sourceVertexID = id; - e.targetVertexID = edge_id; - g.edges.push_back(e); - } - } + const armarx::armem::MemoryID vertexLocationMemoryId( + jVertex.at("locationID")); + + armarx::navigation::core::arondto::Vertex v; + v.vertexID = jVertex.at("vertexID"); + toAron(v.locationID, vertexLocationMemoryId); + toAron(v.locationID.timestamp, armem::Time::Invalid()); + v.locationID.instanceIndex = 0; + + g.vertices.push_back(v); + } + + for (const auto& jEdge : jEdges) + { + std::pair<std::int64_t, std::int64_t> edgeSourceTargetPair; + jEdge.get_to(edgeSourceTargetPair); + + armarx::navigation::core::arondto::Edge e; + e.sourceVertexID = edgeSourceTargetPair.first; + e.targetVertexID = edgeSourceTargetPair.second; + g.edges.push_back(e); } auto& up = c.add(); up.confidence = 1.0; - up.timeCreated = armem::Time::Now(); - up.timeSent = armem::Time::Now(); - up.timeArrived = armem::Time::Now(); - up.entityID = - providerID.withEntityName(singleGraph.filename().string()); + up.timeCreated = now; + up.timeSent = now; + up.timeArrived = now; + up.entityID = providerID.withEntityName(graphName); up.instancesData = {g.toAron()}; } } @@ -457,5 +445,191 @@ namespace armarx::navigation } } + bool + store(const std::map<armem::MemoryID, core::Graph>& graphs, + const std::filesystem::path& baseDirectory) + { + ARMARX_INFO << "Creating export directory `" << baseDirectory << "`."; + std::filesystem::create_directories(baseDirectory); + + for (const auto& [memoryId, graph] : graphs) + { + const std::filesystem::path nestedSubDir = + std::filesystem::path(memoryId.providerSegmentName) / memoryId.coreSegmentName; + const std::filesystem::path dir = baseDirectory / nestedSubDir; + + std::filesystem::create_directories(dir); + + nlohmann::json j; + + // source -> target + std::vector<std::pair<std::size_t, std::size_t>> outgoingEdges; + std::transform(graph.m_edges.begin(), + graph.m_edges.end(), + std::back_inserter(outgoingEdges), + [](const auto& edge) + { return std::make_pair(edge.m_source, edge.m_target); }); + + j["edges"] = outgoingEdges; + j["vertices"] = {}; + + for (const auto& vertex : graph.m_vertices) + { + + armarx::armem::MemoryID locationId; + fromAron(vertex.m_property.aron.locationID, locationId); + + nlohmann::json jVertex; + jVertex["locationID"] = locationId.getEntityID().str(); + jVertex["vertexID"] = vertex.m_property.aron.vertexID; + + j["vertices"].push_back(jVertex); + } + + // save to disk + const std::filesystem::path filename = dir / (memoryId.entityName + ".json"); + ARMARX_VERBOSE << "Saving file `" << filename << "`."; + std::ofstream ofs(filename); + ofs << std::setw(4) << j; + } + + return true; + } + + bool + store(const std::map<armem::MemoryID, location::arondto::Location>& locations, + const std::filesystem::path& baseDirectory) + { + ARMARX_INFO << "Creating export directory `" << baseDirectory << "`."; + std::filesystem::create_directories(baseDirectory); + + // key: provider id + std::map<std::string, nlohmann::json> js; + + + for (const auto& [memoryId, location] : locations) + { + auto& j = js[memoryId.providerSegmentName]; + + if (j.count("locations") == 0) + { + j["locations"] = {}; + } + + nlohmann::json jLoc; + + jLoc["globalRobotPose"] = location.globalRobotPose; + + if (location.relativeToObject) + { + armarx::armem::MemoryID memoryId; + fromAron(location.relativeToObject->objectInstanceID, memoryId); + + jLoc["relativeToObject"]["objectInstanceID"] = memoryId.str(); + jLoc["relativeToObject"]["relativeRobotPose"] = + location.relativeToObject->relativeRobotPose; + } + else + { + jLoc["relativeToObject"] = "null"; + } + + j["locations"][memoryId.getEntityID().str()] = jLoc; + } + + // save to disk + for (const auto& [providerId, j] : js) + { + const std::filesystem::path subDir = std::filesystem::path(providerId); + const std::filesystem::path dir = baseDirectory / subDir; + + if (not std::filesystem::exists(dir)) + { + std::filesystem::create_directories(dir); + } + + const std::filesystem::path filename = dir / "locations.json"; + ARMARX_VERBOSE << "Saving file `" << filename << "`."; + std::ofstream ofs(filename); + ofs << std::setw(4) << j; + } + + + return true; + } + + + bool + NavigationMemory::storeLocationGraph(const armarx::data::PackagePath& packagePath, + const Ice::Current& current) + { + armem::server::wm::CoreSegment& locationCoreSegment = + workingMemory().getCoreSegment(navigation::location::coreSegmentID); + armem::server::wm::CoreSegment& graphCoreSegment = + workingMemory().getCoreSegment(navigation::graph::coreSegmentID); + + // obtain locations and graphs + + const std::map<armem::MemoryID, location::arondto::Location> locations = + [&locationCoreSegment]() + { + std::map<armem::MemoryID, location::arondto::Location> locations; + locationCoreSegment.doLocked( + [&]() + { + locationCoreSegment.forEachEntity( + [&](const armarx::armem::server::wm::Entity& entity) -> bool + { + if (const armarx::armem::server::wm::EntityInstance* instance = + entity.findLatestInstance()) + { + locations[entity.id()].fromAron(instance->data()); + } + + return true; + }); + + return true; + }); + + return locations; + }(); + + const auto graphs = [&graphCoreSegment]() + { + std::map<armem::MemoryID, core::Graph> graphs; + graphCoreSegment.doLocked( + [&]() + { + graphCoreSegment.forEachEntity( + [&](const armarx::armem::server::wm::Entity& entity) -> bool + { + core::Graph& graph = graphs[entity.id()]; + if (const armarx::armem::server::wm::EntityInstance* instance = + entity.findLatestInstance()) + { + navigation::core::arondto::Graph aron; + aron.fromAron(instance->data()); + fromAron(aron, graph); + } + + return true; + }); + }); + + return graphs; + }(); + + + // store on disk + + const std::filesystem::path baseDirectory = armarx::PackagePath(packagePath).toSystemPath(); + + store(locations, baseDirectory); + store(graphs, baseDirectory); + + return true; + } + } // namespace armarx::navigation diff --git a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h index 11bd41fd1785a347daf20aa516a7d8bb232f5754..e6464265300fa98314a1989253e9b227071b325f 100644 --- a/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h +++ b/source/armarx/navigation/components/NavigationMemory/NavigationMemory.h @@ -25,6 +25,7 @@ #include <ArmarXCore/core/Component.h> #include <ArmarXCore/core/services/tasks/TaskUtil.h> +#include <ArmarXCore/interface/core/PackagePath.h> #include <ArmarXGui/libraries/ArmarXGuiComponentPlugins/LightweightRemoteGuiComponentPlugin.h> #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h> @@ -34,6 +35,8 @@ #include <mutex> +#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h> + namespace armarx::navigation { @@ -50,17 +53,20 @@ namespace armarx::navigation * Detailed description of class NavigationMemory. */ class NavigationMemory : - virtual public armarx::Component + virtual public armarx::Component, // , virtual public armarx::DebugObserverComponentPluginUser - , virtual public armarx::LightweightRemoteGuiComponentPluginUser, virtual public armarx::ArVizComponentPluginUser, - virtual public armarx::armem::server::ReadWritePluginUser + virtual public armarx::armem::server::ReadWritePluginUser, + virtual public memory::NavigationMemoryInterface { public: /// @see armarx::ManagedIceObject::getDefaultName() std::string getDefaultName() const override; + bool storeLocationGraph(const armarx::data::PackagePath& packagePath, const Ice::Current& current) override; + + protected: /// @see PropertyUser::createPropertyDefinitions() diff --git a/source/armarx/navigation/gui-plugins/LocationGraphEditor/CMakeLists.txt b/source/armarx/navigation/gui-plugins/LocationGraphEditor/CMakeLists.txt index e12c2b6aabca29cf2f484766e1dbfc86ce56d1d2..c8cd2932321fcf06edf66123b7c21b6fbe8352a9 100644 --- a/source/armarx/navigation/gui-plugins/LocationGraphEditor/CMakeLists.txt +++ b/source/armarx/navigation/gui-plugins/LocationGraphEditor/CMakeLists.txt @@ -56,4 +56,5 @@ armarx_add_qt_plugin(qt_plugin_LocationGraphEditor armarx_navigation::location armarx_navigation::graph + armarx_navigation::navigation_memory_ice ) diff --git a/source/armarx/navigation/gui-plugins/LocationGraphEditor/LocationGraphEditorWidget.ui b/source/armarx/navigation/gui-plugins/LocationGraphEditor/LocationGraphEditorWidget.ui index db72fa0c83009a8fa6c55cd40cf5e2ef39ae552c..d13d0c05feae8e905447e1ec4dabb75065fbdc64 100644 --- a/source/armarx/navigation/gui-plugins/LocationGraphEditor/LocationGraphEditorWidget.ui +++ b/source/armarx/navigation/gui-plugins/LocationGraphEditor/LocationGraphEditorWidget.ui @@ -120,6 +120,70 @@ </layout> </widget> </item> + <item> + <widget class="QGroupBox" name="groupBox"> + <property name="minimumSize"> + <size> + <width>0</width> + <height>130</height> + </size> + </property> + <property name="title"> + <string>Export</string> + </property> + <widget class="QPushButton" name="exportButton"> + <property name="geometry"> + <rect> + <x>30</x> + <y>100</y> + <width>84</width> + <height>28</height> + </rect> + </property> + <property name="text"> + <string>Export</string> + </property> + </widget> + <widget class="QWidget" name="horizontalLayoutWidget"> + <property name="geometry"> + <rect> + <x>0</x> + <y>30</y> + <width>308</width> + <height>61</height> + </rect> + </property> + <layout class="QHBoxLayout" name="horizontalLayout"> + <item> + <widget class="QLineEdit" name="packageNameEdit"> + <property name="minimumSize"> + <size> + <width>150</width> + <height>0</height> + </size> + </property> + <property name="text"> + <string>PriorKnowledgeData</string> + </property> + </widget> + </item> + <item> + <widget class="QLineEdit" name="packageDirectoryEdit"> + <property name="minimumSize"> + <size> + <width>150</width> + <height>0</height> + </size> + </property> + <property name="text"> + <string>navigation-graphs</string> + </property> + </widget> + </item> + </layout> + </widget> + </widget> + </item> <item> <widget class="QGroupBox" name="robotVisuGroupBox"> <property name="title"> diff --git a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp index 33c40dfc3147484998f36f4ea1fe66ceead87404..b59ac4cf2f3cb846c95cb027f16cc796368ba376 100644 --- a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp +++ b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.cpp @@ -26,6 +26,7 @@ #include <ArmarXCore/core/exceptions/local/ExpressionException.h> #include <ArmarXCore/core/logging/Logging.h> +#include <ArmarXCore/core/PackagePath.h> #include <RobotAPI/components/ArViz/Client/Client.h> #include <RobotAPI/libraries/armem/client/MemoryNameSystem.h> @@ -40,11 +41,13 @@ #include "widgets/graph_scene/Scene.h" #include "widgets/graph_scene/Widget.h" #include "widgets/utils.h" +#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h> #include <armarx/navigation/core/aron/Graph.aron.generated.h> #include <armarx/navigation/core/aron/Location.aron.generated.h> #include <armarx/navigation/graph/constants.h> #include <armarx/navigation/gui-plugins/LocationGraphEditor/ui_LocationGraphEditorWidget.h> #include <armarx/navigation/location/constants.h> +#include <armarx/navigation/components/NavigationMemory/ComponentInterface.h> // Qt headers #include <QDialog> @@ -165,8 +168,20 @@ namespace armarx::navigation::qt_plugins::location_graph_editor &This::removeEdgesOfVertex); connect(view.edgeTable, &EdgeTableWidget::edgeRemovalRequested, this, &This::removeEdges); + + // export + connect(widget.exportButton, &QPushButton::clicked, this, &This::exportLocationGraph); } + void WidgetController::exportLocationGraph() + { + auto navigationMemoryPrx = + getProxy<memory::NavigationMemoryInterfacePrx>("NavigationMemory"); + + const ::armarx::PackagePath packagePath(widget.packageNameEdit->text().toStdString(), widget.packageDirectoryEdit->text().toStdString()); + + navigationMemoryPrx->storeLocationGraph(packagePath.serialize()); + } WidgetController::~WidgetController() { diff --git a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.h b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.h index 080b961704568478c2aa18763ab524cc89e679d3..f8f6e97d4ca04227a9aac996c5257315c132d649 100644 --- a/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.h +++ b/source/armarx/navigation/gui-plugins/LocationGraphEditor/WidgetController.h @@ -201,6 +201,7 @@ namespace armarx::navigation::qt_plugins::location_graph_editor QString getGraphDisplayName(const armem::MemoryID& entityID, bool changed = false) const; + void exportLocationGraph(); private: /// Widget Form