Skip to content
Snippets Groups Projects
Commit 76c6b268 authored by Rainer Kartmann's avatar Rainer Kartmann
Browse files

Merge branch 'armem/resolve-memory-link-in-gui' into 'armem/dev'

ArMem Viewer: Resolve Memory IDs

See merge request ArmarX/RobotAPI!170
parents 22b6db87 8e2f1f5e
No related branches found
No related tags found
3 merge requests!171Periodic merge of armem/dev into master,!170ArMem Viewer: Resolve Memory IDs,!163Draft: Resolve "Implement MemoryNameSystemClient"
Showing
with 799 additions and 48 deletions
......@@ -43,10 +43,18 @@
<Proxy include="RobotAPI/interface/units/PlatformUnitInterface.h"
humanName="Platform Unit (obstacle avoiding)"
typeName="PlatformUnitInterfacePrx"
memberName="obstacleAvoidingPlatformUnit"
getterName="getObstacleAvoidingPlatformUnit"
propertyName="ObstacleAvoidingPlatformUnitName"
memberName="platformUnit1"
getterName="getPlatformUnit1"
propertyName="PlatformUnitName1"
propertyDefaultValue="ObstacleAvoidingPlatformUnit"
propertyIsOptional="true" />
<Proxy include="RobotAPI/interface/units/PlatformUnitInterface.h"
humanName="Platform Unit (obstacle aware)"
typeName="PlatformUnitInterfacePrx"
memberName="platformUnit2"
getterName="getPlatformUnit2"
propertyName="PlatformUnitName2"
propertyDefaultValue="ObstacleAwarePlatformUnit"
propertyIsOptional="true" />
<Proxy include="RobotAPI/interface/observers/PlatformUnitObserverInterface.h"
humanName="Platform Unit Observer"
......
......@@ -18,6 +18,7 @@ pwd="$(pwd)"
# Then you have to update the symlinks (not necessary on the lab pcs)
# Update the symlinks because the default mongoc bson cmake configs are shitty
#sudo mkdir -p /usr/lib/include/
#sudo ln -s /usr/include/libbson-1.0/ /usr/lib/include/libbson-1.0
#sudo ln -s /usr/include/libbson-1.0/ /usr/lib/include/libbson-1.0
#sudo ln -s /usr/include/libmongoc-1.0/ /usr/lib/include/libmongoc-1.0
......
<?xml version="1.0" encoding="utf-8"?>
<scenario name="ArMemCore" creation="2021-06-21.11:36:43" globalConfigName="./config/global.cfg" package="RobotAPI" deploymentType="local" nodeName="NodeMain">
<application name="DebugObserver" instance="" package="ArmarXCore" nodeName="" enabled="true" iceAutoRestart="false"/>
<application name="MemoryNameSystem" instance="" package="RobotAPI" nodeName="" enabled="true" iceAutoRestart="false"/>
<application name="RemoteGuiProviderApp" instance="" package="ArmarXGui" nodeName="" enabled="true" iceAutoRestart="false"/>
</scenario>
# ==================================================================
# DebugObserver properties
# ==================================================================
# ArmarX.AdditionalPackages: List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.AdditionalPackages = Default value not mapped.
# ArmarX.ApplicationName: Application name
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.ApplicationName = ""
# ArmarX.CachePath: Path for cache files. If relative path AND env. variable ARMARX_USER_CONFIG_DIR is set, the cache path will be made relative to ARMARX_USER_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${HOME}/.armarx)
# Attributes:
# - Default: mongo/.cache
# - Case sensitivity: yes
# - Required: no
# ArmarX.CachePath = mongo/.cache
# ArmarX.Config: Comma-separated list of configuration files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.Config = ""
# ArmarX.DataPath: Semicolon-separated search list for data files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.DataPath = ""
# ArmarX.DebugObserver.CreateUpdateFrequenciesChannel: If true, an additional channel is created that shows the update frequency of every other channel in that observer.
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.DebugObserver.CreateUpdateFrequenciesChannel = false
# ArmarX.DebugObserver.DebugObserverTopicName: Name of the topic the DebugObserver listens on
# Attributes:
# - Default: DebugObserver
# - Case sensitivity: yes
# - Required: no
# ArmarX.DebugObserver.DebugObserverTopicName = DebugObserver
# ArmarX.DebugObserver.EnableProfiling: enable profiler which is used for logging performance events
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.DebugObserver.EnableProfiling = false
# ArmarX.DebugObserver.MaxHistoryRecordFrequency: The Observer history is written with this maximum frequency. Everything faster is being skipped.
# Attributes:
# - Default: 50
# - Case sensitivity: yes
# - Required: no
# ArmarX.DebugObserver.MaxHistoryRecordFrequency = 50
# ArmarX.DebugObserver.MaxHistorySize: Maximum number of entries in the Observer history
# Attributes:
# - Default: 5000
# - Case sensitivity: yes
# - Required: no
# ArmarX.DebugObserver.MaxHistorySize = 5000
# ArmarX.DebugObserver.MinimumLoggingLevel: Local logging level only for this component
# Attributes:
# - Default: Undefined
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.DebugObserver.MinimumLoggingLevel = Undefined
# ArmarX.DebugObserver.ObjectName: Name of IceGrid well-known object
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.DebugObserver.ObjectName = ""
# ArmarX.DefaultPackages: List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.DefaultPackages = Default value not mapped.
# ArmarX.DependenciesConfig: Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
# Attributes:
# - Default: ./config/dependencies.cfg
# - Case sensitivity: yes
# - Required: no
# ArmarX.DependenciesConfig = ./config/dependencies.cfg
# ArmarX.DisableLogging: Turn logging off in whole application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.DisableLogging = false
# ArmarX.EnableProfiling: Enable profiling of CPU load produced by this application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.EnableProfiling = false
# ArmarX.LoadLibraries: Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoadLibraries = ""
# ArmarX.LoggingGroup: The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoggingGroup = ""
# 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.RedirectStdout = true
# 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: 3000
# - Case sensitivity: yes
# - Required: no
# ArmarX.RemoteHandlesDeletionTimeout = 3000
# ArmarX.SecondsStartupDelay: The startup will be delayed by this number of seconds (useful for debugging)
# Attributes:
# - Default: 0
# - Case sensitivity: yes
# - Required: no
# ArmarX.SecondsStartupDelay = 0
# ArmarX.StartDebuggerOnCrash: If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.StartDebuggerOnCrash = false
# ArmarX.ThreadPoolSize: Size of the ArmarX ThreadPool that is always running.
# Attributes:
# - Default: 1
# - Case sensitivity: yes
# - Required: no
# ArmarX.ThreadPoolSize = 1
# 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: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.TopicSuffix = ""
# ArmarX.UseTimeServer: Enable using a global Timeserver (e.g. from ArmarXSimulator)
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.UseTimeServer = false
# ArmarX.Verbosity: Global logging level for whole application
# Attributes:
# - Default: Info
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.Verbosity = Info
# ==================================================================
# MemoryNameSystem properties
# ==================================================================
# ArmarX.AdditionalPackages: List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.AdditionalPackages = Default value not mapped.
# ArmarX.ApplicationName: Application name
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.ApplicationName = ""
# ArmarX.CachePath: Path for cache files. If relative path AND env. variable ARMARX_USER_CONFIG_DIR is set, the cache path will be made relative to ARMARX_USER_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${HOME}/.armarx)
# Attributes:
# - Default: mongo/.cache
# - Case sensitivity: yes
# - Required: no
# ArmarX.CachePath = mongo/.cache
# ArmarX.Config: Comma-separated list of configuration files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.Config = ""
# ArmarX.DataPath: Semicolon-separated search list for data files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.DataPath = ""
# ArmarX.DefaultPackages: List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.DefaultPackages = Default value not mapped.
# ArmarX.DependenciesConfig: Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
# Attributes:
# - Default: ./config/dependencies.cfg
# - Case sensitivity: yes
# - Required: no
# ArmarX.DependenciesConfig = ./config/dependencies.cfg
# ArmarX.DisableLogging: Turn logging off in whole application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.DisableLogging = false
# ArmarX.EnableProfiling: Enable profiling of CPU load produced by this application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.EnableProfiling = false
# ArmarX.LoadLibraries: Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoadLibraries = ""
# ArmarX.LoggingGroup: The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoggingGroup = ""
# ArmarX.MemoryNameSystem.EnableProfiling: enable profiler which is used for logging performance events
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.MemoryNameSystem.EnableProfiling = false
# ArmarX.MemoryNameSystem.MinimumLoggingLevel: Local logging level only for this component
# Attributes:
# - Default: Undefined
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.MemoryNameSystem.MinimumLoggingLevel = Undefined
# ArmarX.MemoryNameSystem.ObjectName: Name of IceGrid well-known object
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.MemoryNameSystem.ObjectName = ""
# ArmarX.MemoryNameSystem.RemoteGuiName: Name of the remote gui provider
# Attributes:
# - Default: RemoteGuiProvider
# - Case sensitivity: yes
# - Required: no
# ArmarX.MemoryNameSystem.RemoteGuiName = RemoteGuiProvider
# 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.RedirectStdout = true
# 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: 3000
# - Case sensitivity: yes
# - Required: no
# ArmarX.RemoteHandlesDeletionTimeout = 3000
# ArmarX.SecondsStartupDelay: The startup will be delayed by this number of seconds (useful for debugging)
# Attributes:
# - Default: 0
# - Case sensitivity: yes
# - Required: no
# ArmarX.SecondsStartupDelay = 0
# ArmarX.StartDebuggerOnCrash: If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.StartDebuggerOnCrash = false
# ArmarX.ThreadPoolSize: Size of the ArmarX ThreadPool that is always running.
# Attributes:
# - Default: 1
# - Case sensitivity: yes
# - Required: no
# ArmarX.ThreadPoolSize = 1
# 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: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.TopicSuffix = ""
# ArmarX.UseTimeServer: Enable using a global Timeserver (e.g. from ArmarXSimulator)
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.UseTimeServer = false
# ArmarX.Verbosity: Global logging level for whole application
# Attributes:
# - Default: Info
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.Verbosity = Info
# ==================================================================
# RemoteGuiProviderApp properties
# ==================================================================
# ArmarX.AdditionalPackages: List of additional ArmarX packages which should be in the list of default packages. If you have custom packages, which should be found by the gui or other apps, specify them here. Comma separated List.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.AdditionalPackages = Default value not mapped.
# ArmarX.ApplicationName: Application name
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.ApplicationName = ""
# ArmarX.CachePath: Path for cache files. If relative path AND env. variable ARMARX_USER_CONFIG_DIR is set, the cache path will be made relative to ARMARX_USER_CONFIG_DIR. Otherwise if relative it will be relative to the default ArmarX config dir (${HOME}/.armarx)
# Attributes:
# - Default: mongo/.cache
# - Case sensitivity: yes
# - Required: no
# ArmarX.CachePath = mongo/.cache
# ArmarX.Config: Comma-separated list of configuration files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.Config = ""
# ArmarX.DataPath: Semicolon-separated search list for data files
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.DataPath = ""
# ArmarX.DefaultPackages: List of ArmarX packages which are accessible by default. Comma separated List. If you want to add your own packages and use all default ArmarX packages, use the property 'AdditionalPackages'.
# Attributes:
# - Default: Default value not mapped.
# - Case sensitivity: yes
# - Required: no
# ArmarX.DefaultPackages = Default value not mapped.
# ArmarX.DependenciesConfig: Path to the (usually generated) config file containing all data paths of all dependent projects. This property usually does not need to be edited.
# Attributes:
# - Default: ./config/dependencies.cfg
# - Case sensitivity: yes
# - Required: no
# ArmarX.DependenciesConfig = ./config/dependencies.cfg
# ArmarX.DisableLogging: Turn logging off in whole application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.DisableLogging = false
# ArmarX.EnableProfiling: Enable profiling of CPU load produced by this application
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.EnableProfiling = false
# ArmarX.LoadLibraries: Libraries to load at start up of the application. Must be enabled by the Application with enableLibLoading(). Format: PackageName:LibraryName;... or /absolute/path/to/library;...
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoadLibraries = ""
# ArmarX.LoggingGroup: The logging group is transmitted with every ArmarX log message over Ice in order to group the message in the GUI.
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.LoggingGroup = ""
# 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.RedirectStdout = true
# ArmarX.RemoteGuiProvider.EnableProfiling: enable profiler which is used for logging performance events
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.RemoteGuiProvider.EnableProfiling = false
# ArmarX.RemoteGuiProvider.MinimumLoggingLevel: Local logging level only for this component
# Attributes:
# - Default: Undefined
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.RemoteGuiProvider.MinimumLoggingLevel = Undefined
# ArmarX.RemoteGuiProvider.ObjectName: Name of IceGrid well-known object
# Attributes:
# - Default: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.RemoteGuiProvider.ObjectName = ""
# ArmarX.RemoteGuiProvider.TopicName: Name of the topic on which updates to the remote state are reported.
# Attributes:
# - Default: RemoteGuiTopic
# - Case sensitivity: yes
# - Required: no
# ArmarX.RemoteGuiProvider.TopicName = RemoteGuiTopic
# 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: 3000
# - Case sensitivity: yes
# - Required: no
# ArmarX.RemoteHandlesDeletionTimeout = 3000
# ArmarX.SecondsStartupDelay: The startup will be delayed by this number of seconds (useful for debugging)
# Attributes:
# - Default: 0
# - Case sensitivity: yes
# - Required: no
# ArmarX.SecondsStartupDelay = 0
# ArmarX.StartDebuggerOnCrash: If this application crashes (segmentation fault) qtcreator will attach to this process and start the debugger.
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.StartDebuggerOnCrash = false
# ArmarX.ThreadPoolSize: Size of the ArmarX ThreadPool that is always running.
# Attributes:
# - Default: 1
# - Case sensitivity: yes
# - Required: no
# ArmarX.ThreadPoolSize = 1
# 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: ""
# - Case sensitivity: yes
# - Required: no
# ArmarX.TopicSuffix = ""
# ArmarX.UseTimeServer: Enable using a global Timeserver (e.g. from ArmarXSimulator)
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.UseTimeServer = false
# ArmarX.Verbosity: Global logging level for whole application
# Attributes:
# - Default: Info
# - Case sensitivity: yes
# - Required: no
# - Possible values: {Debug, Error, Fatal, Important, Info, Undefined, Verbose, Warning}
# ArmarX.Verbosity = Info
# ==================================================================
# Global Config from Scenario ArMemCore
# ==================================================================
......@@ -118,12 +118,12 @@ ArmarX.ArMemExampleClient.tpc.sub.MemoryListener = MemoryUpdates
# ArmarX.ExampleMemoryClient.RemoteGuiName = RemoteGuiProvider
# ArmarX.ExampleMemoryClient.mem.MemoryName: Name of the memory to use.
# ArmarX.ExampleMemoryClient.mem.UsedMemoryName: Name of the memory to use.
# Attributes:
# - Default: Example
# - Case sensitivity: yes
# - Required: no
# ArmarX.ExampleMemoryClient.mem.MemoryName = Example
# ArmarX.ExampleMemoryClient.mem.UsedMemoryName = Example
# ArmarX.ExampleMemoryClient.mns.MemoryNameSystemEnabled: Whether to use (and depend on) the Memory Name System (MNS).
......
......@@ -135,6 +135,15 @@
# ArmarX.ObjectPoseProviderExample.Objects = KIT/Amicelli, KIT/YellowSaltCylinder
# ArmarX.ObjectPoseProviderExample.SingleShot: If true, publishes only one snapshot.
# Attributes:
# - Default: false
# - Case sensitivity: yes
# - Required: no
# - Possible values: {0, 1, false, no, true, yes}
# ArmarX.ObjectPoseProviderExample.SingleShot = false
# ArmarX.ObjectPoseProviderExample.tpc.pub.DebugObserver: Name of the `DebugObserver` topic to publish data to.
# Attributes:
# - Default: DebugObserver
......
......@@ -169,7 +169,7 @@ namespace armarx
viz::data::LayerUpdates armarx::ArVizStorage::pullUpdatesSince(Ice::Long revision, const Ice::Current&)
viz::data::LayerUpdates ArVizStorage::pullUpdatesSince(Ice::Long revision, const Ice::Current&)
{
viz::data::LayerUpdates result;
......
#include "Path.h"
#include <iterator>
#include <ArmarXCore/interface/core/BasicVectorTypes.h>
#include <ArmarXCore/interface/core/BasicVectorTypesHelpers.h>
namespace armarx::viz
{
Path& Path::clear()
{
data_->points.clear();
return *this;
}
Path& Path::lineColor(Color color)
{
data_->lineColor = color;
return *this;
}
Path& Path::lineColorGlasbeyLUT(std::size_t id, int alpha)
{
return lineColor(Color::fromRGBA(simox::color::GlasbeyLUT::at(id, alpha)));
}
Path& Path::lineWidth(float w)
Path& Path::width(float w)
{
data_->lineWidth = w;
......@@ -33,17 +27,21 @@ namespace armarx::viz
auto& points = data_->points;
points.clear();
points.reserve(ps.size());
for (auto& p : ps)
std::transform(ps.begin(),
ps.end(),
std::back_inserter(points),
[](const auto & e)
{
points.push_back(armarx::Vector3f{p.x(), p.y(), p.z()});
}
return ToBasicVectorType(e);
});
return *this;
}
Path& Path::addPoint(Eigen::Vector3f p)
{
data_->points.push_back(armarx::Vector3f{p.x(), p.y(), p.z()});
data_->points.emplace_back(ToBasicVectorType(p));
return *this;
}
......
......@@ -35,17 +35,7 @@ namespace armarx::viz
Path& clear();
Path& lineColor(Color color);
template<class...Ts>
Path& lineColor(Ts&& ...ts)
{
return lineColor({std::forward<Ts>(ts)...});
}
Path& lineColorGlasbeyLUT(std::size_t id, int alpha = 255);
Path& lineWidth(float w);
Path& width(float w);
Path& points(std::vector<Eigen::Vector3f> const& ps);
......
#include "VisualizationPath.h"
#include <algorithm>
#include <Inventor/SbVec3f.h>
#include <Inventor/nodes/SoCoordinate3.h>
#include <Inventor/nodes/SoDrawStyle.h>
#include <Inventor/nodes/SoLineSet.h>
#include <Inventor/nodes/SoPointSet.h>
namespace armarx::viz::coin
{
......@@ -27,19 +30,36 @@ namespace armarx::viz::coin
node->addChild(coordinate3);
node->addChild(lineSep);
// points (use the following, if the points should be drawn in a different color)
// pclMat = new SoMaterial;
// SoMaterialBinding* pclMatBind = new SoMaterialBinding;
// pclMatBind->value = SoMaterialBinding::PER_PART;
pclCoords = new SoCoordinate3;
pclStyle = new SoDrawStyle;
// node->addChild(pclMat);
// node->addChild(pclMatBind);
node->addChild(pclCoords);
node->addChild(pclStyle);
node->addChild(new SoPointSet);
}
bool VisualizationPath::update(ElementType const& element)
{
// set position
coordinate3->point.setValuesPointer(element.points.size(), reinterpret_cast<const float*>(element.points.data()));
coordinate3->point.setValuesPointer(element.points.size(),
reinterpret_cast<const float*>(element.points.data()));
// set color
const auto lineColor = element.lineColor;
const auto lineColor = element.color;
constexpr float toUnit = 1.0F / 255.0F;
const auto color = SbVec3f(lineColor.r, lineColor.g, lineColor.b) * toUnit;
const auto color = SbVec3f(lineColor.r, lineColor.g, lineColor.b) * toUnit;
const float transparency = 1.0F - static_cast<float>(lineColor.a) * toUnit;
lineMaterial->diffuseColor.setValue(color);
......@@ -58,6 +78,20 @@ namespace armarx::viz::coin
const int pointSize = static_cast<int>(element.points.size());
lineSet->numVertices.set1Value(0, pointSize);
// points at each node
// const std::vector<SbVec3f> colorData(element.points.size(), color);
// pclMat->diffuseColor.setValuesPointer(colorData.size(),
// reinterpret_cast<const float*>(colorData.data()));
// pclMat->ambientColor.setValuesPointer(colorData.size(),
// reinterpret_cast<const float*>(colorData.data()));
// pclMat->transparency = transparency;
pclCoords->point.setValuesPointer(element.points.size(),
reinterpret_cast<const float*>(element.points.data()));
pclStyle->pointSize = element.lineWidth + 5;
return true;
}
} // namespace armarx::viz::coin
\ No newline at end of file
......@@ -39,9 +39,17 @@ namespace armarx::viz::coin
bool update(ElementType const& element);
/// lines
SoCoordinate3* coordinate3;
SoDrawStyle* lineStyle;
SoLineSet* lineSet;
SoMaterial* lineMaterial;
/// points
// SoMaterial* pclMat;
SoCoordinate3* pclCoords;
SoDrawStyle* pclStyle;
};
} // namespace armarx::viz::coin
......@@ -29,6 +29,8 @@
#include <IceUtil/Time.h>
#include <SimoxUtility/math/pose/pose.h>
#include <VirtualRobot/Robot.h>
#include <VirtualRobot/XML/RobotIO.h>
#include <VirtualRobot/VirtualRobot.h>
......@@ -50,8 +52,10 @@
namespace armarx::articulated_object
{
ArticulatedObjectLocalizerExample::ArticulatedObjectLocalizerExample() :
articulatedObjectWriter(new ::armarx::armem::articulated_object::Writer(*this)),
articulatedObjectReader(new ::armarx::armem::articulated_object::Reader(*this)) {}
articulatedObjectWriter(new ::armarx::armem::articulated_object::Writer(memoryNameSystem)),
articulatedObjectReader(new ::armarx::armem::articulated_object::Reader(memoryNameSystem))
{
}
armarx::PropertyDefinitionsPtr ArticulatedObjectLocalizerExample::createPropertyDefinitions()
{
......@@ -62,6 +66,7 @@ namespace armarx::articulated_object
defs->optional(p.updateFrequency, "updateFrequency", "Memory update frequency (write).");
// Reader will override some properties of writer.
articulatedObjectWriter->registerPropertyDefinitions(defs);
articulatedObjectReader->registerPropertyDefinitions(defs);
......@@ -73,7 +78,11 @@ namespace armarx::articulated_object
return "ArticulatedObjectLocalizerExample";
}
void ArticulatedObjectLocalizerExample::onInitComponent() {}
void ArticulatedObjectLocalizerExample::onInitComponent()
{
// Reader overwrote property registered property of articulatedObjectWriter.
articulatedObjectWriter->setProviderName(articulatedObjectReader->getProviderName());
}
void ArticulatedObjectLocalizerExample::onConnectComponent()
{
......@@ -83,7 +92,7 @@ namespace armarx::articulated_object
ARMARX_IMPORTANT << "Running example.";
start = armem::Time::now();
task = new PeriodicTask<ArticulatedObjectLocalizerExample>(this, &ArticulatedObjectLocalizerExample::run, 1000 / p.updateFrequency);
task = new PeriodicTask<ArticulatedObjectLocalizerExample>(this, &ArticulatedObjectLocalizerExample::run, 1000.f / p.updateFrequency);
task->start();
}
......@@ -152,7 +161,7 @@ namespace armarx::articulated_object
ARMARX_DEBUG << "Reporting articulated objects";
const IceUtil::Time now = TimeUtil::GetTime();
const float t = float((now - start).toSecondsDouble());
const float t = float((now - start).toSecondsDouble());
// move joints at certain frequency
const float k = (1 + std::sin(t / (M_2_PIf32))) / 2; // in [0,1]
......@@ -163,9 +172,11 @@ namespace armarx::articulated_object
{"drawer_joint", 350 * k}
};
dishwasher->setGlobalPose(simox::math::pose(Eigen::Vector3f(1000, 0, 0)));
dishwasher->setJointValues(jointValues);
armarx::armem::articulated_object::ArticulatedObject armemDishwasher = convert(*dishwasher, IceUtil::Time::now());
armarx::armem::articulated_object::ArticulatedObject armemDishwasher =
convert(*dishwasher, IceUtil::Time::now());
articulatedObjectWriter->store(armemDishwasher);
}
......
......@@ -22,6 +22,8 @@
#include "DynamicObstacleManager.h"
#include <VirtualRobot/MathTools.h>
// STD/STL
#include <string>
#include <vector>
......@@ -118,6 +120,7 @@ namespace armarx
void DynamicObstacleManager::add_decayable_line_segment(const Eigen::Vector2f& line_start, const Eigen::Vector2f& line_end, const Ice::Current&)
{
TIMING_START(add_decayable_line_segment);
const Eigen::Vector2f difference_vec = line_end - line_start;
const float length = difference_vec.norm();
const Eigen::Vector2f center_vec = line_start + 0.5 * difference_vec;
......@@ -136,10 +139,10 @@ namespace armarx
return;
}
{
std::shared_lock<std::shared_mutex> l(m_managed_obstacles_mutex);
TIMING_START(add_decayable_line_segment_mutex);
// First check own obstacles
for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
{
......@@ -155,13 +158,15 @@ namespace armarx
managed_obstacle->line_matches.push_back(line_start);
managed_obstacle->line_matches.push_back(line_end);
managed_obstacle->m_last_matched = IceUtil::Time::now();
TIMING_END(add_decayable_line_segment_mutex);
return;
}
}
TIMING_END(add_decayable_line_segment_mutex);
}
// Second check the obstacles from the obstacle avoidance
for (const auto& published_obstacle : m_obstacle_detection->getObstacles())
/*for (const auto& published_obstacle : m_obstacle_detection->getObstacles())
{
float coverage = ManagedObstacle::line_segment_ellipsis_coverage(
{published_obstacle.posX, published_obstacle.posY}, published_obstacle.axisLengthX, published_obstacle.axisLengthY, published_obstacle.yaw,
......@@ -172,7 +177,7 @@ namespace armarx
ARMARX_DEBUG << "Found the obstacle in the static obstacle list! Matching name: " << published_obstacle.name;
return;
}
}
}*/
ARMARX_DEBUG << " No matching obstacle found. Create new obstacle and add to list";
ManagedObstaclePtr new_managed_obstacle(new ManagedObstacle());
......@@ -198,6 +203,15 @@ namespace armarx
std::lock_guard<std::shared_mutex> l(m_managed_obstacles_mutex);
m_managed_obstacles.push_back(new_managed_obstacle);
}
TIMING_END(add_decayable_line_segment);
}
void DynamicObstacleManager::add_decayable_line_segments(const dynamicobstaclemanager::LineSegments& lines, const Ice::Current& c)
{
for (const auto& line : lines)
{
add_decayable_line_segment(line.lineStart, line.lineEnd, c);
}
}
......@@ -218,7 +232,7 @@ namespace armarx
std::lock_guard l(m_managed_obstacles_mutex);
ARMARX_DEBUG << "Remove Obstacle " << name << " from obstacle map and from obstacledetection";
for (ManagedObstaclePtr& managed_obstacle : m_managed_obstacles)
for (ManagedObstaclePtr managed_obstacle : m_managed_obstacles)
{
if (managed_obstacle->m_obstacle.name == name)
{
......@@ -240,6 +254,36 @@ namespace armarx
}
float
DynamicObstacleManager::distanceToObstacle(const Eigen::Vector2f& agentPosition, float safetyRadius, const Eigen::Vector2f& goal, const Ice::Current&)
{
std::shared_lock<std::shared_mutex> l{m_managed_obstacles_mutex};
const float sample_step = 5; // in [mm], sample step size towards goal.
const float distance_to_goal = (goal - agentPosition).norm() + safetyRadius;
float current_distance = safetyRadius;
while (current_distance < distance_to_goal)
{
for (const auto man_obstacle : m_managed_obstacles)
{
Eigen::Vector2f sample = agentPosition + ((goal - agentPosition).normalized() * current_distance);
obstacledetection::Obstacle obstacle = man_obstacle->m_obstacle;
Eigen::Vector2f obstacle_origin{obstacle.posX, obstacle.posY};
if (ManagedObstacle::point_ellipsis_coverage(obstacle_origin, obstacle.axisLengthX, obstacle.axisLengthY, obstacle.yaw, sample))
{
return current_distance - safetyRadius;
}
}
current_distance += sample_step;
}
return std::numeric_limits<float>::infinity();
}
void DynamicObstacleManager::directly_update_obstacle(const std::string& name, const Eigen::Vector2f& obs_pos, float e_rx, float e_ry, float e_yaw, const Ice::Current&)
{
obstacledetection::Obstacle new_unmanaged_obstacle;
......@@ -283,7 +327,6 @@ namespace armarx
}
}
// Update obstacle avoidance
int checked_obstacles = 0;
bool updated = false;
......
......@@ -69,10 +69,12 @@ namespace armarx
void add_decayable_obstacle(const Eigen::Vector2f&, float, float, float, const Ice::Current& = Ice::Current()) override;
void add_decayable_line_segment(const Eigen::Vector2f&, const Eigen::Vector2f&, const Ice::Current& = Ice::Current()) override;
void add_decayable_line_segments(const dynamicobstaclemanager::LineSegments& lines, const Ice::Current& = Ice::Current()) override;
void remove_all_decayable_obstacles(const Ice::Current& = Ice::Current()) override;
void directly_update_obstacle(const std::string& name, const Eigen::Vector2f&, float, float, float, const Ice::Current& = Ice::Current()) override;
void remove_obstacle(const std::string& name, const Ice::Current& = Ice::Current()) override;
void wait_unitl_obstacles_are_ready(const Ice::Current& = Ice::Current()) override;
float distanceToObstacle(const Eigen::Vector2f& agentPosition, float safetyRadius, const Eigen::Vector2f& goal, const Ice::Current& = Ice::Current()) override;
protected:
void onInitComponent() override;
......
......@@ -94,10 +94,25 @@ namespace armarx
float ManagedObstacle::line_segment_ellipsis_coverage(const Eigen::Vector2f e_origin, const float e_rx, const float e_ry, const float e_yaw, const Eigen::Vector2f line_seg_start, const Eigen::Vector2f line_seg_end)
{
// Again we discretize the line into n points and we check the coverage of those points
const unsigned int SAMPLES = 40;
const Eigen::Vector2f difference_vec = line_seg_end - line_seg_start;
const Eigen::Vector2f difference_vec_normed = difference_vec.normalized();
const float distance = difference_vec.norm();
const unsigned int SAMPLES = std::max(distance / 10.0, 40.0);
const Vector2f difference_start_origin = e_origin - line_seg_start;
const Vector2f difference_end_origin = e_origin - line_seg_end;
if (difference_start_origin.norm() > std::max(e_rx, e_ry) && distance < std::max(e_rx, e_ry))
{
return 0.0;
}
if (difference_end_origin.norm() > std::max(e_rx, e_ry) && distance < std::max(e_rx, e_ry))
{
return 0.0;
}
const float step_size = distance / SAMPLES;
const Eigen::Vector2f dir = difference_vec_normed * step_size;
......
......@@ -4,6 +4,7 @@ find_package(Qt5 COMPONENTS Core Bluetooth QUIET)
armarx_build_if(Qt5_FOUND "Qt5 Core or Bluetooth not available")
set(COMPONENT_LIBS
RemoteGui
RobotAPIUnits
KITProstheticHandDriver
)
......
......@@ -42,6 +42,8 @@ namespace armarx
defs->optional(initialObjectIDs, "Objects", "Object IDs of objects to be tracked.")
.map(simox::alg::join(initialObjectIDs, ", "), initialObjectIDs);
defs->optional(singleShot, "SingleShot", "If true, publishes only one snapshot.");
return defs;
}
......@@ -172,6 +174,11 @@ namespace armarx
ARMARX_VERBOSE << "Reporting " << poses.size() << " object poses";
objectPoseTopic->reportObjectPoses(getName(), poses);
if (singleShot)
{
break;
}
cycle.waitForCycleDuration();
}
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment