Classes | Macros | Functions | Variables
sick_generic_laser.cpp File Reference

Laser Scanner Main Handling Copyright (C) 2013, Osnabrueck University Copyright (C) 2017,2018 Ing.-Buero Dr. Michael Lehning, Hildesheim Copyright (C) 2017,2018 SICK AG, Waldkirch. More...

#include <sick_scan/sick_ros_wrapper.h>
#include <sick_scan/sick_scan_xd_version.h>
#include "softwarePLL.h"
#include <sick_scan/sick_scan_common_tcp.h>
#include <sick_scan/sick_generic_parser.h>
#include <sick_scan/sick_generic_laser.h>
#include <sick_scan/sick_scan_services.h>
#include <sick_scan/sick_generic_monitoring.h>
#include <sick_scan/sick_tf_publisher.h>
#include "launchparser.h"
#include <math.h>
#include <string>
#include <stdio.h>
#include <stdlib.h>
#include <signal.h>
#include "sick_scan_api.h"
#include "sick_scan/sick_nav_scandata_parser.h"
Include dependency graph for sick_generic_laser.cpp:

Go to the source code of this file.

Classes

class  GenericLaserCallable
 

Macros

#define _USE_MATH_DEFINES
 
#define DELETE_PTR(p)   if(p){delete(p);p=0;}
 
#define GITHASH_STR   std::string("")
 
#define GITINFO_STR   std::string("")
 
#define USE_LAUNCHPARSER
 

Functions

bool convertSendSOPASCommand (const std::string &sopas_ascii_request, std::string &sopas_response, bool wait_for_reply)
 Converts a given SOPAS command from ascii to binary (in case of binary communication), sends sopas (ascii or binary) and returns the response (if wait_for_reply:=true) More...
 
bool ends_with (std::string const &value, std::string const &ending)
 
void getDiagnosticStatus (SICK_DIAGNOSTIC_STATUS &status_code, std::string &status_message)
 
bool getTagVal (std::string tagVal, std::string &tag, std::string &val)
 splitting expressions like <tag>:=into <tag> and More...
 
int32_t getVerboseLevel ()
 
std::string getVersionInfo ()
 
void joinGenericLaser (void)
 Waits until all GenericLaser jobs finished. More...
 
int mainGenericLaser (int argc, char **argv, std::string nodeName, rosNodePtr nhPriv)
 Internal Startup routine. More...
 
void mainGenericLaserInternal (int argc, char **argv, std::string nodeName, rosNodePtr nhPriv, bool do_ros_spin, int &exit_code)
 Internal Startup routine. More...
 
bool parseLaunchfileSetParameter (rosNodePtr nhPriv, int argc, char **argv)
 Parses an optional launchfile and sets all parameters. This function is used at startup to enable system independant parameter handling for native Linux/Windows, ROS-1 and ROS-2. Parameter are overwritten by optional commandline arguments. More...
 
void rosSignalHandler (int signalRecv)
 
void setDiagnosticStatus (SICK_DIAGNOSTIC_STATUS status_code, const std::string &status_message)
 
void setVerboseLevel (int32_t verbose_level)
 
void setVersionInfo (std::string _versionInfo)
 
bool shutdownSignalReceived ()
 
int32_t SickScanApiNavOdomVelocityImpl (SickScanApiHandle apiHandle, SickScanNavOdomVelocityMsg *src_msg)
 
int32_t SickScanApiOdomVelocityImpl (SickScanApiHandle apiHandle, SickScanOdomVelocityMsg *src_msg)
 
bool startGenericLaser (int argc, char **argv, std::string nodeName, rosNodePtr nhPriv, int *exit_code)
 Runs mainGenericLaser non-blocking in a new thread. More...
 
bool stopScannerAndExit (bool force_immediate_shutdown)
 
std::string vargs_to_string (const char *const format,...)
 

Variables

static GenericLaserCallables_generic_laser_thread = 0
 
static bool s_isInitialized = false
 
static NodeRunState s_runState = scanner_init
 
static sick_scan_xd::SickScanCommonTcps_scanner = NULL
 
static bool s_shutdownSignalReceived = false
 
SICK_DIAGNOSTIC_STATUS s_status_code = SICK_DIAGNOSTIC_STATUS::INIT
 
std::string s_status_message = ""
 
int32_t s_verbose_level = 1
 
