Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
sick_scan::SickScanCommon Class Referenceabstract

#include <sick_scan_common.h>

Inheritance diagram for sick_scan::SickScanCommon:
Inheritance graph
[legend]

Public Types

enum  SOPAS_CMD {
  CMD_DEVICE_IDENT_LEGACY, CMD_DEVICE_IDENT, CMD_SERIAL_NUMBER, CMD_REBOOT,
  CMD_WRITE_EEPROM, CMD_FIRMWARE_VERSION, CMD_DEVICE_STATE, CMD_OPERATION_HOURS,
  CMD_POWER_ON_COUNT, CMD_LOCATION_NAME, CMD_ACTIVATE_STANDBY, CMD_SET_PARTICLE_FILTER,
  CMD_SET_MEAN_FILTER, CMD_ALIGNMENT_MODE, CMD_APPLICATION_MODE, CMD_APPLICATION_MODE_FIELD_ON,
  CMD_APPLICATION_MODE_FIELD_OFF, CMD_APPLICATION_MODE_RANGING_ON, CMD_SET_ACCESS_MODE_3, CMD_SET_ACCESS_MODE_3_SAFETY_SCANNER,
  CMD_SET_OUTPUT_RANGES, CMD_SET_OUTPUT_RANGES_NAV3, CMD_GET_OUTPUT_RANGES, CMD_RUN,
  CMD_SET_PARTIAL_SCAN_CFG, CMD_GET_PARTIAL_SCAN_CFG, CMD_GET_PARTIAL_SCANDATA_CFG, CMD_SET_PARTIAL_SCANDATA_CFG,
  CMD_STOP_SCANDATA, CMD_START_SCANDATA, CMD_START_RADARDATA, CMD_ACTIVATE_NTP_CLIENT,
  CMD_SET_NTP_INTERFACE_ETH, CMD_SET_ENCODER_MODE, CMD_SET_ENCODER_MODE_NO, CMD_SET_ENCODER_MODE_SI,
  CMD_SET_ENCODER_MODE_DP, CMD_SET_ENCODER_MODE_DL, CMD_SET_INCREMENTSOURCE_ENC, CMD_SET_3_4_TO_ENCODER,
  CMD_SET_ENOCDER_RES_1, CMD_SET_ENCODER_RES, CMD_START_IMU_DATA, CMD_STOP_IMU_DATA,
  CMD_SET_TRANSMIT_RAWTARGETS_ON, CMD_SET_TRANSMIT_RAWTARGETS_OFF, CMD_SET_TRANSMIT_OBJECTS_ON, CMD_SET_TRANSMIT_OBJECTS_OFF,
  CMD_SET_TRACKING_MODE_0, CMD_SET_TRACKING_MODE_1, CMD_LOAD_APPLICATION_DEFAULT, CMD_DEVICE_TYPE,
  CMD_ORDER_NUMBER, CMD_START_MEASUREMENT, CMD_STOP_MEASUREMENT, CMD_SET_ECHO_FILTER,
  CMD_SET_NTP_UPDATETIME, CMD_SET_NTP_TIMEZONE, CMD_SET_IP_ADDR, CMD_SET_GATEWAY,
  CMD_SET_NTP_SERVER_IP_ADDR, CMD_SET_SCANDATACONFIGNAV, CMD_GET_ANGLE_COMPENSATION_PARAM, CMD_SET_TO_COLA_A_PROTOCOL,
  CMD_SET_TO_COLA_B_PROTOCOL, CMD_GET_SAFTY_FIELD_CFG, CMD_SET_LFEREC_ACTIVE, CMD_SET_LID_OUTPUTSTATE_ACTIVE,
  CMD_SET_LID_INPUTSTATE_ACTIVE, CMD_END
}
 

Public Member Functions

int ActivateStandBy (void)
 
bool changeIPandreboot (boost::asio::ip::address_v4 IpAdress)
 Send a SOPAS command to the scanner that logs in the authorized client, changes the ip adress and the reboots the scanner. More...
 
