void enableProfiler (bool enable)
setProfiler allows setting ManagedIceObject::profiler to a new instance (if the new instance is actually not a null pointer) More...
std::string generateSubObjectName (const std::string &subObjectName)
Generates a unique name for a sub object from a general name. More...
ArmarXManagerPtr getArmarXManager () const
Returns the ArmarX manager used to add and remove components. More...
ManagedIceObjectConnectivity getConnectivity () const
Retrieve connectivity of the object (topcis as well as proxies) More...
virtual std::string getDefaultName () const =0
Retrieve default name of component. More...
IceManagerPtr getIceManager () const
Returns the IceManager . More...
VariantBasePtr getMetaInfo (const std::string &id)
StringVariantBaseMap getMetaInfoMap () const
std::string getName () const
Retrieve name of object. More...
Ice::ObjectAdapterPtr getObjectAdapter () const
Returns object's Ice adapter. More...
ArmarXObjectSchedulerPtr getObjectScheduler () const
PeriodicTaskPtr getPeriodicTask (const std::string &name)
Profiler::ProfilerPtr getProfiler () const
getProfiler returns an instance of armarx::Profiler More...
template<class ProxyTarg , class... Args>
void getProxy (const char *name, IceInternal::ProxyHandle < ProxyTarg > &proxy, Args &&...args)
template<class ProxyType >
ProxyType getProxy (const std::string &name, bool addToDependencies=false, const std::string &endpoints="", bool throwOnProxyError=true)
Retrieves a proxy object. More...
template<class ProxyTarg , class... Args>
void getProxy (const std::string &name, IceInternal::ProxyHandle < ProxyTarg > &proxy, Args &&...args)
template<class ProxyTarg , class... Args>
void getProxy (IceInternal::ProxyHandle < ProxyTarg > &proxy, const char *name, Args &&...args)
template<class ProxyTarg , class... Args>
void getProxy (IceInternal::ProxyHandle < ProxyTarg > &proxy, const std::string &name, Args &&...args)
Assigns a proxy to proxy
. More...
Ice::ObjectPrx getProxy (long timeoutMs=0, bool waitForScheduler=true) const
Returns the proxy of this object (optionally it waits for the proxy) More...
template<class Prx >
Prx getProxy (long timeoutMs=0, bool waitForScheduler=true) const
template<class ProxyType >
void getProxy (ProxyType &proxy, const char *name, bool addToDependencies=false, const std::string &endpoints="", bool throwOnProxyError=true)
Overload to allow using string literals as name (solve ambiguous overload). More...
template<class Prx >
void getProxy (Prx &prx, long timeoutMs=0, bool waitForScheduler=true) const
int getState () const
Retrieve current state of the ManagedIceObject . More...
template<class TopicProxyType >
TopicProxyType getTopic (const std::string &name)
Returns a proxy of the specified topic. More...
template<class TopicProxyType >
void getTopic (TopicProxyType &topicProxy, const std::string &name)
Assigns a proxy of the specified topic to topicProxy
. More...
std::vector< std::string > getUnresolvedDependencies () const
returns the names of all unresolved dependencies More...
ManagedIceObject (ManagedIceObject const &other)
void offeringTopic (const std::string &name)
Registers a topic for retrival after initialization. More...
void preambleGetTopic (std::string const &name)
void setMetaInfo (const std::string &id, const VariantBasePtr &value)
Allows to set meta information that can be queried live via Ice interface on the ArmarXManager . More...
void startPeriodicTask (const std::string &uniqueName, std::function< void(void)> f, int periodMs, bool assureMeanInterval=false, bool forceSystemTime=true)
bool stopPeriodicTask (const std::string &name)
bool unsubscribeFromTopic (const std::string &name)
Unsubscribe from a topic. More...
bool usingProxy (const std::string &name, const std::string &endpoints="")
Registers a proxy for retrieval after initialization and adds it to the dependency list. More...
void usingTopic (const std::string &name, bool orderedPublishing=false)
Registers a proxy for subscription after initialization. More...
void waitForObjectScheduler ()
Waits until the ObjectScheduler could resolve all dependencies. More...
void waitForProxy (std::string const &name, bool addToDependencies)
SpamFilterDataPtr deactivateSpam (float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds. More...
MessageTypeT getEffectiveLoggingLevel () const
Logging ()
void setLocalMinimumLoggingLevel (MessageTypeT level)
With setLocalMinimumLoggingLevel the minimum verbosity-level of log-messages can be set. More...
void setTag (const LogTag &tag )
void setTag (const std::string &tagName)
virtual ~Logging ()
template<class PluginT , class... ParamsT>
PluginT * addPlugin (const std::string prefix="", ParamsT &&...params)
template<class PluginT , class... ParamsT>
void addPlugin (PluginT *&targ, const std::string prefix="", ParamsT &&...params)
template<class PluginT , class... ParamsT>
void addPlugin (std::experimental::observer_ptr < PluginT > &targ, const std::string prefix="", ParamsT &&...params)
Ice::CommunicatorPtr getCommunicator () const
std::unique_ptr< ManagedIceObjectPlugin > & getPluginPointer (std::type_info const &type, std::string const &prefix)
ManagedIceObject ()
Protected default constructor. More...
virtual void onConnectComponent ()=0
Pure virtual hook for the subclass. More...
virtual void onDisconnectComponent ()
Hook for subclass. More...
virtual void onExitComponent ()
Hook for subclass. More...
virtual void onInitComponent ()=0
Pure virtual hook for the subclass. More...
virtual void postOnConnectComponent ()
virtual void postOnDisconnectComponent ()
virtual void postOnExitComponent ()
virtual void postOnInitComponent ()
virtual void preOnConnectComponent ()
virtual void preOnDisconnectComponent ()
virtual void preOnExitComponent ()
virtual void preOnInitComponent ()
bool removeProxyDependency (const std::string &name)
This function removes the dependency of this object on the in parameter name specified object. More...
void setName (std::string name)
Override name of well-known object. More...
void terminate ()
Initiates termination of this IceManagedObject. More...
~ManagedIceObject () override
bool checkLogLevel (MessageTypeT level) const
const LogSenderPtr & getLogSender () const
Retrieve log sender. More...
LogSenderPtr loghelper (const char *file, int line, const char *function) const
The ManagedIceObject is the base class for all ArmarX objects.
ManagedIceObject are the ArmarX equivalent to well-known Ice objects. A defined lifecycle is guaranteed which and state dependent interface is provided by the following framework hooks:
ManagedIceObjects::onInitComponent()
ManagedIceObjects::onConnectComponent()
ManagedIceObjects::onExitComponent()
Lifecyle of a ManagedIceObject managed by the ArmarXObjectScheduler
Every subclass of ManagedIceObject can specify dependent proxies and topics as well as offered topics in ManagedIceObjects::onInitComponent(). These connectivity parameters are specified through the following methods:
MangedIceObject::usingProxy()
MangedIceObject::usingTopic()
MangedIceObject::offeringTopic()
These dependencies are resolved at runtime and can be visualized. Additionally it is possible to handle the case of crashed dependencies.
MyManagedIceObject::onInitComponent()
{
}
See also ArmarXObjectScheduler
Definition at line 163 of file ManagedIceObject.h .
virtual std::string getDefaultName
(
)
const
pure virtual
Retrieve default name of component.
Implement this method in each IceManagedObject. The default name of a is used if no name is specified in the factory method.
Returns default name of the component (e.g. "KinematicUnit")
Implemented in NJointControllerBase , ArVizInteractExample , ResultImageProvider , ModuleBase , EmergencyStopNode< T > , SimpleConfigDialog , IEEE1394ImageProvider , EmergencyStopMaster , RemoteStateOfferer< ContextType > , WorkingMemoryController , TrajectoryControllerSubUnit , PrimitiveExtractor , KBMComponent , DenseCRFSegmentationProcessor , RobotUnitSimulation , LaserScannerSelfLocalisation , TCPControlUnit , OpenPoseEstimation , WorkerNode , ManagerNode , SceneModifier , ResultPointCloudProvider , CoFusionProcessor , ObstacleAvoidingPlatformUnit , SegmentableTemplateRecognition , Simulator , HapticObserver , ObstacleAwarePlatformUnit , ConditionHandler , RemoteGuiExample2 , PointCloudSegmenter , RobotIK , XMLStateComponent , KinematicUnitSimulation , CalibrationCreator2 , ArmarXSimulatorWindow , DMPComponent , PointCloudObjectLocalizer , TabletopSegmentation , TopicRecorderComponent , DebugDrawerComponent , ReflexCombination , OpenNIPointCloudProvider , Component , MaskRCNNPointCloudObjectLocalizer , LaserScannerSimulation , RTABMapRegistration , ObjectLearningByPushing , GraspingManager , ViewSelection , HokuyoLaserUnit , RGBDHandLocalizer , FrameTracking , MotionPlanningServer , RemoteObjectNode , RemoteState , ObjectMemoryObserver , CollisionCheckerComponent , AffordanceExtraction , VisualContactDetection , BigBowlLocalization , AzureKinectPointCloudProvider , CropRobotFromImage , IntelRealSenseProvider , SegmentableObjectRecognition , KinectV2PointCloudProvider , OpticalFlow , TrajectoryPlayer , ObjectLocalizationMemoryUpdater , ImageToPointCloud , ObjectLocalizationSaliency , ImageSourceSelection , MultiSensePointCloudProvider , ResultImageFuser , VoxelGridMappingProvider , ThreadList , PointCloudVisualization , AffordancePipelineVisualization , StereoCameraProvider , BlobRecognition , XMLSceneImporter , StreamProviderI , MMMSimulation , Component , SystemObserver , ValveAttention , KLGImageProvider , TexturedObjectRecognition , FlyCaptureImageProvider , ImageSequenceProvider , TCPControllerSubUnit , ImageProviderDynamicSimulation , ATINetFTUnit , SimpleRobotPlacement , NaturalIKTest , MaskFilterPointCloudProcessor , CoupledInteractionGroupStatechartContext , KinectAndCameraCalibration , PrimitiveVisualization , OptoForceUnit , StatechartEventDistributor , KinematicUnitObserver , ColorMarkerObjectLocalizer , RCPointCloudProvider , RobotHandLocalizationDynamicSimulation , FunctionApproximator , PlatformUnitObserver , EntityDrawerComponent , TrackingError , PointCloudFilter , PointCloudRecorder , SimpleStatechartExecutor , HumanObstacleDetection , RCImageProvider , MotionPlanningServerConfigDialog , ExternalApplicationManager , RobotStateComponent , CalibrationCreator , PointCloudToArViz , KinematicSelfLocalization , LaserScannerFeatureExtraction , BlurrinessMetric , RobotHandLocalizationWithFingertips , UCLObjectRecognition , KinectV1PointCloudProvider , PointCloudUtility , ObjectLocalizerDynamicSimulation , HandMarkerLocalization , StereoImagePointCloudProvider , KinematicUnit , Component , LaserScannerPointCloudProvider , RobotPoseUnitDynamicSimulation , BringObjectGroupStatechartContext , DHParameterOptimizationLogger , SimpleGraspGenerator , ArVizExample , GamepadControlUnit , SimoxSceneImporter , OpenCVImageStabilizer , StreamDecoderImageProvider , MMMPlayer , GamepadUnit , RobotStateObserver , CommonStorage , DummyObjectLocalizer , AbstractWorkingMemory , FakePointCloudProvider , OrientedTactileSensorUnit , XsensIMU , WorkingMemory , SceneEditorConfigDialog , AzureKinectIRImageProvider , ArmarXPhysicsWorldVisualization , AStarPathPlannerTestComponent , WorkerNode , ArMarkerLocalizerOpenCV , SemanticRelationAnalyzer , ForceTorqueObserver , ForceTorqueUnit , HandUnit , DeepFaceRecognition , LabeledPointCloudMerger , SegmentRansacShapeExtractor , HandUnitDynamicSimulation , DebugObserver , ObjectMemory , HeadIKUnit , PlatformUnit , PrimitiveExtractionParameterTuning , LocalTimeServer , RobotPoseUnit , CommonPlacesTester , DummyAgentReporter , WorkingMemoryObjectPoseProvider , OLPEvaluation , PlaybackImageProvider , FaceRecognition , EfficientRANSACPrimitiveExtractor , ShapesSupportRelations , RobotStateMemory , RobotHealthDummy , WorkingMemoryToArViz , PriorKnowledgeImporter , IMUSimulation , Component , PythonApplicationManager , DSObstacleAvoidance , CyberGloveObserver , KITProstheticHandUnit , RobotToArViz , OpenPoseSimulation , SimpleEpisodicMemoryImageConnector , MultiViewPointCloudProcessor , SegmentAABBShapesProvider , SegmentSpatialRelations , ForceTorqueUnitDynamicSimulation , KinematicUnitDynamicSimulation , Component , Component , RobotStatechartContext , LongtermMemory , DummyArMarkerLocalizer , ArMarkerLocalizer , MultiImageProvider , MotionControlGroupStatechartContext , PlannedMotionProvider , DynamicRemoteState , EmergencyStopWidget , RemoteGuiProvider , TopicTimingClient , InertialMeasurementUnitObserver , Component , UserAssistedSegmenter , FakeWorkingMemoryObjectLocalizer , PlatformContext , Component , DebugDrawerToArVizComponent , DummyTextToSpeech , RobotHealth , ForceTorqueUnitSimulation , GamepadUnitObserver , OptoForceUnitObserver , MetaWearIMU , GraphNodePoseResolver , ArMarkerExternalCameraCalibration , WebCamImageProvider , HandGroupStatechartContext , StaticAgentReporter , RTUnit , ArmarXTimeserver , PingLoadTest , BatteryWidget , SkillsMemory , DynamicObstacleManager , StatechartExecutorExample , HapticUnit , OrientedTactileSensorUnitObserver , SelfLocalizationDynamicSimulation , SimulatorToArviz , Component , KITHandUnit , LaserScannerUnitObserver , DummyWorldStateObserver , PriorEditorConfigDialog , SemanticGraphStorage , ArticulatedObjectLocalizerDynamicSimulation , Component , StateWatcher , TopicTimingServer , SpeechObserver , FilterKnownObjects , PointCloudToArMem , GraspingManagerTest , Component , KITProstheticHandObserver , SkillProviderExample , GraspCandidateObserver , TCPControlUnitObserver , WorkingMemoryExample , PriorKnowledge , AffordanceUpdateListener , DepthImageProviderDynamicSimulation , LaserScannerObstacleDetection , ObjectInstanceToIndex , ArVizStorage , MultiHandUnit , InertialMeasurementUnit , CommonPlacesLearner , ProfilerStorage , SemanticGraphExample , Component , TopicReplayer , ExampleMemoryClient , ObjectPoseProviderExample , WorldStateObserver , Component , ObjectPoseClientExample , HandUnitSimulation , MetaWearIMUObserver , AStarPathPlanner , Component , GraspablePredicateProvider , PlatformUnitConfigDialog , Component , MemoryGrapher , SimulatorTimeServerProxy , Component , ArmarXFileLogger , SimpleEpisodicMemorySemanticGraphConnector , PlatformUnitDynamicSimulation , Component , VirtualRobotReaderExampleClient , LaserScansMemory , RobotDefinition , PutAwayLocationPredicateProvider , HumanMemory , ExampleMemory , GeneralPurposeMemory , MotionMemory , ik_demo , RobotNameService , AgentAtPredicateProvider , ObjectAtPredicateProvider , ImageToArMem , ArMemToImageProvider , Component , GraspSelectionManager , Component , Component , MemoryNameSystem , ArmarXObjectsImporter , AbstractLongtermMemory , HandControlSkillProvider , PlatformControlSkillProvider , ProfilerObserver , SubjectMemory , HandPredicateProvider , VisionMemory , VideoFileImageProvider , JointControlSkillProvider , TCPControlSkillProvider , VisualSearchSkillProvider , VisualServoTCPControlSkillProvider , IndexMemory , SimpleEpisodicMemoryOpenPoseEstimationConnector , PersonMemoryDebugger , LegacyRobotStateMemoryAdapter , HandUnitConfigDialog , KinematicUnitConfigDialog , TCPMoverConfigDialog , AffordancePipelineGuiConfigDialog , PointCloudVisualizationConfigDialog , PrimitiveExtractionConfigDialog , DummyCriterion , NaturalGraspFilter , PlatformUnitSimulation , GraspControlSkillProvider , MMMPlayerConfigDialog , ExternalApplicationManagerStarter , LocalizationUnit , SimpleEpisodicMemory , SimpleEpisodicMemoryWorkingMemoryConnector , StatechartPerformanceTest , ArmarXComponentWidgetController , Component , BringObjectSkillProvider , SimpleEpisodicMemoryPlatformUnitConnector , ArticulatedObjectLocalizerExample , RGBDPoseEstimationWithMemoryWriter , SimulationObjectPoseProvider , ExternalApplicationManagerDependency , VirtualRobotWriterExample , SystemStateMemory , AronComponentConfigExample , OnTopPredicateProvider , PersonInstanceUpdater , ArMemToPointCloudProvider , TimeoutExample , RobotControlUI , RobotUnitObserver , ObjectLearningByPushingObserver , VisualContactDetectionObserver , SimpleEpisodicMemoryKinematicUnitConnector , ClientState , ReasoningMemory , ViewSelectionConfigDialog , Component , JsonStorage , OnTablePredicateProvider , Component , StateParameterExample , GraspMemory , Receiver , SimpleVirtualRobot , CommonStorageExample , KinectAndCameraCalibrationObserver , LegacyRGBOpenPoseEstimation , LegacyRGBDOpenPoseEstimation , RGBDOpenPoseEstimation , GraspProviderExample , StatechartListener , UserAssistedSegmenterConfigDialog , ObjectMemoryEditor , X11ScreenCaptureImageProvider , DiagnosticsSubUnit , RobotUnitEmergencyStopMaster , OpenNIImageProvider , ObjectShapeClassification , StreamReceiver , ViconMarkerProvider , OptoForce , StreamImageProvider , ResultImageAndPointCloudProvider , and InstallConditionExample .
virtual void onConnectComponent
(
)
protected pure virtual
Pure virtual hook for the subclass.
Is called once all dependencies of the object have been resolved and Ice connection is established. This hook is called whenever the dependencies are found. That means if the a depedency crashes or shuts down, the ManagedIceObject goes into disconnected state. When the dependencies are found again, this hook is called again.
See also onDisconnectComponent()
Implemented in ArVizInteractExample , PointCloudProcessor , KBMComponent , EmergencyStopNode< T > , RobotIK , ImageProcessor , SceneEditorMainWindowController , DMPComponent , GraphVisualizerWidget , PointCloudProvider , SimpleConfigDialog , TrajectoryPlayer , OpenNIPointCloudProvider , CoFusionProcessor , EmergencyStopMaster , WorkingMemoryController , LaserScannerSelfLocalisation , WorkingMemoryController , ImageProvider , SimoxCSpaceVisualizerWidgetController , TrajectoryControllerSubUnit , MultiSensePointCloudProvider , StatechartEditorController , KinectV2PointCloudProvider , PointCloudAndImageProcessor , GraspingManager , TCPControlUnit , Component , ConditionHandler , KinematicUnitWidgetController , FTSensorCalibrationGuiWidgetController , DeepFaceRecognition , ImageToPointCloud , SceneModifier , ObjectLocalizationSaliency , EventSenderOverview , RTABMapRegistration , RemoteGuiExample2 , SimpleRobotPlacement , ReflexCombination , WorkerNode , LocalTimeServer , RobotStateComponent , StereoImagePointCloudProvider , Simulator , LaserScannerSimulation , CollisionCheckerComponent , KinectV1PointCloudProvider , ArmarXPlotter , ManagerNode , AffordanceExtraction , ArmarXSimulatorWindow , Viewer3DWidget , ATINetFTUnit , AffordancePipelineVisualization , DebugDrawerComponent , ViewSelection , HokuyoLaserUnit , PriorEditorController , XMLStateComponent , FrameTracking , MMMSimulation , SimulatorControlController , IntelRealSenseProvider , MotionPlanningServer , RemoteObjectNode , TopicRecorderComponent , DSObstacleAvoidance , ArmarXTimeserver , OrientedTactileSensorUnit , WidgetController , SystemStateMonitorWidget , AzureKinectPointCloudProvider , RobotTrajectoryDesignerGuiPluginWidgetController , FakePointCloudProvider , PlatformUnitWidget , AffordancePipelineGuiWidgetController , UserAssistedSegmenterGuiWidgetController , RemoteState , SkillsMemory , ObjectLocalizationMemoryUpdater , MotionPlanningServerWidgetController , ClockWidgetController , ViewSelectionWidgetController , SemanticRelationViewerWidgetController , SnapshotControlWidgetController , PrimitiveExtractionWidgetController , DHParameterOptimizationLogger , GridFSFileEditorWidgetController , UCLObjectRecognition , PrimitiveVisualization , SimpleGraspGenerator , ScenarioManagerWidgetController , PointCloudVisualizationWidgetController , ExternalApplicationManager , TopicReplayerWidgetController , TCPMover , PointCloudUtility , RobotIKWidgetController , RobotHealth , OptoForceUnit , FunctionApproximator , SelfLocalization , CartesianNaturalPositionControllerWidgetController , RemoteGuiWidgetController , NaturalIKTest , ObjectLocalizationRequesterWidgetController , XMLSceneImporter , ArVizWidgetController , GuiHealthClientWidgetController , GraphNodePoseResolver , RobotUnitPluginWidgetController , HumanObstacleDetection , PlannedMotionProvider , LaserScannerSelfLocalisationWidgetController , LoadObjectsIntoMemoryWidgetController , KinematicSelfLocalization , ThreadList , MessageDisplayPluginWidgetController , PathPlanner , LaserScannerFeatureExtraction , IceProxyWidgetController , HomogeneousMatrixCalculatorWidgetController , LaserScannerPluginWidgetController , RobotViewerWidgetController , ShapesSupportRelations , MMMPlayerWidget , ThreadViewer , WriteToDebugObserverGuiPluginWidgetController , OpenPoseSimulation , RCPointCloudProvider , SimpleStatechartExecutor , GamepadControlUnit , SceneEditorConfigDialog , ClutteredSceneGeneratorWidgetController , MMMPlayer , IceGridViewer , GamepadUnit , DummyObjectLocalizer , EntityDrawerComponent , RobotHealthDummy , WorkingMemoryToArViz , HandUnit , WorkingMemoryObjectPoseProvider , SemanticRelationAnalyzer , DepthImageProviderDynamicSimulation , GraspingManagerTest , PlatformUnit , RobotPoseUnit , TCPControllerSubUnit , ArMemMemoryViewerWidgetController , GraspCandidateViewerWidgetController , DebugPlotterWidgetWidgetController , HandUnitWidget , DummyAgentReporter , OLPEvaluation , KinematicUnit , StreamDecoderImageProvider , Component , RobotStateMemory , DebugDrawerViewerWidgetController , DebugRobotUnitDataStreamingWidgetController , SimoxSceneImporter , Component , Component , ArVizExample , AbstractWorkingMemory , DummyArMarkerLocalizer , ObjectMemory , ArmarXPhysicsWorldVisualization , ViconMarkerProvider , RemoteGuiProvider , ForceTorqueUnit , ObjectPoseGuiWidgetController , LogViewer , DummyTextToSpeech , MetaWearIMU , CommonStorage , SemanticGraphStorage , StaticAgentReporter , MotionPlanningServerConfigDialog , Component , PythonApplicationManager , ExampleMemory , RobotToArViz , TopicTimingClient , ProfilerStorage , RobotHandLocalizationDynamicSimulation , Base , Component , TopicReplayer , MemoryNameSystem , DynamicObstacleManager , ObjectPoseProviderExample , CommonPlacesTester , DummyWorldStateObserver , FakeWorkingMemoryObjectLocalizer , Component , BoxToGraspCandidatesWidgetController , PriorKnowledgeImporter , LaserScannerObstacleDetection , KITProstheticHandObserver , InertialMeasurementUnit , AffordanceUpdateListener , ImageRecorderWidgetController , ArticulatedObjectLocalizerDynamicSimulation , LegacyRobotStateMemoryAdapter , DebugDrawerToArVizComponent , DebugDrawerGuiPluginWidgetController , ArMarkerExternalCameraCalibration , WorkerNode , Component , PingLoadTest , ExampleMemoryClient , Component , StatechartExecutorExample , HapticUnitWidget , WorkingMemoryUpdater , SimulatorToArviz , ArVizDrawerGuiWidgetController , SkillManagerMonitorWidgetController , Component , GeneralPurposeMemory , TopicTimingServer , Component , Component , CartesianImpedanceControllerWidgetController , ArVizStorage , ik_demo , HapticUnit , HeadIKUnit , Component , DynamicRemoteState , MultiHandUnit , SemanticGraphExample , AStarPathPlannerTestComponent , RobotDefinition , LaserScansMemory , RobotNameService , SkillProviderExample , MemoryGrapher , PersonMemoryDebugger , SimpleEpisodicMemorySemanticGraphConnector , ObjectLocalizerDynamicSimulation , StatechartViewerController , ObjectInstanceToIndex , ObjectPoseClientExample , WorkingMemoryExample , PriorKnowledge , Component , Component , Component , EmergencyStopWidget , StateWatcher , CommonPlacesLearner , CartesianWaypointControlGuiWidgetController , ArmarXFileLogger , WorldStateObserver , GraspSelectionCriterionBase , GraspSelectionManager , ObserverWidgetController , ArmarXObjectsImporter , BatteryWidget , IndexMemory , SimulationObjectPoseProvider , VirtualRobotReaderExampleClient , MotionMemory , SimpleEpisodicMemoryKinematicUnitConnector , ConditionViewerWidgetController , WorldStateUpdaterBase , PriorEditorConfigDialog , HumanMemory , ArMemToImageProvider , Component , Component , SimulatorTimeServerProxy , HandControlSkillProvider , PlatformControlSkillProvider , SubjectMemory , VisionMemory , JointControlSkillProvider , TCPControlSkillProvider , VisualSearchSkillProvider , VisualServoTCPControlSkillProvider , SimpleEpisodicMemoryPlatformUnitConnector , LocalizationUnit , SimpleEpisodicMemory , AbstractLongtermMemory , PersonInstanceUpdater , GraspMemory , PlatformUnitConfigDialog , SimpleEpisodicMemoryWorkingMemoryConnector , AffordancePipelineGuiConfigDialog , PointCloudVisualizationConfigDialog , PrimitiveExtractionConfigDialog , GraspControlSkillProvider , HandUnitConfigDialog , KinematicUnitConfigDialog , TCPMoverConfigDialog , MMMPlayerConfigDialog , SelfLocalizationDynamicSimulation , Component , Receiver , BringObjectSkillProvider , Component , StaticPlotterWidgetController , ExternalApplicationManagerStarter , ArticulatedObjectLocalizerExample , Component , SystemStateMemory , VirtualRobotWriterExample , AronComponentConfigExample , RobotControlUI , ReasoningMemory , ExternalApplicationManagerDependency , SimpleVirtualRobot , CommonStorageExample , JsonStorage , GraspProviderExample , ViewSelectionConfigDialog , UserAssistedSegmenterConfigDialog , StatechartListener , DiagnosticsSubUnit , ObjectMemoryEditor , ModuleBase , RobotUnitEmergencyStopMaster , PointCloudAndImageProvider , NJointControllerBase , StreamReceiver , ObjectShapeClassification , OptoForce , StreamImageProvider , ResultImageAndPointCloudProvider , and SimpleEpisodicMemoryOpenPoseEstimationConnector .
virtual void onDisconnectComponent
(
)
inline protected virtual
Hook for subclass.
Is called if a dependency of the object got lost (crash, network error, stopped, ...). This hook should be the inverse to onConnectComponent() . So that onDisconnectComponent() and onConnectComponent() can be called alternatingly and the ManagedIceObject remains in valid states. *
See also onConnectComponent
Reimplemented in ArVizInteractExample , PointCloudProcessor , KBMComponent , ImageProcessor , RobotIK , SceneEditorMainWindowController , DMPComponent , PointCloudProvider , TrajectoryPlayer , OpenNIPointCloudProvider , CoFusionProcessor , LaserScannerSelfLocalisation , WorkingMemoryController , SimoxCSpaceVisualizerWidgetController , ImageProvider , TrajectoryControllerSubUnit , MultiSensePointCloudProvider , PointCloudAndImageProcessor , StatechartEditorController , KinectV2PointCloudProvider , ImageToPointCloud , GraspingManagerTest , GraspingManager , Component , TCPControlUnit , KinematicUnitWidgetController , RTABMapRegistration , ObjectLocalizationSaliency , FTSensorCalibrationGuiWidgetController , SceneModifier , SimpleRobotPlacement , RemoteGuiExample2 , ReflexCombination , ObjectLocalizerProcessor , WorkerNode , XMLStateComponent , LaserScannerSimulation , CollisionCheckerComponent , LocalTimeServer , RobotStateComponent , ManagerNode , StereoImagePointCloudProvider , Simulator , AffordanceExtraction , KinectV1PointCloudProvider , ATINetFTUnit , AffordancePipelineVisualization , ViewSelection , HokuyoLaserUnit , ArmarXSimulatorWindow , DebugDrawerComponent , FrameTracking , MMMSimulation , PriorEditorController , DSObstacleAvoidance , MotionPlanningServer , ArmarXTimeserver , SimulatorControlController , IntelRealSenseProvider , TopicRecorderComponent , SystemStateMonitorWidget , ForceTorqueObserver , RobotTrajectoryDesignerGuiPluginWidgetController , AzureKinectPointCloudProvider , MotionPlanningServerWidgetController , ClockWidgetController , SnapshotControlWidgetController , FakePointCloudProvider , SkillsMemory , PlatformUnitWidget , GridFSFileEditorWidgetController , AffordancePipelineGuiWidgetController , DHParameterOptimizationLogger , RemoteState , ObjectLocalizationMemoryUpdater , PrimitiveVisualization , SimpleGraspGenerator , SemanticRelationViewerWidgetController , PointCloudUtility , PrimitiveExtractionWidgetController , RobotHealth , OptoForceUnit , FunctionApproximator , SelfLocalization , PointCloudVisualizationWidgetController , ExternalApplicationManager , NaturalIKTest , GraphNodePoseResolver , RobotIKWidgetController , PlannedMotionProvider , CartesianNaturalPositionControllerWidgetController , GuiHealthClientWidgetController , ObjectLocalizationRequesterWidgetController , KinematicSelfLocalization , ArVizWidgetController , RobotUnitPluginWidgetController , HumanObstacleDetection , LaserScannerFeatureExtraction , OpenPoseSimulation , ShapesSupportRelations , ThreadList , GamepadControlUnit , MMMPlayer , MMMPlayerWidget , GamepadUnit , RobotViewerWidgetController , DummyObjectLocalizer , RobotHealthDummy , RCPointCloudProvider , SemanticRelationAnalyzer , EntityDrawerComponent , WorkingMemoryObjectPoseProvider , GraspCandidateViewerWidgetController , DummyAgentReporter , WorkingMemoryToArViz , OLPEvaluation , PlatformUnit , RobotPoseUnit , ArMemMemoryViewerWidgetController , Component , DebugPlotterWidgetWidgetController , HandUnitWidget , DummyArMarkerLocalizer , ViconMarkerProvider , Component , RemoteGuiProvider , RobotStateMemory , ArVizExample , DummyTextToSpeech , MetaWearIMU , DebugRobotUnitDataStreamingWidgetController , StaticAgentReporter , Component , ObjectMemory , ObjectPoseGuiWidgetController , ProfilerStorage , DepthImageProviderDynamicSimulation , DummyWorldStateObserver , SemanticGraphStorage , ArmarXPhysicsWorldVisualization , FakeWorkingMemoryObjectLocalizer , Base , Component , RobotToArViz , TopicTimingClient , Component , MemoryNameSystem , KITProstheticHandObserver , ObjectPoseProviderExample , InertialMeasurementUnit , AffordanceUpdateListener , Component , PythonApplicationManager , ExampleMemory , RobotHandLocalizationDynamicSimulation , TopicReplayer , DynamicObstacleManager , ArticulatedObjectLocalizerDynamicSimulation , LegacyRobotStateMemoryAdapter , DebugDrawerToArVizComponent , ArMarkerExternalCameraCalibration , ImageRecorderWidgetController , LaserScannerObstacleDetection , Component , PingLoadTest , StatechartExecutorExample , SimulatorToArviz , DebugDrawerGuiPluginWidgetController , HapticUnitWidget , Component , ExampleMemoryClient , Component , GeneralPurposeMemory , TopicTimingServer , WorkingMemoryUpdater , Component , Component , ArVizStorage , ik_demo , RobotDefinition , ArVizDrawerGuiWidgetController , Component , MultiHandUnit , RobotNameService , SemanticGraphExample , HeadIKUnit , LaserScansMemory , MemoryGrapher , PersonMemoryDebugger , SimpleEpisodicMemorySemanticGraphConnector , Component , Component , Component , SkillProviderExample , ObjectLocalizerDynamicSimulation , StatechartViewerController , ObjectInstanceToIndex , ObjectPoseClientExample , EmergencyStopWidget , StateWatcher , ArmarXObjectsImporter , ArmarXFileLogger , SimulationObjectPoseProvider , SimpleEpisodicMemoryKinematicUnitConnector , BatteryWidget , IndexMemory , VirtualRobotReaderExampleClient , MotionMemory , ConditionViewerWidgetController , HumanMemory , Component , Component , SimpleEpisodicMemoryPlatformUnitConnector , ArMemToImageProvider , PersonInstanceUpdater , SimulatorTimeServerProxy , HandControlSkillProvider , PlatformControlSkillProvider , SubjectMemory , WeissHapticUnit , SimpleEpisodicMemory , SimpleEpisodicMemoryWorkingMemoryConnector , VisionMemory , JointControlSkillProvider , TCPControlSkillProvider , VisualSearchSkillProvider , VisualServoTCPControlSkillProvider , GraspMemory , GraspControlSkillProvider , Component , SelfLocalizationDynamicSimulation , Component , BringObjectSkillProvider , ExternalApplicationManagerStarter , Component , AronComponentConfigExample , ArticulatedObjectLocalizerExample , SystemStateMemory , VirtualRobotWriterExample , ExternalApplicationManagerDependency , ReasoningMemory , SimpleVirtualRobot , JsonStorage , GraspProviderExample , ObjectMemoryEditor , ModuleBase , PointCloudAndImageProvider , NJointControllerBase , StreamReceiver , NJointBimanualCCDMPController , OptoForce , SkillManagerMonitorWidgetController , and ResultImageAndPointCloudProvider .
Definition at line 563 of file ManagedIceObject.h .
virtual void onExitComponent
(
)
inline protected virtual
Hook for subclass.
Is called once the component terminates. Use for cleanup. Only called once.
Reimplemented in ArVizInteractExample , PointCloudProcessor , KBMComponent , ImageProcessor , DMPComponent , GraphVisualizerWidget , PointCloudProvider , TrajectoryPlayer , LaserScannerSelfLocalisation , SimoxCSpaceVisualizerWidgetController , OpenNIPointCloudProvider , CoFusionProcessor , ImageProvider , WorkingMemoryController , MultiSensePointCloudProvider , PointCloudAndImageProcessor , GraspingManagerTest , StatechartEditorController , KinectV2PointCloudProvider , GraspingManager , RTABMapRegistration , Component , ObjectLocalizationSaliency , TCPControlUnit , KinematicUnitWidgetController , ImageToPointCloud , SimpleRobotPlacement , ReflexCombination , RemoteGuiExample2 , FTSensorCalibrationGuiWidgetController , WorkerNode , SceneModifier , LaserScannerSimulation , CollisionCheckerComponent , ManagerNode , AffordanceExtraction , ATINetFTUnit , AffordancePipelineVisualization , KinectV1PointCloudProvider , StereoImagePointCloudProvider , Simulator , ViewSelection , HokuyoLaserUnit , ArmarXPlotter , DSObstacleAvoidance , FrameTracking , ArmarXSimulatorWindow , MMMSimulation , DebugDrawerComponent , ArmarXTimeserver , PriorEditorController , MotionPlanningServer , RemoteObjectNode , SimulatorControlController , TopicRecorderComponent , SystemStateMonitorWidget , AzureKinectPointCloudProvider , DHParameterOptimizationLogger , SkillsMemory , FakePointCloudProvider , PrimitiveVisualization , SimpleGraspGenerator , PlatformUnitWidget , PointCloudUtility , RobotHealth , OptoForceUnit , FunctionApproximator , SelfLocalization , SensorActorUnit , GraphNodePoseResolver , PlannedMotionProvider , ExternalApplicationManager , NaturalIKTest , KinematicSelfLocalization , ScenarioManagerWidgetController , RobotIKWidgetController , TCPMover , OpenPoseSimulation , GamepadControlUnit , HumanObstacleDetection , MMMPlayer , LaserScannerFeatureExtraction , GamepadUnit , RobotUnitPluginWidgetController , DummyObjectLocalizer , ShapesSupportRelations , RobotHealthDummy , SceneEditorConfigDialog , SemanticRelationAnalyzer , ArVizWidgetController , RobotViewerWidgetController , DummyAgentReporter , OLPEvaluation , MMMPlayerWidget , ThreadViewer , PlatformUnit , WorkingMemoryObjectPoseProvider , RCPointCloudProvider , HandUnit , RobotPoseUnit , SimpleStatechartExecutor , EntityDrawerComponent , IceGridViewer , GraspCandidateViewerWidgetController , WorkingMemoryToArViz , DummyArMarkerLocalizer , ViconMarkerProvider , Component , RemoteGuiProvider , DepthImageProviderDynamicSimulation , DummyTextToSpeech , MetaWearIMU , StaticAgentReporter , Component , DebugPlotterWidgetWidgetController , HandUnitWidget , ProfilerStorage , DummyWorldStateObserver , FakeWorkingMemoryObjectLocalizer , RobotStateMemory , KinematicUnit , DebugDrawerViewerWidgetController , Base , ArVizExample , KITProstheticHandObserver , InertialMeasurementUnit , DebugRobotUnitDataStreamingWidgetController , AffordanceUpdateListener , SemanticGraphStorage , Component , Component , ObjectMemory , RobotToArViz , TopicTimingClient , Component , MemoryNameSystem , ObjectPoseProviderExample , ArmarXPhysicsWorldVisualization , Component , ForceTorqueUnit , ArticulatedObjectLocalizerDynamicSimulation , PythonApplicationManager , LogViewer , LegacyRobotStateMemoryAdapter , ExampleMemory , DebugDrawerToArVizComponent , CommonStorage , ArMarkerExternalCameraCalibration , RobotHandLocalizationDynamicSimulation , Component , PingLoadTest , DynamicObstacleManager , StatechartExecutorExample , ImageRecorderWidgetController , SimulatorToArviz , RobotDefinition , LaserScannerObstacleDetection , Component , GeneralPurposeMemory , RobotNameService , TopicTimingServer , Component , Component , ArVizStorage , ik_demo , Component , ExampleMemoryClient , Component , MultiHandUnit , WorkingMemoryUpdater , SemanticGraphExample , WorkerNode , HapticUnitWidget , LaserScansMemory , MemoryGrapher , PersonMemoryDebugger , SimpleEpisodicMemorySemanticGraphConnector , HeadIKUnit , Component , Component , Component , HapticUnit , AStarPathPlannerTestComponent , SkillProviderExample , ArmarXObjectsImporter , ObjectLocalizerDynamicSimulation , StatechartViewerController , ObjectInstanceToIndex , ObjectPoseClientExample , SimulationObjectPoseProvider , SimpleEpisodicMemoryKinematicUnitConnector , ArmarXFileLogger , CommonPlacesLearner , ObserverWidgetController , IndexMemory , Component , VirtualRobotReaderExampleClient , MotionMemory , SimpleEpisodicMemoryPlatformUnitConnector , ConditionViewerWidgetController , HumanMemory , Component , PersonInstanceUpdater , SimpleEpisodicMemoryWorkingMemoryConnector , SimpleEpisodicMemory , ArMemToImageProvider , SimulatorTimeServerProxy , HandControlSkillProvider , PlatformControlSkillProvider , SubjectMemory , VisionMemory , JointControlSkillProvider , TCPControlSkillProvider , VisualSearchSkillProvider , VisualServoTCPControlSkillProvider , Component , GraspMemory , Receiver , GraspControlSkillProvider , Component , AffordancePipelineGuiConfigDialog , PointCloudVisualizationConfigDialog , PrimitiveExtractionConfigDialog , KinematicUnitConfigDialog , MMMPlayerConfigDialog , AronComponentConfigExample , Component , BringObjectSkillProvider , ExternalApplicationManagerStarter , ArticulatedObjectLocalizerExample , SystemStateMemory , VirtualRobotWriterExample , ExternalApplicationManagerDependency , ReasoningMemory , RobotControlUI , SimpleVirtualRobot , JsonStorage , GraspProviderExample , ViewSelectionConfigDialog , UserAssistedSegmenterConfigDialog , ObjectMemoryEditor , ModuleBase , PointCloudAndImageProvider , NJointControllerBase , IntelRealSenseProvider , StreamReceiver , OptoForce , and ResultImageAndPointCloudProvider .
Definition at line 570 of file ManagedIceObject.h .
virtual void onInitComponent
(
)
protected pure virtual
Pure virtual hook for the subclass.
Is called once initialization of the ManagedIceObject is done. This hook is called in the implenting class once and never again during the lifecyle of the object. This function is called as soon as the ManagedIceObject was added to the ArmarXManager . Called in an own thread and not the thread it was created in.
Implemented in ArVizInteractExample , PointCloudProcessor , KBMComponent , EmergencyStopNode< T > , RobotIK , ImageProcessor , SceneEditorMainWindowController , DMPComponent , GraphVisualizerWidget , PointCloudProvider , SimpleConfigDialog , TrajectoryPlayer , OpenNIPointCloudProvider , CoFusionProcessor , WorkingMemoryController , EmergencyStopMaster , LaserScannerSelfLocalisation , TrajectoryControllerSubUnit , ImageProvider , WorkingMemoryController , StatechartEditorController , MultiSensePointCloudProvider , SimoxCSpaceVisualizerWidgetController , KinectV2PointCloudProvider , TCPControlUnit , ConditionHandler , KinematicUnitWidgetController , Component , GraspingManager , FTSensorCalibrationGuiWidgetController , DeepFaceRecognition , PointCloudAndImageProcessor , EventSenderOverview , SceneModifier , ObjectLocalizationSaliency , RemoteGuiExample2 , ImageToPointCloud , RTABMapRegistration , SimpleRobotPlacement , RobotStateComponent , WorkerNode , ReflexCombination , StereoImagePointCloudProvider , Simulator , LocalTimeServer , ArmarXPlotter , KinectV1PointCloudProvider , ArmarXSimulatorWindow , LaserScannerSimulation , CollisionCheckerComponent , ManagerNode , Viewer3DWidget , DebugDrawerComponent , AffordanceExtraction , PriorEditorController , XMLStateComponent , ATINetFTUnit , AffordancePipelineVisualization , ViewSelection , HokuyoLaserUnit , SimulatorControlController , IntelRealSenseProvider , TopicRecorderComponent , FrameTracking , MMMSimulation , OrientedTactileSensorUnit , WidgetController , MotionPlanningServer , AzureKinectPointCloudProvider , RemoteObjectNode , ArmarXTimeserver , DSObstacleAvoidance , SystemStateMonitorWidget , FakePointCloudProvider , RobotTrajectoryDesignerGuiPluginWidgetController , PlatformUnitWidget , RemoteState , ObjectLocalizationMemoryUpdater , UserAssistedSegmenterGuiWidgetController , SkillsMemory , AffordancePipelineGuiWidgetController , MotionPlanningServerWidgetController , ClockWidgetController , UCLObjectRecognition , ViewSelectionWidgetController , SemanticRelationViewerWidgetController , TCPMover , PrimitiveExtractionWidgetController , DHParameterOptimizationLogger , RobotIKWidgetController , ExternalApplicationManager , CartesianNaturalPositionControllerWidgetController , RemoteGuiWidgetController , XMLSceneImporter , PrimitiveVisualization , SimpleGraspGenerator , ScenarioManagerWidgetController , SnapshotControlWidgetController , PointCloudVisualizationWidgetController , SelfLocalization , TopicReplayerWidgetController , NaturalIKTest , PointCloudUtility , RobotHealth , OptoForceUnit , ArVizWidgetController , GridFSFileEditorWidgetController , FunctionApproximator , ObjectLocalizationRequesterWidgetController , HumanObstacleDetection , ThreadList , GuiHealthClientWidgetController , RobotUnitPluginWidgetController , RobotViewerWidgetController , GraphNodePoseResolver , MMMPlayerWidget , PlannedMotionProvider , LaserScannerSelfLocalisationWidgetController , LaserScannerFeatureExtraction , LoadObjectsIntoMemoryWidgetController , RCPointCloudProvider , ShapesSupportRelations , KinematicSelfLocalization , SimpleStatechartExecutor , MessageDisplayPluginWidgetController , PathPlanner , IceProxyWidgetController , HomogeneousMatrixCalculatorWidgetController , LaserScannerPluginWidgetController , EntityDrawerComponent , ThreadViewer , WriteToDebugObserverGuiPluginWidgetController , WorkingMemoryToArViz , ClutteredSceneGeneratorWidgetController , OpenPoseSimulation , DepthImageProviderDynamicSimulation , GamepadControlUnit , MMMPlayer , IceGridViewer , GamepadUnit , ArMemMemoryViewerWidgetController , GraspCandidateViewerWidgetController , DummyObjectLocalizer , WorkingMemoryObjectPoseProvider , DebugPlotterWidgetWidgetController , RobotHealthDummy , HandUnitWidget , HandUnit , KinematicUnit , SceneEditorConfigDialog , SemanticRelationAnalyzer , RobotStateMemory , PlatformUnit , RobotPoseUnit , TCPControllerSubUnit , DebugRobotUnitDataStreamingWidgetController , SimoxSceneImporter , Component , Component , ArVizExample , DebugDrawerViewerWidgetController , DummyAgentReporter , AbstractWorkingMemory , OLPEvaluation , ObjectMemory , ArmarXPhysicsWorldVisualization , Component , ForceTorqueUnit , LogViewer , CommonStorage , PythonApplicationManager , ExampleMemory , ObjectPoseGuiWidgetController , DummyArMarkerLocalizer , RobotHandLocalizationDynamicSimulation , GraspingManagerTest , TopicReplayer , DynamicObstacleManager , CommonPlacesTester , SemanticGraphStorage , ViconMarkerProvider , Component , RemoteGuiProvider , RobotToArViz , TopicTimingClient , BoxToGraspCandidatesWidgetController , PriorKnowledgeImporter , LaserScannerObstacleDetection , MotionPlanningServerConfigDialog , Component , MemoryNameSystem , DummyTextToSpeech , ObjectPoseProviderExample , MetaWearIMU , StaticAgentReporter , Base , Component , DebugDrawerGuiPluginWidgetController , ProfilerStorage , ImageRecorderWidgetController , WorkerNode , ExampleMemoryClient , Component , HapticUnitWidget , DummyWorldStateObserver , WorkingMemoryUpdater , ArticulatedObjectLocalizerDynamicSimulation , FakeWorkingMemoryObjectLocalizer , LegacyRobotStateMemoryAdapter , DebugDrawerToArVizComponent , ArVizDrawerGuiWidgetController , SkillManagerMonitorWidgetController , ArMarkerExternalCameraCalibration , Component , PingLoadTest , KITProstheticHandObserver , StatechartExecutorExample , InertialMeasurementUnit , AffordanceUpdateListener , SimulatorToArviz , HapticUnit , HeadIKUnit , Component , DynamicRemoteState , GeneralPurposeMemory , TopicTimingServer , Component , Component , ArVizStorage , ik_demo , Component , MultiHandUnit , SkillProviderExample , SemanticGraphExample , ObjectLocalizerDynamicSimulation , StatechartViewerController , ObjectInstanceToIndex , ObjectPoseClientExample , WorkingMemoryExample , PriorKnowledge , EmergencyStopWidget , StateWatcher , LaserScansMemory , CommonPlacesLearner , MemoryGrapher , PersonMemoryDebugger , SimpleEpisodicMemorySemanticGraphConnector , AStarPathPlannerTestComponent , ArmarXFileLogger , RobotDefinition , WorldStateObserver , Component , GraspSelectionCriterionBase , GraspSelectionManager , Component , Component , ObserverWidgetController , RobotNameService , BatteryWidget , IndexMemory , VirtualRobotReaderExampleClient , MotionMemory , ArmarXObjectsImporter , ConditionViewerWidgetController , WorldStateUpdaterBase , HumanMemory , SimulationObjectPoseProvider , SimpleEpisodicMemoryKinematicUnitConnector , ArMemToImageProvider , SimulatorTimeServerProxy , HandControlSkillProvider , PlatformControlSkillProvider , SubjectMemory , PriorEditorConfigDialog , VisionMemory , Component , JointControlSkillProvider , TCPControlSkillProvider , VisualSearchSkillProvider , VisualServoTCPControlSkillProvider , AbstractLongtermMemory , Component , GraspMemory , PlatformUnitConfigDialog , SimpleEpisodicMemory , SimpleEpisodicMemoryPlatformUnitConnector , PersonInstanceUpdater , AffordancePipelineGuiConfigDialog , PointCloudVisualizationConfigDialog , PrimitiveExtractionConfigDialog , GraspControlSkillProvider , HandUnitConfigDialog , KinematicUnitConfigDialog , TCPMoverConfigDialog , SimpleEpisodicMemoryWorkingMemoryConnector , MMMPlayerConfigDialog , LocalizationUnit , BringObjectSkillProvider , Component , StaticPlotterWidgetController , ExternalApplicationManagerStarter , ArticulatedObjectLocalizerExample , Component , SystemStateMemory , Receiver , Component , VirtualRobotWriterExample , RobotControlUI , ReasoningMemory , AronComponentConfigExample , ExternalApplicationManagerDependency , SimpleVirtualRobot , CommonStorageExample , JsonStorage , GraspProviderExample , ViewSelectionConfigDialog , UserAssistedSegmenterConfigDialog , StatechartListener , DiagnosticsSubUnit , ObjectMemoryEditor , ModuleBase , RobotUnitEmergencyStopMaster , PointCloudAndImageProvider , NJointControllerBase , StreamReceiver , NJointBimanualCCDMPController , ObjectShapeClassification , OptoForce , SimpleEpisodicMemoryOpenPoseEstimationConnector , and ResultImageAndPointCloudProvider .