static std::string versionInfo = std::string(SICK_SCAN_XD_VERSION) + GITHASH_STR + GITINFO_STR
 

Detailed Description

Laser Scanner Main Handling Copyright (C) 2013, Osnabrueck University Copyright (C) 2017,2018 Ing.-Buero Dr. Michael Lehning, Hildesheim Copyright (C) 2017,2018 SICK AG, Waldkirch.

Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at

  http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright
  notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
  notice, this list of conditions and the following disclaimer in the
  documentation and/or other materials provided with the distribution.
* Neither the name of Osnabrueck University nor the names of its
  contributors may be used to endorse or promote products derived from
  this software without specific prior written permission.
* Neither the name of SICK AG nor the names of its
  contributors may be used to endorse or promote products derived from
  this software without specific prior written permission
* Neither the name of Ing.-Buero Dr. Michael Lehning nor the names of its
  contributors may be used to endorse or promote products derived from
  this software without specific prior written permission

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Last modified: 13th April 2024

Authors:
   Michael Lehning <michael.lehning@lehning.de>
   Jochen Sprickerhof <jochen@sprickerhof.de>
   Martin Günther <mguenthe@uos.de>

Definition in file sick_generic_laser.cpp.

Macro Definition Documentation

◆ _USE_MATH_DEFINES

#define _USE_MATH_DEFINES

Definition at line 89 of file sick_generic_laser.cpp.

◆ DELETE_PTR

#define DELETE_PTR (   p)    if(p){delete(p);p=0;}

Definition at line 108 of file sick_generic_laser.cpp.

◆ GITHASH_STR

#define GITHASH_STR   std::string("")

Definition at line 100 of file sick_generic_laser.cpp.

◆ GITINFO_STR

#define GITINFO_STR   std::string("")

Definition at line 105 of file sick_generic_laser.cpp.

◆ USE_LAUNCHPARSER

#define USE_LAUNCHPARSER

Definition at line 86 of file sick_generic_laser.cpp.

Function Documentation

◆ convertSendSOPASCommand()

bool convertSendSOPASCommand ( const std::string &  sopas_ascii_request,
std::string &  sopas_response,
bool  wait_for_reply 
)

Converts a given SOPAS command from ascii to binary (in case of binary communication), sends sopas (ascii or binary) and returns the response (if wait_for_reply:=true)

Parameters
[in]sopas_ascii_requestsopas command to send in ascii (converted automatically to binary if required)
[out]sopas_responsesopas response from lidar (with optional parameter in hex values)

Definition at line 233 of file sick_generic_laser.cpp.

◆ ends_with()

bool ends_with ( std::string const value,
std::string const ending 
)
inline

Definition at line 334 of file sick_generic_laser.cpp.

◆ getDiagnosticStatus()

void getDiagnosticStatus ( SICK_DIAGNOSTIC_STATUS status_code,
std::string &  status_message 
)

Definition at line 314 of file sick_generic_laser.cpp.

◆ getTagVal()

bool getTagVal ( std::string  tagVal,
std::string &  tag,
std::string &  val 
)

splitting expressions like <tag>:=into <tag> and

Parameters
[In]tagVal: string expression like <tag>:=
[Out]tag: Tag after Parsing
[Ozt]val: Value after Parsing
Returns
Result of matching process (true: matching expression found, false: no match found)

Definition at line 170 of file sick_generic_laser.cpp.

◆ getVerboseLevel()

int32_t getVerboseLevel ( )

Definition at line 329 of file sick_generic_laser.cpp.

◆ getVersionInfo()

std::string getVersionInfo ( )

Definition at line 121 of file sick_generic_laser.cpp.

◆ joinGenericLaser()

void joinGenericLaser ( void  )

Waits until all GenericLaser jobs finished.

Definition at line 855 of file sick_generic_laser.cpp.

◆ mainGenericLaser()

int mainGenericLaser ( int  argc,
char **  argv,
std::string  nodeName,
rosNodePtr  nhPriv 
)

Internal Startup routine.

Parameters
argcNumber of Arguments
argvArgument variable
nodeNamename of the ROS-node
Returns
exit-code
See also
main

Definition at line 873 of file sick_generic_laser.cpp.

◆ mainGenericLaserInternal()