void check_angle_range (SickScanConfig &conf)
 check angle setting in the config and adjust the min_ang to the max_ang if min_ang greater than max_ax More...
 
int convertAscii2BinaryCmd (const char *requestAscii, std::vector< unsigned char > *requestBinary)
 Convert ASCII-message to Binary-message. More...
 
std::string generateExpectedAnswerString (const std::vector< unsigned char > requestStr)
 Generate expected answer string from the command string. More...
 
double get_expected_frequency () const
 
SickScanConfig * getConfigPtr ()
 
int getProtocolType (void)
 get protocol type as enum More...
 
int getReadTimeOutInMs ()
 get timeout in milliseconds More...
 
virtual int init ()
 init routine of scanner More...
 
int init_cmdTables ()
 init command tables and define startup sequence More...
 
int loopOnce ()
 parsing datagram and publishing ros messages More...
 
virtual bool rebootScanner ()
 Send a SOPAS command to the scanner that should cause a soft reset. More...
 
int sendSopasAndCheckAnswer (std::string request, std::vector< unsigned char > *reply, int cmdId)
 send command and check answer More...
 
int sendSopasAndCheckAnswer (std::vector< unsigned char > request, std::vector< unsigned char > *reply, int cmdId)
 send command and check answer More...
 
int setAligmentMode (int _AligmentMode)
 
int setApplicationMode (bool _active, int _mode)
 
int setMeanFilter (bool _active, int _numberOfScans)
 
int setParticleFilter (bool _active, int _particleThreshold)
 
void setProtocolType (SopasProtocol cola_dialect_id)
 set protocol type as enum More...
 
void setReadTimeOutInMs (int timeOutInMs)
 set timeout in milliseconds More...
 
 SickScanCommon (SickGenericParser *parser)
 Construction of SickScanCommon. More...
 
std::string sopasReplyToString (const std::vector< unsigned char > &reply)
 Converts reply from sendSOPASCommand to string. More...
 
bool testsetActivateStandBy ()
 
bool testsetAligmentMode ()
 
bool testsetApplicationMode ()
 
bool testsetMeanFilter ()
 
bool testsetParticleFilter ()
 
bool testSettingIpAddress ()
 
void update_config (sick_scan::SickScanConfig &new_config, uint32_t level=0)
 updating configuration More...
 
virtual ~SickScanCommon ()
 Destructor of SickScanCommon. More...
 

Public Attributes

sensor_msgs::PointCloud2 cloud_
 
ros::Publisher cloud_pub_
 
SickScanConfig config_
 
ros::Publisher Encoder_pub
 
ros::Publisher imuScan_pub_
 
SickScanCommonNw m_nw
 

Protected Member Functions

int checkForBinaryAnswer (const std::vector< unsigned char > *reply)
 Check block for correct framing and starting sequence of a binary message. More...
 
virtual int close_device ()=0
 
unsigned long convertBigEndianCharArrayToUnsignedLong (const unsigned char *vecArr)
 Convert little endian to big endian (should be replaced by swap-routine) More...
 
bool dumpDatagramForDebugging (unsigned char *buffer, int bufLen)
 
virtual int get_datagram (ros::Time &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length, bool isBinaryProtocol, int *numberOfRemainingFifoEntries)=0
 Read a datagram from the device. More...
 
virtual int init_device ()=0
 
virtual int init_scanner ()
 initialize scanner More...
 
bool isCompatibleDevice (const std::string identStr) const
 check the identification string More...
 
std::string replyToString (const std::vector< unsigned char > &reply)
 Converts reply from sendSOPASCommand to string. More...
 
virtual int sendSOPASCommand (const char *request, std::vector< unsigned char > *reply, int cmdLen=-1)=0
 Send a SOPAS command to the device and print out the response to the console. More...
 
virtual int stop_scanner ()
 Stops sending scan data. More...
 

Protected Attributes

diagnostic_updater::Updater diagnostics_
 

