Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Private Attributes | List of all members
sick_scan::SickScanCommonTcp Class Reference

#include <sick_scan_common_tcp.h>

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

Public Member Functions

SopasEventMessage findFrameInReceiveBuffer ()
 
bool getEmulSensor ()
 get emulation flag (using emulation instead of "real" scanner - currently implemented for radar More...
 
int getReplyMode ()
 
int numberOfDatagramInInputFifo ()
 
void processFrame (ros::Time timeStamp, SopasEventMessage &frame)
 
void readCallbackFunction (UINT8 *buffer, UINT32 &numOfBytes)
 
void setEmulSensor (bool _emulFlag)
 Set emulation flag (using emulation instead of "real" scanner - currently implemented for radar. More...
 
void setReplyMode (int _mode)
 
 SickScanCommonTcp (const std::string &hostname, const std::string &port, int &timelimit, SickGenericParser *parser, char cola_dialect_id)
 
bool stopScanData ()
 
virtual ~SickScanCommonTcp ()
 
- Public Member Functions inherited from sick_scan::SickScanCommon
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...
 

Static Public Member Functions

static void disconnectFunctionS (void *obj)
 
static void readCallbackFunctionS (void *obj, UINT8 *buffer, UINT32 &numOfBytes)
 

Public Attributes

UINT32 m_alreadyReceivedBytes
 
UINT32 m_lastPacketSize
 
UINT8 m_packetBuffer [480000]
 
Queue< DatagramWithTimeStamprecvQueue
 
- Public Attributes inherited from sick_scan::SickScanCommon
sensor_msgs::PointCloud2 cloud_
 
ros::Publisher cloud_pub_
 
SickScanConfig config_
 
ros::Publisher Encoder_pub
 
ros::Publisher imuScan_pub_
 
SickScanCommonNw m_nw
 

Protected Member Functions

void checkDeadline ()
 
virtual int close_device ()
 
void disconnectFunction ()
 
virtual int get_datagram (ros::Time &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length, bool isBinaryProtocol, int *numberOfRemainingFifoEntries)
 Read a datagram from the device. More...
 
void handleRead (boost::system::error_code error, size_t bytes_transfered)
 
virtual int init_device ()
 
void readCallbackFunctionOld (UINT8 *buffer, UINT32 &numOfBytes)
 
int readWithTimeout (size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read=0, bool *exception_occured=0, bool isBinary=false)
 
virtual int sendSOPASCommand (const char *request, std::vector< unsigned char > *reply, int cmdLen)
 Send a SOPAS command to the device and print out the response to the console. More...
 
- Protected Member Functions inherited from sick_scan::SickScanCommon
int checkForBinaryAnswer (const std::vector< unsigned char > *reply)
 Check block for correct framing and starting sequence of a binary message. More...
 
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 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 stop_scanner ()
 Stops sending scan data. More...
 

Private Attributes

size_t bytes_transfered_
 
boost::asio::deadline_timer deadline_
 
boost::system::error_code ec_
 
std::string hostname_
 
boost::asio::streambuf input_buffer_
 
boost::asio::io_service io_service_
 
bool m_beVerbose
 
bool m_emulSensor
 
UINT32 m_numberOfBytesInReceiveBuffer
 Number of bytes in buffer. More...
 
UINT32 m_numberOfBytesInResponseBuffer
 Number of bytes in buffer. More...
 
UINT8 m_receiveBuffer [480000]
 Low-Level receive buffer for all data. More...
 
Mutex m_receiveDataMutex
 Access mutex for buffer. More...
 
int m_replyMode
 
UINT8 m_responseBuffer [1024]
 Receive buffer for everything except scan data and eval case data. More...
 
std::string port_
 
boost::asio::ip::tcp::socket socket_
 
int timelimit_
 

Additional Inherited Members

- Public Types inherited from sick_scan::SickScanCommon
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
}
 
- Protected Attributes inherited from sick_scan::SickScanCommon
diagnostic_updater::Updater diagnostics_
 

Detailed Description

Definition at line 68 of file sick_scan_common_tcp.h.

Constructor & Destructor Documentation

◆ SickScanCommonTcp()

sick_scan::SickScanCommonTcp::SickScanCommonTcp ( const std::string &  hostname,
const std::string &  port,
int &  timelimit,
SickGenericParser parser,
char  cola_dialect_id 
)

Definition at line 171 of file sick_scan_common_tcp.cpp.

◆ ~SickScanCommonTcp()

sick_scan::SickScanCommonTcp::~SickScanCommonTcp ( )
virtual

Definition at line 208 of file sick_scan_common_tcp.cpp.

Member Function Documentation

◆ checkDeadline()

void sick_scan::SickScanCommonTcp::checkDeadline ( )
protected

Definition at line 602 of file sick_scan_common_tcp.cpp.

◆ close_device()

int sick_scan::SickScanCommonTcp::close_device ( )
protectedvirtual

Implements sick_scan::SickScanCommon.

Definition at line 581 of file sick_scan_common_tcp.cpp.

◆ disconnectFunction()

void sick_scan::SickScanCommonTcp::disconnectFunction ( )
protected

Read callback. Diese Funktion wird aufgerufen, sobald Daten auf der Schnittstelle hereingekommen sind.

Definition at line 219 of file sick_scan_common_tcp.cpp.

◆ disconnectFunctionS()

void sick_scan::SickScanCommonTcp::disconnectFunctionS ( void *  obj)
static

Definition at line 224 of file sick_scan_common_tcp.cpp.

◆ findFrameInReceiveBuffer()

SopasEventMessage sick_scan::SickScanCommonTcp::findFrameInReceiveBuffer ( )

Definition at line 289 of file sick_scan_common_tcp.cpp.

◆ get_datagram()

int sick_scan::SickScanCommonTcp::get_datagram ( ros::Time recvTimeStamp,
unsigned char *  receiveBuffer,
int  bufferSize,
int *  actual_length,
bool  isBinaryProtocol,
int *  numberOfRemainingFifoEntries 
)
protectedvirtual

Read a datagram from the device.

Parameters
[out]recvTimeStamptimestamp of received datagram
[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]isBinaryProtocoltrue=binary False=ASCII

Implements sick_scan::SickScanCommon.

Definition at line 783 of file sick_scan_common_tcp.cpp.

◆ getEmulSensor()

bool sick_scan::SickScanCommonTcp::getEmulSensor ( )

get emulation flag (using emulation instead of "real" scanner - currently implemented for radar

Parameters

Definition at line 277 of file sick_scan_common_tcp.cpp.

◆ getReplyMode()

int sick_scan::SickScanCommonTcp::getReplyMode ( )

Definition at line 243 of file sick_scan_common_tcp.cpp.

◆ handleRead()

void sick_scan::SickScanCommonTcp::handleRead ( boost::system::error_code  error,
size_t  bytes_transfered 
)
protected

Definition at line 595 of file sick_scan_common_tcp.cpp.

◆ init_device()

int sick_scan::SickScanCommonTcp::init_device ( )
protectedvirtual

Implements sick_scan::SickScanCommon.

Definition at line 564 of file sick_scan_common_tcp.cpp.

◆ numberOfDatagramInInputFifo()

int sick_scan::SickScanCommonTcp::numberOfDatagramInInputFifo ( )

Definition at line 617 of file sick_scan_common_tcp.cpp.

◆ processFrame()

void sick_scan::SickScanCommonTcp::processFrame ( ros::Time  timeStamp,
SopasEventMessage frame 
)

Read callback. Diese Funktion wird aufgerufen, sobald Daten auf der Schnittstelle hereingekommen sind.

Definition at line 466 of file sick_scan_common_tcp.cpp.

◆ readCallbackFunction()

void sick_scan::SickScanCommonTcp::readCallbackFunction ( UINT8 buffer,
UINT32 numOfBytes 
)

Definition at line 493 of file sick_scan_common_tcp.cpp.

◆ readCallbackFunctionOld()

void sick_scan::SickScanCommonTcp::readCallbackFunctionOld ( UINT8 buffer,
UINT32 numOfBytes 
)
protected

◆ readCallbackFunctionS()

void sick_scan::SickScanCommonTcp::readCallbackFunctionS ( void *  obj,
UINT8 buffer,
UINT32 numOfBytes 
)
static

Definition at line 232 of file sick_scan_common_tcp.cpp.

◆ readWithTimeout()

int sick_scan::SickScanCommonTcp::readWithTimeout ( size_t  timeout_ms,
char *  buffer,
int  buffer_size,
int *  bytes_read = 0,
bool *  exception_occured = 0,
bool  isBinary = false 
)
protected

Definition at line 624 of file sick_scan_common_tcp.cpp.

◆ sendSOPASCommand()

int sick_scan::SickScanCommonTcp::sendSOPASCommand ( const char *  request,
std::vector< unsigned char > *  reply,
int  cmdLen 
)
protectedvirtual

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

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

Implements sick_scan::SickScanCommon.

Definition at line 664 of file sick_scan_common_tcp.cpp.

◆ setEmulSensor()

void sick_scan::SickScanCommonTcp::setEmulSensor ( bool  _emulFlag)

Set emulation flag (using emulation instead of "real" scanner - currently implemented for radar.

Parameters
_emulFlagFlag to switch emulation on or off
Returns

Definition at line 267 of file sick_scan_common_tcp.cpp.

◆ setReplyMode()

void sick_scan::SickScanCommonTcp::setReplyMode ( int  _mode)

Definition at line 238 of file sick_scan_common_tcp.cpp.

◆ stopScanData()

bool sick_scan::SickScanCommonTcp::stopScanData ( )

Definition at line 589 of file sick_scan_common_tcp.cpp.

Member Data Documentation

◆ bytes_transfered_

size_t sick_scan::SickScanCommonTcp::bytes_transfered_
private

Definition at line 160 of file sick_scan_common_tcp.h.

◆ deadline_

boost::asio::deadline_timer sick_scan::SickScanCommonTcp::deadline_
private

Definition at line 157 of file sick_scan_common_tcp.h.

◆ ec_

boost::system::error_code sick_scan::SickScanCommonTcp::ec_
private

Definition at line 159 of file sick_scan_common_tcp.h.

◆ hostname_

std::string sick_scan::SickScanCommonTcp::hostname_
private

Definition at line 162 of file sick_scan_common_tcp.h.

◆ input_buffer_

boost::asio::streambuf sick_scan::SickScanCommonTcp::input_buffer_
private

Definition at line 158 of file sick_scan_common_tcp.h.

◆ io_service_

boost::asio::io_service sick_scan::SickScanCommonTcp::io_service_
private

Definition at line 155 of file sick_scan_common_tcp.h.

◆ m_alreadyReceivedBytes

UINT32 sick_scan::SickScanCommonTcp::m_alreadyReceivedBytes

Definition at line 100 of file sick_scan_common_tcp.h.

◆ m_beVerbose

bool sick_scan::SickScanCommonTcp::m_beVerbose
private

Definition at line 152 of file sick_scan_common_tcp.h.

◆ m_emulSensor

bool sick_scan::SickScanCommonTcp::m_emulSensor
private

Definition at line 153 of file sick_scan_common_tcp.h.

◆ m_lastPacketSize

UINT32 sick_scan::SickScanCommonTcp::m_lastPacketSize

Definition at line 101 of file sick_scan_common_tcp.h.

◆ m_numberOfBytesInReceiveBuffer

UINT32 sick_scan::SickScanCommonTcp::m_numberOfBytesInReceiveBuffer
private

Number of bytes in buffer.

Definition at line 149 of file sick_scan_common_tcp.h.

◆ m_numberOfBytesInResponseBuffer

UINT32 sick_scan::SickScanCommonTcp::m_numberOfBytesInResponseBuffer
private

Number of bytes in buffer.

Definition at line 144 of file sick_scan_common_tcp.h.

◆ m_packetBuffer

UINT8 sick_scan::SickScanCommonTcp::m_packetBuffer[480000]

Definition at line 102 of file sick_scan_common_tcp.h.

◆ m_receiveBuffer

UINT8 sick_scan::SickScanCommonTcp::m_receiveBuffer[480000]
private

Low-Level receive buffer for all data.

Definition at line 150 of file sick_scan_common_tcp.h.

◆ m_receiveDataMutex

Mutex sick_scan::SickScanCommonTcp::m_receiveDataMutex
private

Access mutex for buffer.

Definition at line 146 of file sick_scan_common_tcp.h.

◆ m_replyMode

int sick_scan::SickScanCommonTcp::m_replyMode
private

Definition at line 165 of file sick_scan_common_tcp.h.

◆ m_responseBuffer

UINT8 sick_scan::SickScanCommonTcp::m_responseBuffer[1024]
private

Receive buffer for everything except scan data and eval case data.

Definition at line 145 of file sick_scan_common_tcp.h.

◆ port_

std::string sick_scan::SickScanCommonTcp::port_
private

Definition at line 163 of file sick_scan_common_tcp.h.

◆ recvQueue

Queue<DatagramWithTimeStamp> sick_scan::SickScanCommonTcp::recvQueue

Definition at line 99 of file sick_scan_common_tcp.h.

◆ socket_

boost::asio::ip::tcp::socket sick_scan::SickScanCommonTcp::socket_
private

Definition at line 156 of file sick_scan_common_tcp.h.

◆ timelimit_

int sick_scan::SickScanCommonTcp::timelimit_
private

Definition at line 164 of file sick_scan_common_tcp.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 Wed Sep 7 2022 02:25:06