From dbc8eead57420e36a595f6b85d2849836b0fa0d2 Mon Sep 17 00:00:00 2001
From: Johann Mantel <j-mantel@gmx.net>
Date: Wed, 28 Jul 2021 15:26:59 +0200
Subject: [PATCH] reduce variable count

---
 .../drivers/SickLaserUnit/SickLaserUnit.cpp   |  53 +++---
 .../drivers/SickLaserUnit/SickLaserUnit.h     | 165 +++++++++---------
 2 files changed, 111 insertions(+), 107 deletions(-)

diff --git a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
index fbfe25bdd..5498ee1d8 100644
--- a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
+++ b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
@@ -91,20 +91,18 @@ namespace armarx
         ARMARX_INFO_S << "Start initialising scanner [Ip: " << this->ip
                       << "] [Port: " << this->port << "]";
         // attempt to connect/reconnect
-        delete this->scanner; // disconnect scanner
-        if (this->useTcp)
+        if (this->scanner)
         {
-            this->scanner = new SickScanAdapter(this->ip, this->port, this->timelimit, this->parser, 'A');
+            ARMARX_WARNING_S << "Scanner already initized.";
+            delete this->scanner; // disconnect scanner
         }
-        else
-        {
-            ARMARX_ERROR_S << "TCP is not switched on. Probably hostname or port not set.\n";
-            return;
-        }
-        result = this->scanner->init();
+
+        this->scanner = new SickScanAdapter(this->ip, this->port, this->timelimit, this->parser, 'A');
+
+        this->result = this->scanner->init();
 
 
-        if (result == sick_scan::ExitSuccess) // OK -> loop again
+        if (this->result == sick_scan::ExitSuccess) // OK -> loop again
         {
             this->isSensorInitialized = true;
             ARMARX_INFO_S << "Scanner initialized.";
@@ -126,12 +124,12 @@ namespace armarx
         // def->topic(myTopicListener);
 
         // Subscribe to a topic (passing the topic name).
-        def->topic<LaserScannerUnitListenerPrx>(properties.topicName);
+        //def->topic<LaserScannerUnitListenerPrx>(properties.topicName);
 
         // Use (and depend on) another component (passing the ComponentInterfacePrx).
         // def->component(myComponentProxy)
 
-        def->optional(properties.topicName, "topicName", "Name of the topic");
+        def->topic(topic, properties.topicName, "TopicName", "Name of the laserscanner topic to report to.");
         //Scanner parameters
         def->optional(properties.devices, "devices", "List of Devices in format frame1,ip1,port1;frame2,ip2,port2");
         def->optional(properties.scannerType, "scannerType", "Name of the LaserScanner");
@@ -145,8 +143,8 @@ namespace armarx
     {
         // Topics and properties defined above are automagically registered.
 
-        offeringTopic(properties.topicName);
-        ARMARX_INFO_S << "SickLaserUnit is going to report on topic " << properties.topicName;
+        //offeringTopic(properties.topicName);
+        //ARMARX_INFO_S << "SickLaserUnit is going to report on topic " << properties.topicName;
         // Keep debug observer data until calling `sendDebugObserverBatch()`.
         // (Requies the armarx::DebugObserverComponentPluginUser.)
         // setDebugObserverBatchModeEnabled(true);
@@ -169,21 +167,23 @@ namespace armarx
             device.frameName = deviceInfo[0];
             if (deviceInfo[1] != "")
             {
-                device.useTcp = true;
                 device.ip = deviceInfo[1];
             }
+            else
+            {
+                ARMARX_FATAL << "TCP is not switched on. Probably hostname or port not set.";
+                return;
+
+            }
             device.port = deviceInfo[2];
-            device.scannerType = properties.scannerType;
             device.timelimit = properties.timelimit;
-            device.rangeMin = properties.rangeMin;
-            device.rangeMax = properties.rangeMax;
             //scanInfo
             device.scanInfo.device = device.ip;
             device.scanInfo.frame = device.frameName;
             //scanner Parameters
             try
             {
-                device.parser = new sick_scan::SickGenericParser(device.scannerType);
+                device.parser = new sick_scan::SickGenericParser(properties.scannerType);
                 device.parser->set_range_min(properties.rangeMin);
                 device.parser->set_range_max(properties.rangeMax);
                 device.parser->getCurrentParamPtr()->setUseBinaryProtocol(false);
@@ -201,7 +201,7 @@ namespace armarx
 
     void SickLaserUnit::onConnectComponent()
     {
-        topic = getTopic<LaserScannerUnitListenerPrx>(properties.topicName);
+        //topic = getTopic<LaserScannerUnitListenerPrx>(properties.topicName);
 
         for (SickLaserScanDevice& device : scanDevices)
         {
@@ -209,6 +209,7 @@ namespace armarx
             //start the laser scanner
             if (device.task)
             {
+                ARMARX_WARNING << "this should not happen.";
                 device.task->stop();
                 device.task = nullptr;
             }
@@ -240,6 +241,14 @@ namespace armarx
                 device.task->stop();
                 device.task = nullptr;
             }
+        }
+    }
+
+    void SickLaserUnit::onExitComponent()
+    {
+        for (SickLaserScanDevice& device : scanDevices)
+        {
+
             if (device.scanner)
             {
                 delete device.scanner;
@@ -249,9 +258,9 @@ namespace armarx
                 delete device.parser;
             }
         }
-    }
 
-    void SickLaserUnit::onExitComponent() {}
+
+    }
 
     std::string SickLaserUnit::getDefaultName() const
     {
diff --git a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.h b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.h
index 9bbc4fa64..f6ffc67a1 100644
--- a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.h
+++ b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.h
@@ -41,45 +41,40 @@ namespace armarx
 
     enum class ScanProtocol
     {
-	ASCII,
-	Binary
+        ASCII,
+        Binary
     };
 
     enum class RunState
     {
-	scannerInit,
-	scannerRun,
-	scannerFinalize
+        scannerInit,
+        scannerRun,
+        scannerFinalize
     };
 
     struct SickLaserScanDevice
     {
-	//scanner parameters
-	std::string scannerType = "sick_tim_5xx";
-	//communication parameters
-	std::string ip;
-	std::string port;
-	int timelimit = 5;
-	double rangeMin  = 0.0;
-	double rangeMax = 10.0;
-	bool useTcp = false;
-	//data and task pointers
-	IceUtil::Time scanTime;
-	LaserScan scanData;
-	LaserScannerInfo scanInfo;
-	int initCnt = 0;
-	RunState runState = RunState::scannerFinalize;
-	RunningTask<SickLaserScanDevice>::pointer_type task;
-	std::string frameName = "LaserScannerFront";
-	LaserScannerUnitListenerPrx scanTopic;
-	//scanner pointers
-	sick_scan::SickGenericParser* parser;
-	SickScanAdapter* scanner;
-	int result = sick_scan::ExitError;
-	bool isSensorInitialized = false;
-
-	void initScanner();
-	void run();
+        //communication parameters
+        std::string ip;
+        std::string port;
+        int timelimit = 5;
+        //data and task pointers
+        IceUtil::Time scanTime;
+        LaserScan scanData;
+        LaserScannerInfo scanInfo;
+        int initCnt = 0;
+        RunState runState = RunState::scannerFinalize;
+        RunningTask<SickLaserScanDevice>::pointer_type task;
+        std::string frameName = "LaserScannerFront";
+        LaserScannerUnitListenerPrx scanTopic;
+        //scanner pointers
+        sick_scan::SickGenericParser* parser = 0;
+        SickScanAdapter* scanner = 0;
+        int result = sick_scan::ExitError;
+        bool isSensorInitialized = false;
+
+        void initScanner();
+        void run();
     };
     /**
      * @defgroup Component-SickLaserUnit SickLaserUnit
@@ -94,74 +89,74 @@ namespace armarx
      */
     class SickLaserUnit :
     //virtual public armarx::LaserScannerUnitInterface,
-	virtual public armarx::Component
+        virtual public armarx::Component
     // , virtual public armarx::DebugObserverComponentPluginUser
     // , virtual public armarx::LightweightRemoteGuiComponentPluginUser
     // , virtual public armarx::ArVizComponentPluginUser
     {
     public:
-	/// @see armarx::ManagedIceObject::getDefaultName()
-	std::string getDefaultName() const override;
+        /// @see armarx::ManagedIceObject::getDefaultName()
+        std::string getDefaultName() const override;
 
     protected:
-	/// @see PropertyUser::createPropertyDefinitions()
-	armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
+        /// @see PropertyUser::createPropertyDefinitions()
+        armarx::PropertyDefinitionsPtr createPropertyDefinitions() override;
 
-	/// @see armarx::ManagedIceObject::onInitComponent()
-	void onInitComponent() override;
+        /// @see armarx::ManagedIceObject::onInitComponent()
+        void onInitComponent() override;
 
-	/// @see armarx::ManagedIceObject::onConnectComponent()
-	void onConnectComponent() override;
+        /// @see armarx::ManagedIceObject::onConnectComponent()
+        void onConnectComponent() override;
 
-	/// @see armarx::ManagedIceObject::onDisconnectComponent()
-	void onDisconnectComponent() override;
+        /// @see armarx::ManagedIceObject::onDisconnectComponent()
+        void onDisconnectComponent() override;
 
-	/// @see armarx::ManagedIceObject::onExitComponent()
-	void onExitComponent() override;
+        /// @see armarx::ManagedIceObject::onExitComponent()
+        void onExitComponent() override;
 
     private:
-	// Private methods go here.
+        // Private methods go here.
 
     private:
-	// Private member variables go here.
-
-	/// Properties shown in the Scenario GUI.
-	struct Properties
-	{
-	    std::string topicName = "SICKLaserScanner";
-	    //scanner parameters
-	    std::string devices = "LaserScannerFront,192.168.8.133,2112";
-	    std::string scannerType = "sick_tim_5xx";
-	    int timelimit = 5;
-	    double rangeMin  = 0.0;
-	    double rangeMax = 10.0;
-	};
-	Properties properties;
-	std::vector<SickLaserScanDevice> scanDevices;
-	LaserScannerUnitListenerPrx topic;
-	//HeartbeatComponentPlugin heartbeat;
-
-	/* Use a mutex if you access variables from different threads
-	 * (e.g. ice functions and RemoteGui_update()).
-	std::mutex propertiesMutex;
-	*/
-
-	/* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
-	/// Tab shown in the Remote GUI.
-	struct RemoteGuiTab : armarx::RemoteGui::Client::Tab
-	{
-	    armarx::RemoteGui::Client::LineEdit boxLayerName;
-	    armarx::RemoteGui::Client::IntSpinBox numBoxes;
-
-	    armarx::RemoteGui::Client::Button drawBoxes;
-	};
-	RemoteGuiTab tab;
-	*/
-
-	/* (Requires the armarx::ArVizComponentPluginUser.)
-	 * When used from different threads, an ArViz client needs to be synchronized.
-	/// Protects the arviz client inherited from the ArViz plugin.
-	std::mutex arvizMutex;
-	*/
+        // Private member variables go here.
+
+        /// Properties shown in the Scenario GUI.
+        struct Properties
+        {
+            std::string topicName = "SICKLaserScanner";
+            //scanner parameters
+            std::string devices = "LaserScannerFront,192.168.8.133,2112";
+            std::string scannerType = "sick_tim_5xx";
+            int timelimit = 5;
+            double rangeMin  = 0.0;
+            double rangeMax = 10.0;
+        };
+        Properties properties;
+        std::vector<SickLaserScanDevice> scanDevices;
+        LaserScannerUnitListenerPrx topic;
+        //HeartbeatComponentPlugin heartbeat;
+
+        /* Use a mutex if you access variables from different threads
+         * (e.g. ice functions and RemoteGui_update()).
+        std::mutex propertiesMutex;
+        */
+
+        /* (Requires the armarx::LightweightRemoteGuiComponentPluginUser.)
+        /// Tab shown in the Remote GUI.
+        struct RemoteGuiTab : armarx::RemoteGui::Client::Tab
+        {
+            armarx::RemoteGui::Client::LineEdit boxLayerName;
+            armarx::RemoteGui::Client::IntSpinBox numBoxes;
+
+            armarx::RemoteGui::Client::Button drawBoxes;
+        };
+        RemoteGuiTab tab;
+        */
+
+        /* (Requires the armarx::ArVizComponentPluginUser.)
+         * When used from different threads, an ArViz client needs to be synchronized.
+        /// Protects the arviz client inherited from the ArViz plugin.
+        std::mutex arvizMutex;
+        */
     };
 } // namespace armarx
-- 
GitLab