From 92ce1a77f0944d4b60cb89f1e1f0b1ef8133d618 Mon Sep 17 00:00:00 2001
From: Johann Mantel <j-mantel@gmx.net>
Date: Thu, 17 Jun 2021 18:32:04 +0200
Subject: [PATCH] code formatting

---
 .../drivers/SickLaserUnit/SickLaserUnit.cpp   | 31 +++++++++----------
 1 file changed, 14 insertions(+), 17 deletions(-)

diff --git a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
index 2de3d8415..a38cc31d3 100644
--- a/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
+++ b/source/RobotAPI/drivers/SickLaserUnit/SickLaserUnit.cpp
@@ -76,10 +76,9 @@ void SickLaserUnit::onInitComponent() {
 
   std::string scannerName;
   if (false == nhPriv.getParam("scanner_type", scannerName)) {
-    ROS_ERROR(
-	"cannot find parameter "
-	"scanner_type"
-	" in the param set. Please specify scanner_type.");
+    ROS_ERROR("cannot find parameter "
+	      "scanner_type"
+	      " in the param set. Please specify scanner_type.");
     ROS_ERROR("Try to set %s as fallback.\n", nodeName.c_str());
     scannerName = nodeName;
   }
@@ -109,7 +108,7 @@ void SickLaserUnit::onInitComponent() {
       new sick_scan::SickGenericParser(scannerName);
 
   double param;
-  char colaDialectId = 'A';  // A or B (Ascii or Binary)
+  char colaDialectId = 'A'; // A or B (Ascii or Binary)
 
   if (nhPriv.getParam("range_min", param)) {
     parser->set_range_min(param);
@@ -163,14 +162,13 @@ void SickLaserUnit::onConnectComponent() {
   ROS_INFO("Start initialising scanner [Ip: %s] [Port: %s]", hostname.c_str(),
 	   port.c_str());
   // attempt to connect/reconnect
-  delete s;  // disconnect scanner
+  delete s; // disconnect scanner
   if (useTCP) {
     s = new sick_scan::SickScanCommonTcp(hostname, port, timelimit, parser,
 					 colaDialectId);
   } else {
-    ROS_ERROR(
-	"TCP is not switched on. Probably hostname or port not set. Use "
-	"roslaunch to start node.");
+    ROS_ERROR("TCP is not switched on. Probably hostname or port not set. Use "
+	      "roslaunch to start node.");
     exit(-1);
   }
 
@@ -181,16 +179,15 @@ void SickLaserUnit::onConnectComponent() {
 
   isInitialized = true;
   signal(SIGINT,
-	 SIG_DFL);  // change back to standard signal handler after initialising
-  if (result == sick_scan::ExitSuccess)  // OK -> loop again
+	 SIG_DFL); // change back to standard signal handler after initialising
+  if (result == sick_scan::ExitSuccess) // OK -> loop again
   {
     if (changeIP) {
       runState = scanner_finalize;
     }
-
-    runState = scanner_run;  // after initialising switch to run state
+    runState = scanner_run; // after initialising switch to run state
   } else {
-    runState = scanner_init;  // If there was an error, try to restart scanner
+    runState = scanner_init; // If there was an error, try to restart scanner
   }
   // Do things after connecting to topics and components.
 
@@ -222,12 +219,12 @@ void SickLaserUnit::onConnectComponent() {
 
 void SickLaserUnit::run() {
   while (!task->isStopped()) {
-    if (result == sick_scan::ExitSuccess)  // OK -> loop again
+    if (result == sick_scan::ExitSuccess) // OK -> loop again
     {
       ros::spinOnce();
       result = s->loopOnce();
     } else {
-      runState = scanner_finalize;  // interrupt
+      runState = scanner_finalize; // interrupt
     }
   }
 }
@@ -315,4 +312,4 @@ arviz)
 }
 */
 
-}  // namespace armarx
+} // namespace armarx
-- 
GitLab