#include <sick_scan_common.h>

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 | |
| AngleCompensator * | angleCompensator = NULL |
| SickScanMarker * | cloud_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_ |
| SopasProtocol | m_protocolId |
| ros::NodeHandle | nh_ |
| int | outputChannelFlagId |
| SickGenericParser * | parser_ |
| 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 |
Definition at line 86 of file sick_scan_common.h.
Definition at line 89 of file sick_scan_common.h.
| sick_scan::SickScanCommon::SickScanCommon | ( | SickGenericParser * | parser | ) |
Construction of SickScanCommon.
| parser | Corresponding parser holding specific scanner parameter |
Definition at line 335 of file sick_scan_common.cpp.
|
virtual |
Destructor of SickScanCommon.
Definition at line 569 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::ActivateStandBy | ( | void | ) |
| 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.
| IpAdress | new IP adress |
| 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 4085 of file sick_scan_common.cpp.
|
protected |
Check block for correct framing and starting sequence of a binary message.
| [in] | reply | check reply whether is SOPAS-ASCII or SOPAS-Binary |
| reply | Pointer to datablock |
Definition at line 480 of file sick_scan_common.cpp.
|
private |
checks the current protocol type and gives information about necessary change
| useBinaryCmdNow | Input/Output: Holds information about current protocol |
Definition at line 4496 of file sick_scan_common.cpp.
|
protectedpure virtual |
Implemented in sick_scan::SickScanCommonTcp.
| int sick_scan::SickScanCommon::convertAscii2BinaryCmd | ( | const char * | requestAscii, |
| std::vector< unsigned char > * | requestBinary | ||
| ) |
Convert ASCII-message to Binary-message.
| requestAscii | holds ASCII-encoded command |
| requestBinary | hold binary command as vector of unsigned char |
Definition at line 4111 of file sick_scan_common.cpp.
|
protected |
Convert little endian to big endian (should be replaced by swap-routine)
| [in] | *vecArr | to (unsigned) char buffer in big endian byte oder (MSB first) |
| *vecArr | Pointer to 4 byte block |
Definition at line 463 of file sick_scan_common.cpp.
|
protected |
Definition at line 2692 of file sick_scan_common.cpp.
| 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
| requestStr | sent request string |
| requestStr | command string (either as ASCII or BINARY) |
Map that defines expected answer identifiers
Definition at line 583 of file sick_scan_common.cpp.
|
protectedpure virtual |
Read a datagram from the device.
| [out] | recvTimeStamp | timestamp of received packet |
| [in] | receiveBuffer | data buffer to fill |
| [in] | bufferSize | max data size to write to buffer (result should be 0 terminated) |
| [out] | actual_length | the actual amount of data written |
| [in] | isBinaryProtocol | used Communication protocol True=Binary false=ASCII |
Implemented in sick_scan::SickScanCommonTcp.
|
inline |
Definition at line 233 of file sick_scan_common.h.
|
inline |
Definition at line 255 of file sick_scan_common.h.
| int sick_scan::SickScanCommon::getProtocolType | ( | void | ) |
get protocol type as enum
Definition at line 818 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::getReadTimeOutInMs | ( | ) |
get timeout in milliseconds
Definition at line 808 of file sick_scan_common.cpp.
|
private |
Definition at line 4654 of file sick_scan_common.cpp.
|
virtual |
| int sick_scan::SickScanCommon::init_cmdTables | ( | ) |
init command tables and define startup sequence
Definition at line 864 of file sick_scan_common.cpp.
|
protectedpure virtual |
Implemented in sick_scan::SickScanCommonTcp.
|
protectedvirtual |
|
protected |
check the identification string
| identStr | string (got from sopas request) |
Definition at line 2731 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::loopOnce | ( | ) |
parsing datagram and publishing ros messages
Definition at line 2811 of file sick_scan_common.cpp.
|
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!
Definition at line 517 of file sick_scan_common.cpp.
|
protected |
Converts reply from sendSOPASCommand to string.
convert ASCII or binary reply to a human readable string
| [in] | reply | reply from sendSOPASCommand |
| reply | datablock, which should be converted |
Definition at line 2649 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::sendSopasAndCheckAnswer | ( | std::string | requestStr, |
| std::vector< unsigned char > * | reply, | ||
| int | cmdId = -1 |
||
| ) |
send command and check answer
| requestStr | Sopas-Command |
| *reply | Antwort-String |
| cmdId | Command index to derive the correct error message (optional) |
Definition at line 703 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::sendSopasAndCheckAnswer | ( | std::vector< unsigned char > | requestStr, |
| std::vector< unsigned char > * | reply, | ||
| int | cmdId = -1 |
||
| ) |
send command and check answer
| requestStr | Sopas-Command given as byte-vector |
| *reply | Antwort-String |
| cmdId | Command index to derive the correct error message (optional) |
Definition at line 721 of file sick_scan_common.cpp.
|
protectedpure virtual |
Send a SOPAS command to the device and print out the response to the console.
| [in] | request | the command to send. |
| [out] | reply | if not NULL, will be filled with the reply package to the command. |
| [in] | cmdLen | Length of the Comandstring in bytes used for Binary Mode only |
Implemented in sick_scan::SickScanCommonTcp.
| int sick_scan::SickScanCommon::setAligmentMode | ( | int | _AligmentMode | ) |
| int sick_scan::SickScanCommon::setApplicationMode | ( | bool | _active, |
| int | _mode | ||
| ) |
| int sick_scan::SickScanCommon::setMeanFilter | ( | bool | _active, |
| int | _numberOfScans | ||
| ) |
|
private |
Definition at line 4532 of file sick_scan_common.cpp.
|
private |
Definition at line 4590 of file sick_scan_common.cpp.
| int sick_scan::SickScanCommon::setParticleFilter | ( | bool | _active, |
| int | _particleThreshold | ||
| ) |
| void sick_scan::SickScanCommon::setProtocolType | ( | SopasProtocol | cola_dialect_id | ) |
set protocol type as enum
Definition at line 827 of file sick_scan_common.cpp.
| void sick_scan::SickScanCommon::setReadTimeOutInMs | ( | int | timeOutInMs | ) |
set timeout in milliseconds
| timeOutInMs | in milliseconds |
Definition at line 798 of file sick_scan_common.cpp.
|
private |
Definition at line 4649 of file sick_scan_common.cpp.
|
inline |
Converts reply from sendSOPASCommand to string.
| [in] | reply | reply from sendSOPASCommand |
Definition at line 265 of file sick_scan_common.h.
|
protectedvirtual |
| bool sick_scan::SickScanCommon::testsetActivateStandBy | ( | ) |
| bool sick_scan::SickScanCommon::testsetAligmentMode | ( | ) |
| bool sick_scan::SickScanCommon::testsetApplicationMode | ( | ) |
| bool sick_scan::SickScanCommon::testsetMeanFilter | ( | ) |
| bool sick_scan::SickScanCommon::testsetParticleFilter | ( | ) |
| bool sick_scan::SickScanCommon::testSettingIpAddress | ( | ) |
| void sick_scan::SickScanCommon::update_config | ( | sick_scan::SickScanConfig & | new_config, |
| uint32_t | level = 0 |
||
| ) |
updating configuration
| new_config | Pointer to new configuration |
| level | (not used - should be removed) |
Definition at line 4099 of file sick_scan_common.cpp.
|
private |
Definition at line 394 of file sick_scan_common.h.
| sensor_msgs::PointCloud2 sick_scan::SickScanCommon::cloud_ |
Definition at line 279 of file sick_scan_common.h.
|
private |
Definition at line 355 of file sick_scan_common.h.
| ros::Publisher sick_scan::SickScanCommon::cloud_pub_ |
Definition at line 275 of file sick_scan_common.h.
| SickScanConfig sick_scan::SickScanCommon::config_ |
Definition at line 282 of file sick_scan_common.h.
|
private |
Definition at line 348 of file sick_scan_common.h.
|
private |
Definition at line 358 of file sick_scan_common.h.
|
protected |
Definition at line 340 of file sick_scan_common.h.
|
private |
Definition at line 363 of file sick_scan_common.h.
| ros::Publisher sick_scan::SickScanCommon::Encoder_pub |
Definition at line 277 of file sick_scan_common.h.
|
private |
Definition at line 359 of file sick_scan_common.h.
| ros::Publisher sick_scan::SickScanCommon::imuScan_pub_ |
Definition at line 276 of file sick_scan_common.h.
|
private |
Definition at line 351 of file sick_scan_common.h.
|
private |
Definition at line 353 of file sick_scan_common.h.
| SickScanCommonNw sick_scan::SickScanCommon::m_nw |
Definition at line 253 of file sick_scan_common.h.
|
private |
Definition at line 344 of file sick_scan_common.h.
|
private |
Definition at line 346 of file sick_scan_common.h.
|
private |
Definition at line 375 of file sick_scan_common.h.
|
private |
Definition at line 366 of file sick_scan_common.h.
|
private |
Definition at line 347 of file sick_scan_common.h.
|
private |
Definition at line 349 of file sick_scan_common.h.
|
private |
Definition at line 352 of file sick_scan_common.h.
|
private |
Definition at line 354 of file sick_scan_common.h.
|
private |
Definition at line 387 of file sick_scan_common.h.
|
private |
Definition at line 392 of file sick_scan_common.h.
|
private |
Definition at line 373 of file sick_scan_common.h.
|
private |
Definition at line 372 of file sick_scan_common.h.
|
private |
Definition at line 368 of file sick_scan_common.h.
|
private |
Definition at line 367 of file sick_scan_common.h.
|
private |
Definition at line 370 of file sick_scan_common.h.
|
private |
Definition at line 371 of file sick_scan_common.h.
|
private |
Definition at line 369 of file sick_scan_common.h.
|
private |
Definition at line 389 of file sick_scan_common.h.