void mainGenericLaserInternal ( int  argc,
char **  argv,
std::string  nodeName,
rosNodePtr  nhPriv,
bool  do_ros_spin,
int &  exit_code 
)

Internal Startup routine.

Parameters
argcNumber of Arguments
argvArgument variable
nodeNamename of the ROS-node
nhPrivros node handle
exit_codeexit-code
See also
main

Definition at line 423 of file sick_generic_laser.cpp.

◆ parseLaunchfileSetParameter()

bool parseLaunchfileSetParameter ( rosNodePtr  nhPriv,
int  argc,
char **  argv 
)

Parses an optional launchfile and sets all parameters. This function is used at startup to enable system independant parameter handling for native Linux/Windows, ROS-1 and ROS-2. Parameter are overwritten by optional commandline arguments.

Parameters
argcNumber of commandline arguments
argvcommandline arguments
nodeNamename of the ROS-node
Returns
exit-code
See also
main

Definition at line 352 of file sick_generic_laser.cpp.

◆ rosSignalHandler()

void rosSignalHandler ( int  signalRecv)

Definition at line 211 of file sick_generic_laser.cpp.

◆ setDiagnosticStatus()

void setDiagnosticStatus ( SICK_DIAGNOSTIC_STATUS  status_code,
const std::string &  status_message 
)

Definition at line 302 of file sick_generic_laser.cpp.

◆ setVerboseLevel()

void setVerboseLevel ( int32_t  verbose_level)

Definition at line 323 of file sick_generic_laser.cpp.

◆ setVersionInfo()

void setVersionInfo ( std::string  _versionInfo)

Definition at line 116 of file sick_generic_laser.cpp.

◆ shutdownSignalReceived()

bool shutdownSignalReceived ( )

Definition at line 206 of file sick_generic_laser.cpp.

◆ SickScanApiNavOdomVelocityImpl()

int32_t SickScanApiNavOdomVelocityImpl ( SickScanApiHandle  apiHandle,
SickScanNavOdomVelocityMsg src_msg 
)

Definition at line 883 of file sick_generic_laser.cpp.

◆ SickScanApiOdomVelocityImpl()

int32_t SickScanApiOdomVelocityImpl ( SickScanApiHandle  apiHandle,
SickScanOdomVelocityMsg src_msg 
)

Definition at line 898 of file sick_generic_laser.cpp.

◆ startGenericLaser()

bool startGenericLaser ( int  argc,
char **  argv,
std::string  nodeName,
rosNodePtr  nhPriv,
int *  exit_code 
)

Runs mainGenericLaser non-blocking in a new thread.

Parameters
argcNumber of Arguments
argvArgument variable
nodeNamename of the ROS-node
nhPrivros node handle
exit_codeexit-code
Returns
true if mainGenericLaser is running, false otherwise
See also
mainGenericLaser

Definition at line 837 of file sick_generic_laser.cpp.

◆ stopScannerAndExit()

bool stopScannerAndExit ( bool  force_immediate_shutdown)

Definition at line 190 of file sick_generic_laser.cpp.

◆ vargs_to_string()

std::string vargs_to_string ( const char *const  format,
  ... 
)

Definition at line 281 of file sick_generic_laser.cpp.

Variable Documentation

◆ s_generic_laser_thread

GenericLaserCallable* s_generic_laser_thread = 0
static

Definition at line 155 of file sick_generic_laser.cpp.

◆ s_isInitialized

bool s_isInitialized = false
static

Definition at line 110 of file sick_generic_laser.cpp.

◆ s_runState

NodeRunState s_runState = scanner_init
static

Definition at line 157 of file sick_generic_laser.cpp.

◆ s_scanner

Definition at line 111 of file sick_generic_laser.cpp.

◆ s_shutdownSignalReceived

bool s_shutdownSignalReceived = false
static

Definition at line 114 of file sick_generic_laser.cpp.

◆ s_status_code

Definition at line 158 of file sick_generic_laser.cpp.

◆ s_status_message

std::string s_status_message = ""

Definition at line 159 of file sick_generic_laser.cpp.

◆ s_verbose_level

int32_t s_verbose_level = 1

Definition at line 160 of file sick_generic_laser.cpp.

◆ versionInfo

std::string versionInfo = std::string(SICK_SCAN_XD_VERSION) + GITHASH_STR + GITINFO_STR
static

Definition at line 113 of file sick_generic_laser.cpp.



sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:14