Private Member Functions

bool checkForProtocolChangeAndMaybeReconnect (bool &useBinaryCmdNow)
 checks the current protocol type and gives information about necessary change More...
 
bool getSensorIsRadar (void)
 
bool setNewIpAddress (boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
 
bool setNTPServerAndStart (boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
 
void setSensorIsRadar (bool _isRadar)
 

Private Attributes

AngleCompensatorangleCompensator = NULL
 
SickScanMarkercloud_marker_
 
ros::Publisher datagram_pub_
 
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * diagnosticPub_
 
dynamic_reconfigure::Server< sick_scan::SickScanConfig > dynamic_reconfigure_server_
 
double expectedFrequency_
 
ros::Publisher lferec_pub_
 
ros::Publisher lidoutputstate_pub_
 
double m_min_intensity
 
SopasProtocol m_protocolId
 
ros::NodeHandle nh_
 
int outputChannelFlagId
 
SickGenericParserparser_
 
ros::Publisher pub_
 
bool publish_datagram_
 
bool publish_lferec_
 
bool publish_lidoutputstate_
 
int readTimeOutInMs
 
bool sensorIsRadar
 
std::vector< int > sopasCmdChain
 
std::vector< std::string > sopasCmdErrMsg
 
std::vector< std::string > sopasCmdMaskVec
 
std::vector< std::string > sopasCmdVec
 
std::vector< std::vector< unsigned char > > sopasReplyBinVec
 
std::vector< std::string > sopasReplyStrVec
 
std::vector< std::string > sopasReplyVec
 
std::mutex sopasSendMutex
 

Detailed Description

Definition at line 86 of file sick_scan_common.h.

Member Enumeration Documentation

◆ SOPAS_CMD

Enumerator
CMD_DEVICE_IDENT_LEGACY 
CMD_DEVICE_IDENT 
CMD_SERIAL_NUMBER 
CMD_REBOOT 
CMD_WRITE_EEPROM 
CMD_FIRMWARE_VERSION 
CMD_DEVICE_STATE 
CMD_OPERATION_HOURS 
CMD_POWER_ON_COUNT 
CMD_LOCATION_NAME 
CMD_ACTIVATE_STANDBY 
CMD_SET_PARTICLE_FILTER 
CMD_SET_MEAN_FILTER 
CMD_ALIGNMENT_MODE 
CMD_APPLICATION_MODE 
CMD_APPLICATION_MODE_FIELD_ON 
CMD_APPLICATION_MODE_FIELD_OFF 
CMD_APPLICATION_MODE_RANGING_ON 
CMD_SET_ACCESS_MODE_3 
CMD_SET_ACCESS_MODE_3_SAFETY_SCANNER 
CMD_SET_OUTPUT_RANGES 
CMD_SET_OUTPUT_RANGES_NAV3 
CMD_GET_OUTPUT_RANGES 
CMD_RUN 
CMD_SET_PARTIAL_SCAN_CFG 
CMD_GET_PARTIAL_SCAN_CFG 
CMD_GET_PARTIAL_SCANDATA_CFG 
CMD_SET_PARTIAL_SCANDATA_CFG 
CMD_STOP_SCANDATA 
CMD_START_SCANDATA 
CMD_START_RADARDATA 
CMD_ACTIVATE_NTP_CLIENT 
CMD_SET_NTP_INTERFACE_ETH 
CMD_SET_ENCODER_MODE 
CMD_SET_ENCODER_MODE_NO 
CMD_SET_ENCODER_MODE_SI 
CMD_SET_ENCODER_MODE_DP 
CMD_SET_ENCODER_MODE_DL 
CMD_SET_INCREMENTSOURCE_ENC 
CMD_SET_3_4_TO_ENCODER 
CMD_SET_ENOCDER_RES_1 
CMD_SET_ENCODER_RES 
CMD_START_IMU_DATA 
CMD_STOP_IMU_DATA 
CMD_SET_TRANSMIT_RAWTARGETS_ON 
CMD_SET_TRANSMIT_RAWTARGETS_OFF 
CMD_SET_TRANSMIT_OBJECTS_ON 
CMD_SET_TRANSMIT_OBJECTS_OFF 
CMD_SET_TRACKING_MODE_0 
CMD_SET_TRACKING_MODE_1 
CMD_LOAD_APPLICATION_DEFAULT 
CMD_DEVICE_TYPE 
CMD_ORDER_NUMBER 
CMD_START_MEASUREMENT 
CMD_STOP_MEASUREMENT 
CMD_SET_ECHO_FILTER 
CMD_SET_NTP_UPDATETIME 
CMD_SET_NTP_TIMEZONE 
CMD_SET_IP_ADDR 
CMD_SET_GATEWAY 
CMD_SET_NTP_SERVER_IP_ADDR 
CMD_SET_SCANDATACONFIGNAV 
CMD_GET_ANGLE_COMPENSATION_PARAM 
CMD_SET_TO_COLA_A_PROTOCOL 
CMD_SET_TO_COLA_B_PROTOCOL 
CMD_GET_SAFTY_FIELD_CFG 
CMD_SET_LFEREC_ACTIVE 
CMD_SET_LID_OUTPUTSTATE_ACTIVE 
CMD_SET_LID_INPUTSTATE_ACTIVE 
CMD_END 

Definition at line 89 of file sick_scan_common.h.

Constructor & Destructor Documentation

◆ SickScanCommon()

sick_scan::SickScanCommon::SickScanCommon ( SickGenericParser parser)

Construction of SickScanCommon.

Parameters
parserCorresponding parser holding specific scanner parameter

Definition at line 335 of file sick_scan_common.cpp.

◆ ~SickScanCommon()

sick_scan::SickScanCommon::~SickScanCommon ( )
virtual

Destructor of SickScanCommon.

Definition at line 570 of file sick_scan_common.cpp.

Member Function Documentation

◆ ActivateStandBy()

int sick_scan::SickScanCommon::ActivateStandBy ( void  )

◆ changeIPandreboot()

bool sick_scan::SickScanCommon::changeIPandreboot ( boost::asio::ip::address_v4  IpAdress)

Send a SOPAS command to the scanner that logs in the authorized client, changes the ip adress and the reboots the scanner.

Parameters
IpAdressnew IP adress
Returns
true if ip was changed and scanner is rebooting

◆ check_angle_range()

void sick_scan::SickScanCommon::check_angle_range ( SickScanConfig &  conf)

check angle setting in the config and adjust the min_ang to the max_ang if min_ang greater than max_ax

Definition at line 4088 of file sick_scan_common.cpp.

◆ checkForBinaryAnswer()

int sick_scan::SickScanCommon::checkForBinaryAnswer ( const std::vector< unsigned char > *  reply)
protected

Check block for correct framing and starting sequence of a binary message.

Parameters
[in]replycheck reply whether is SOPAS-ASCII or SOPAS-Binary
Returns
-1 if ascii otherwise the length of data content following offset 8
Parameters
replyPointer to datablock
Returns
length of message (-1 if message format is not correct)

Definition at line 481 of file sick_scan_common.cpp.

◆ checkForProtocolChangeAndMaybeReconnect()

bool sick_scan::SickScanCommon::checkForProtocolChangeAndMaybeReconnect ( bool &  useBinaryCmdNow)
private

checks the current protocol type and gives information about necessary change

Parameters
useBinaryCmdNowInput/Output: Holds information about current protocol
Returns
true, if protocol type is already the right one

Definition at line 4499 of file sick_scan_common.cpp.

◆ close_device()

virtual int sick_scan::SickScanCommon::close_device ( )
protectedpure virtual

◆ convertAscii2BinaryCmd()

int sick_scan::SickScanCommon::convertAscii2BinaryCmd ( const char *  requestAscii,
std::vector< unsigned char > *  requestBinary 
)

Convert ASCII-message to Binary-message.

Parameters
requestAsciiholds ASCII-encoded command
requestBinaryhold binary command as vector of unsigned char
Returns
success = 0

Definition at line 4114 of file sick_scan_common.cpp.

◆ convertBigEndianCharArrayToUnsignedLong()

unsigned long sick_scan::SickScanCommon::convertBigEndianCharArrayToUnsignedLong ( const unsigned char *  vecArr)
protected

Convert little endian to big endian (should be replaced by swap-routine)

Parameters
[in]*vecArrto (unsigned) char buffer in big endian byte oder (MSB first)
Returns
unsigned long value as interpretation of big endian long value
Parameters
*vecArrPointer to 4 byte block
Returns
swapped 4-byte-value as long

Definition at line 464 of file sick_scan_common.cpp.

◆ dumpDatagramForDebugging()

bool sick_scan::SickScanCommon::dumpDatagramForDebugging ( unsigned char *  buffer,
int  bufLen 
)
protected

Definition at line 2683 of file sick_scan_common.cpp.

◆ generateExpectedAnswerString()

std::string sick_scan::SickScanCommon::generateExpectedAnswerString ( const std::vector< unsigned char >  requestStr)

Generate expected answer string from the command string.

Changes the Identifier of a commandstr. to its expected answer counterpart

Parameters
requestStrsent request string
Returns
Expected answer
Parameters
requestStrcommand string (either as ASCII or BINARY)
Returns
expected answer string

Map that defines expected answer identifiers

Definition at line 584 of file sick_scan_common.cpp.

◆ get_datagram()

virtual int sick_scan::SickScanCommon::get_datagram ( ros::Time recvTimeStamp,
unsigned char *  receiveBuffer,
int  bufferSize,
int *  actual_length,
bool  isBinaryProtocol,
int *  numberOfRemainingFifoEntries 
)
protectedpure virtual

Read a datagram from the device.

Parameters
[out]recvTimeStamptimestamp of received packet
[in]receiveBufferdata buffer to fill
[in]bufferSizemax data size to write to buffer (result should be 0 terminated)
[out]actual_lengththe actual amount of data written
[in]isBinaryProtocolused Communication protocol True=Binary false=ASCII

Implemented in sick_scan::SickScanCommonTcp.

◆ get_expected_frequency()

double sick_scan::SickScanCommon::get_expected_frequency ( ) const
inline

Definition at line 233 of file sick_scan_common.h.

◆ getConfigPtr()

SickScanConfig* sick_scan::SickScanCommon::getConfigPtr ( )
inline

Definition at line 255 of file sick_scan_common.h.

◆ getProtocolType()

int sick_scan::SickScanCommon::getProtocolType ( void  )

get protocol type as enum

Returns
enum type of type SopasProtocol
See also
setProtocolType

Definition at line 819 of file sick_scan_common.cpp.

◆ getReadTimeOutInMs()

int sick_scan::SickScanCommon::getReadTimeOutInMs ( )

get timeout in milliseconds

Returns
timeout in milliseconds
See also
setReadTimeOutInMs

Definition at line 809 of file sick_scan_common.cpp.

◆ getSensorIsRadar()

bool sick_scan::SickScanCommon::getSensorIsRadar ( void  )
private

Definition at line 4657 of file sick_scan_common.cpp.

◆ init()

int sick_scan::SickScanCommon::init ( )
virtual

init routine of scanner

Returns
exit code

Definition at line 837 of file sick_scan_common.cpp.

◆ init_cmdTables()

int sick_scan::SickScanCommon::init_cmdTables ( )

init command tables and define startup sequence

Returns
exit code

Definition at line 865 of file sick_scan_common.cpp.

◆ init_device()

virtual int sick_scan::SickScanCommon::init_device ( )
protectedpure virtual

◆ init_scanner()

int sick_scan::SickScanCommon::init_scanner ( )
protectedvirtual

initialize scanner

Returns
exit code

Definition at line 1163 of file sick_scan_common.cpp.

◆ isCompatibleDevice()

bool sick_scan::SickScanCommon::isCompatibleDevice ( const std::string  identStr) const
protected

check the identification string

Parameters
identStrstring (got from sopas request)
Returns
true, if this driver supports the scanner identified by the identification string

Definition at line 2722 of file sick_scan_common.cpp.

◆ loopOnce()

int sick_scan::SickScanCommon::loopOnce ( )

parsing datagram and publishing ros messages

Returns
error code

Definition at line 2802 of file sick_scan_common.cpp.

◆ rebootScanner()

bool sick_scan::SickScanCommon::rebootScanner ( )
virtual

Send a SOPAS command to the scanner that should cause a soft reset.

Reboot scanner (todo: this does not work if the scanner is set to binary mode) Fix me!

Returns
true if reboot command was accepted, false otherwise
Result of rebooting attempt

Definition at line 518 of file sick_scan_common.cpp.

◆ replyToString()

std::string sick_scan::SickScanCommon::replyToString ( const std::vector< unsigned char > &  reply)
protected

Converts reply from sendSOPASCommand to string.

convert ASCII or binary reply to a human readable string

Parameters
[in]replyreply from sendSOPASCommand
Returns
reply as string with special characters stripped out
Parameters
replydatablock, which should be converted
Returns
human readable string (used for debug/monitoring output)

Definition at line 2640 of file sick_scan_common.cpp.

◆ sendSopasAndCheckAnswer() [1/2]

int sick_scan::SickScanCommon::sendSopasAndCheckAnswer ( std::string  requestStr,
std::vector< unsigned char > *  reply,
int  cmdId = -1 
)

send command and check answer

Parameters
requestStrSopas-Command
*replyAntwort-String
cmdIdCommand index to derive the correct error message (optional)
Returns
error code

Definition at line 704 of file sick_scan_common.cpp.

◆ sendSopasAndCheckAnswer() [2/2]

int sick_scan::SickScanCommon::sendSopasAndCheckAnswer ( std::vector< unsigned char >  requestStr,
std::vector< unsigned char > *  reply,
int  cmdId = -1 
)

send command and check answer

Parameters
requestStrSopas-Command given as byte-vector
*replyAntwort-String
cmdIdCommand index to derive the correct error message (optional)
Returns
error code

Definition at line 722 of file sick_scan_common.cpp.

◆ sendSOPASCommand()

virtual int sick_scan::SickScanCommon::sendSOPASCommand ( const char *  request,
std::vector< unsigned char > *  reply,
int  cmdLen = -1 
)
protectedpure virtual

Send a SOPAS command to the device and print out the response to the console.

Parameters
[in]requestthe command to send.
[out]replyif not NULL, will be filled with the reply package to the command.
[in]cmdLenLength of the Comandstring in bytes used for Binary Mode only

Implemented in sick_scan::SickScanCommonTcp.

◆ setAligmentMode()

int sick_scan::SickScanCommon::setAligmentMode ( int  _AligmentMode)

◆ setApplicationMode()

int sick_scan::SickScanCommon::setApplicationMode ( bool  _active,
int  _mode 
)

◆ setMeanFilter()

int sick_scan::SickScanCommon::setMeanFilter ( bool  _active,
int  _numberOfScans 
)

◆ setNewIpAddress()

bool sick_scan::SickScanCommon::setNewIpAddress ( boost::asio::ip::address_v4  ipNewIPAddr,
bool  useBinaryCmd 
)
private

Definition at line 4535 of file sick_scan_common.cpp.

◆ setNTPServerAndStart()

bool sick_scan::SickScanCommon::setNTPServerAndStart ( boost::asio::ip::address_v4  ipNewIPAddr,
bool  useBinaryCmd 
)
private

Definition at line 4593 of file sick_scan_common.cpp.

◆ setParticleFilter()

int sick_scan::SickScanCommon::setParticleFilter ( bool  _active,
int  _particleThreshold 
)

◆ setProtocolType()

void sick_scan::SickScanCommon::setProtocolType ( SopasProtocol  cola_dialect_id)

set protocol type as enum

See also
getProtocolType

Definition at line 828 of file sick_scan_common.cpp.

◆ setReadTimeOutInMs()

void sick_scan::SickScanCommon::setReadTimeOutInMs ( int  timeOutInMs)

set timeout in milliseconds

Parameters
timeOutInMsin milliseconds
See also
getReadTimeOutInMs

Definition at line 799 of file sick_scan_common.cpp.

◆ setSensorIsRadar()

void sick_scan::SickScanCommon::setSensorIsRadar ( bool  _isRadar)
private

Definition at line 4652 of file sick_scan_common.cpp.

◆ sopasReplyToString()

std::string sick_scan::SickScanCommon::sopasReplyToString ( const std::vector< unsigned char > &  reply)
inline

Converts reply from sendSOPASCommand to string.

Parameters
[in]replyreply from sendSOPASCommand
Returns
reply as string with special characters stripped out

Definition at line 265 of file sick_scan_common.h.

◆ stop_scanner()

int sick_scan::SickScanCommon::stop_scanner ( )
protectedvirtual

Stops sending scan data.

Returns
error code

Definition at line 424 of file sick_scan_common.cpp.

◆ testsetActivateStandBy()

bool sick_scan::SickScanCommon::testsetActivateStandBy ( )

◆ testsetAligmentMode()

bool sick_scan::SickScanCommon::testsetAligmentMode ( )

◆ testsetApplicationMode()

bool sick_scan::SickScanCommon::testsetApplicationMode ( )

◆ testsetMeanFilter()

bool sick_scan::SickScanCommon::testsetMeanFilter ( )

◆ testsetParticleFilter()

bool sick_scan::SickScanCommon::testsetParticleFilter ( )

◆ testSettingIpAddress()

bool sick_scan::SickScanCommon::testSettingIpAddress ( )

◆ update_config()

void sick_scan::SickScanCommon::update_config ( sick_scan::SickScanConfig &  new_config,
uint32_t  level = 0 
)

updating configuration

Parameters
new_configPointer to new configuration
level(not used - should be removed)

Definition at line 4102 of file sick_scan_common.cpp.

Member Data Documentation

◆ angleCompensator

AngleCompensator* sick_scan::SickScanCommon::angleCompensator = NULL
private

Definition at line 394 of file sick_scan_common.h.

◆ cloud_

sensor_msgs::PointCloud2 sick_scan::SickScanCommon::cloud_

Definition at line 279 of file sick_scan_common.h.

◆ cloud_marker_

SickScanMarker* sick_scan::SickScanCommon::cloud_marker_
private

Definition at line 355 of file sick_scan_common.h.

◆ cloud_pub_

ros::Publisher sick_scan::SickScanCommon::cloud_pub_

Definition at line 275 of file sick_scan_common.h.

◆ config_

SickScanConfig sick_scan::SickScanCommon::config_

Definition at line 282 of file sick_scan_common.h.

◆ datagram_pub_

ros::Publisher sick_scan::SickScanCommon::datagram_pub_
private

Definition at line 348 of file sick_scan_common.h.

◆ diagnosticPub_

diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan>* sick_scan::SickScanCommon::diagnosticPub_
private

Definition at line 358 of file sick_scan_common.h.

◆ diagnostics_

diagnostic_updater::Updater sick_scan::SickScanCommon::diagnostics_
protected

Definition at line 340 of file sick_scan_common.h.

◆ dynamic_reconfigure_server_

dynamic_reconfigure::Server<sick_scan::SickScanConfig> sick_scan::SickScanCommon::dynamic_reconfigure_server_
private

Definition at line 363 of file sick_scan_common.h.

◆ Encoder_pub

ros::Publisher sick_scan::SickScanCommon::Encoder_pub

Definition at line 277 of file sick_scan_common.h.

◆ expectedFrequency_

double sick_scan::SickScanCommon::expectedFrequency_
private

Definition at line 359 of file sick_scan_common.h.

◆ imuScan_pub_

ros::Publisher sick_scan::SickScanCommon::imuScan_pub_

Definition at line 276 of file sick_scan_common.h.

◆ lferec_pub_

ros::Publisher sick_scan::SickScanCommon::lferec_pub_
private

Definition at line 351 of file sick_scan_common.h.

◆ lidoutputstate_pub_

ros::Publisher sick_scan::SickScanCommon::lidoutputstate_pub_
private

Definition at line 353 of file sick_scan_common.h.

◆ m_min_intensity

double sick_scan::SickScanCommon::m_min_intensity
private

Definition at line 396 of file sick_scan_common.h.

◆ m_nw

SickScanCommonNw sick_scan::SickScanCommon::m_nw

Definition at line 253 of file sick_scan_common.h.

◆ m_protocolId

SopasProtocol sick_scan::SickScanCommon::m_protocolId
private

Definition at line 344 of file sick_scan_common.h.

◆ nh_

ros::NodeHandle sick_scan::SickScanCommon::nh_
private

Definition at line 346 of file sick_scan_common.h.

◆ outputChannelFlagId

int sick_scan::SickScanCommon::outputChannelFlagId
private

Definition at line 375 of file sick_scan_common.h.

◆ parser_

SickGenericParser* sick_scan::SickScanCommon::parser_
private

Definition at line 366 of file sick_scan_common.h.

◆ pub_

ros::Publisher sick_scan::SickScanCommon::pub_
private

Definition at line 347 of file sick_scan_common.h.

◆ publish_datagram_

bool sick_scan::SickScanCommon::publish_datagram_
private

Definition at line 349 of file sick_scan_common.h.

◆ publish_lferec_

bool sick_scan::SickScanCommon::publish_lferec_
private

Definition at line 352 of file sick_scan_common.h.

◆ publish_lidoutputstate_

bool sick_scan::SickScanCommon::publish_lidoutputstate_
private

Definition at line 354 of file sick_scan_common.h.

◆ readTimeOutInMs

int sick_scan::SickScanCommon::readTimeOutInMs
private

Definition at line 387 of file sick_scan_common.h.

◆ sensorIsRadar

bool sick_scan::SickScanCommon::sensorIsRadar
private

Definition at line 392 of file sick_scan_common.h.

◆ sopasCmdChain

std::vector<int> sick_scan::SickScanCommon::sopasCmdChain
private

Definition at line 373 of file sick_scan_common.h.

◆ sopasCmdErrMsg

std::vector<std::string> sick_scan::SickScanCommon::sopasCmdErrMsg
private

Definition at line 372 of file sick_scan_common.h.

◆ sopasCmdMaskVec

std::vector<std::string> sick_scan::SickScanCommon::sopasCmdMaskVec
private

Definition at line 368 of file sick_scan_common.h.

◆ sopasCmdVec

std::vector<std::string> sick_scan::SickScanCommon::sopasCmdVec
private

Definition at line 367 of file sick_scan_common.h.

◆ sopasReplyBinVec

std::vector<std::vector<unsigned char> > sick_scan::SickScanCommon::sopasReplyBinVec
private

Definition at line 370 of file sick_scan_common.h.

◆ sopasReplyStrVec

std::vector<std::string> sick_scan::SickScanCommon::sopasReplyStrVec
private

Definition at line 371 of file sick_scan_common.h.

◆ sopasReplyVec

std::vector<std::string> sick_scan::SickScanCommon::sopasReplyVec
private

Definition at line 369 of file sick_scan_common.h.

◆ sopasSendMutex

std::mutex sick_scan::SickScanCommon::sopasSendMutex
private

Definition at line 389 of file sick_scan_common.h.


The documentation for this class was generated from the following files:


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Thu Sep 8 2022 02:30:19