#include <sick_scan_common.h>
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_OUTPUT_RANGES, 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_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_TO_COLA_A_PROTOCOL, CMD_SET_TO_COLA_B_PROTOCOL, 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. | |
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 | |
int | convertAscii2BinaryCmd (const char *requestAscii, std::vector< unsigned char > *requestBinary) |
Convert ASCII-message to Binary-message. | |
std::string | generateExpectedAnswerString (const std::vector< unsigned char > requestStr) |
Generate expected answer string from the command string. | |
double | get_expected_frequency () const |
SickScanConfig * | getConfigPtr () |
int | getProtocolType (void) |
get protocol type as enum | |
int | getReadTimeOutInMs () |
get timeout in milliseconds | |
virtual int | init () |
init routine of scanner | |
int | init_cmdTables () |
init command tables and define startup sequence | |
int | loopOnce () |
parsing datagram and publishing ros messages | |
virtual bool | rebootScanner () |
Send a SOPAS command to the scanner that should cause a soft reset. | |
int | sendSopasAndCheckAnswer (std::string request, std::vector< unsigned char > *reply, int cmdId) |
send command and check answer | |
int | sendSopasAndCheckAnswer (std::vector< unsigned char > request, std::vector< unsigned char > *reply, int cmdId) |
send command and check answer | |
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 | |
void | setReadTimeOutInMs (int timeOutInMs) |
set timeout in milliseconds | |
SickScanCommon (SickGenericParser *parser) | |
Construction of SickScanCommon. | |
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 | |
virtual | ~SickScanCommon () |
Destructor of SickScanCommon. | |
Public Attributes | |
sensor_msgs::PointCloud2 | cloud_ |
ros::Publisher | cloud_pub_ |
ros::Publisher | cloud_radar_rawtarget_pub_ |
ros::Publisher | cloud_radar_track_pub_ |
SickScanConfig | config_ |
ros::Publisher | imuScan_pub_ |
SickScanCommonNw | m_nw |
ros::Publisher | radarScan_pub_ |
Protected Member Functions | |
int | checkForBinaryAnswer (const std::vector< unsigned char > *reply) |
Check block for correct framing and starting sequence of a binary message. | |
virtual int | close_device ()=0 |
unsigned long | convertBigEndianCharArrayToUnsignedLong (const unsigned char *vecArr) |
Convert little endian to big endian (should be replaced by swap-routine) | |
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. | |
virtual int | init_device ()=0 |
virtual int | init_scanner () |
initialize scanner | |
bool | isCompatibleDevice (const std::string identStr) const |
check the identification string | |
std::string | replyToString (const std::vector< unsigned char > &reply) |
Converts reply from sendSOPASCommand to string. | |
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. | |
virtual int | stop_scanner () |
Stops sending scan data. | |
Protected Attributes | |
diagnostic_updater::Updater | diagnostics_ |
Private Member Functions | |
bool | checkForProtocolChangeAndMaybeReconnect (bool &useBinaryCmdNow) |
checks the current protocol type and gives information about necessary change | |
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 | |
ros::Publisher | datagram_pub_ |
diagnostic_updater::DiagnosedPublisher < sensor_msgs::LaserScan > * | diagnosticPub_ |
dynamic_reconfigure::Server < sick_scan::SickScanConfig > | dynamic_reconfigure_server_ |
double | expectedFrequency_ |
SopasProtocol | m_protocolId |
ros::NodeHandle | nh_ |
int | outputChannelFlagId |
SickGenericParser * | parser_ |
ros::Publisher | pub_ |
bool | publish_datagram_ |
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 |
Definition at line 76 of file sick_scan_common.h.
Definition at line 79 of file sick_scan_common.h.
Construction of SickScanCommon.
parser,: | Corresponding parser holding specific scanner parameter |
Definition at line 332 of file sick_scan_common.cpp.
sick_scan::SickScanCommon::~SickScanCommon | ( | ) | [virtual] |
Destructor of SickScanCommon.
Definition at line 539 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 3457 of file sick_scan_common.cpp.
int sick_scan::SickScanCommon::checkForBinaryAnswer | ( | const std::vector< unsigned char > * | reply | ) | [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 450 of file sick_scan_common.cpp.
bool sick_scan::SickScanCommon::checkForProtocolChangeAndMaybeReconnect | ( | bool & | useBinaryCmdNow | ) | [private] |
checks the current protocol type and gives information about necessary change
useBinaryCmdNow | Input/Output: Holds information about current protocol |
Definition at line 3776 of file sick_scan_common.cpp.
virtual int sick_scan::SickScanCommon::close_device | ( | ) | [protected, pure 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 3483 of file sick_scan_common.cpp.
unsigned long sick_scan::SickScanCommon::convertBigEndianCharArrayToUnsignedLong | ( | const unsigned char * | vecArr | ) | [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 433 of file sick_scan_common.cpp.
bool sick_scan::SickScanCommon::dumpDatagramForDebugging | ( | unsigned char * | buffer, |
int | bufLen | ||
) | [protected] |
Definition at line 2261 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 552 of file sick_scan_common.cpp.
virtual int sick_scan::SickScanCommon::get_datagram | ( | ros::Time & | recvTimeStamp, |
unsigned char * | receiveBuffer, | ||
int | bufferSize, | ||
int * | actual_length, | ||
bool | isBinaryProtocol, | ||
int * | numberOfRemainingFifoEntries | ||
) | [protected, pure 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.
double sick_scan::SickScanCommon::get_expected_frequency | ( | ) | const [inline] |
Definition at line 184 of file sick_scan_common.h.
SickScanConfig* sick_scan::SickScanCommon::getConfigPtr | ( | ) | [inline] |
Definition at line 203 of file sick_scan_common.h.
int sick_scan::SickScanCommon::getProtocolType | ( | void | ) |
get protocol type as enum
Definition at line 786 of file sick_scan_common.cpp.
get timeout in milliseconds
Definition at line 776 of file sick_scan_common.cpp.
bool sick_scan::SickScanCommon::getSensorIsRadar | ( | void | ) | [private] |
Definition at line 3936 of file sick_scan_common.cpp.
int sick_scan::SickScanCommon::init | ( | ) | [virtual] |
init command tables and define startup sequence
Definition at line 831 of file sick_scan_common.cpp.
virtual int sick_scan::SickScanCommon::init_device | ( | ) | [protected, pure virtual] |
Implemented in sick_scan::SickScanCommonTcp.
int sick_scan::SickScanCommon::init_scanner | ( | ) | [protected, virtual] |
bool sick_scan::SickScanCommon::isCompatibleDevice | ( | const std::string | identStr | ) | const [protected] |
check the identification string
identStr | string (got from sopas request) |
Definition at line 2300 of file sick_scan_common.cpp.
parsing datagram and publishing ros messages
Definition at line 2380 of file sick_scan_common.cpp.
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!
Definition at line 487 of file sick_scan_common.cpp.
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
[in] | reply | reply from sendSOPASCommand |
reply | datablock, which should be converted |
Definition at line 2218 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 672 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 690 of file sick_scan_common.cpp.
virtual int sick_scan::SickScanCommon::sendSOPASCommand | ( | const char * | request, |
std::vector< unsigned char > * | reply, | ||
int | cmdLen = -1 |
||
) | [protected, pure 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 | ||
) |
bool sick_scan::SickScanCommon::setNewIpAddress | ( | boost::asio::ip::address_v4 | ipNewIPAddr, |
bool | useBinaryCmd | ||
) | [private] |
Definition at line 3812 of file sick_scan_common.cpp.
bool sick_scan::SickScanCommon::setNTPServerAndStart | ( | boost::asio::ip::address_v4 | ipNewIPAddr, |
bool | useBinaryCmd | ||
) | [private] |
Definition at line 3871 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 795 of file sick_scan_common.cpp.
void sick_scan::SickScanCommon::setReadTimeOutInMs | ( | int | timeOutInMs | ) |
set timeout in milliseconds
timeOutInMs | in milliseconds |
Definition at line 766 of file sick_scan_common.cpp.
void sick_scan::SickScanCommon::setSensorIsRadar | ( | bool | _isRadar | ) | [private] |
Definition at line 3931 of file sick_scan_common.cpp.
int sick_scan::SickScanCommon::stop_scanner | ( | ) | [protected, virtual] |
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 3471 of file sick_scan_common.cpp.
sensor_msgs::PointCloud2 sick_scan::SickScanCommon::cloud_ |
Definition at line 218 of file sick_scan_common.h.
Definition at line 212 of file sick_scan_common.h.
Definition at line 213 of file sick_scan_common.h.
Definition at line 214 of file sick_scan_common.h.
SickScanConfig sick_scan::SickScanCommon::config_ |
Definition at line 221 of file sick_scan_common.h.
Definition at line 285 of file sick_scan_common.h.
diagnostic_updater::DiagnosedPublisher<sensor_msgs::LaserScan>* sick_scan::SickScanCommon::diagnosticPub_ [private] |
Definition at line 290 of file sick_scan_common.h.
Definition at line 275 of file sick_scan_common.h.
dynamic_reconfigure::Server<sick_scan::SickScanConfig> sick_scan::SickScanCommon::dynamic_reconfigure_server_ [private] |
Definition at line 295 of file sick_scan_common.h.
double sick_scan::SickScanCommon::expectedFrequency_ [private] |
Definition at line 291 of file sick_scan_common.h.
Definition at line 216 of file sick_scan_common.h.
Definition at line 201 of file sick_scan_common.h.
Definition at line 281 of file sick_scan_common.h.
Definition at line 283 of file sick_scan_common.h.
int sick_scan::SickScanCommon::outputChannelFlagId [private] |
Definition at line 307 of file sick_scan_common.h.
Definition at line 298 of file sick_scan_common.h.
Definition at line 284 of file sick_scan_common.h.
bool sick_scan::SickScanCommon::publish_datagram_ [private] |
Definition at line 286 of file sick_scan_common.h.
Definition at line 215 of file sick_scan_common.h.
int sick_scan::SickScanCommon::readTimeOutInMs [private] |
Definition at line 314 of file sick_scan_common.h.
bool sick_scan::SickScanCommon::sensorIsRadar [private] |
Definition at line 316 of file sick_scan_common.h.
std::vector<int> sick_scan::SickScanCommon::sopasCmdChain [private] |
Definition at line 305 of file sick_scan_common.h.
std::vector<std::string> sick_scan::SickScanCommon::sopasCmdErrMsg [private] |
Definition at line 304 of file sick_scan_common.h.
std::vector<std::string> sick_scan::SickScanCommon::sopasCmdMaskVec [private] |
Definition at line 300 of file sick_scan_common.h.
std::vector<std::string> sick_scan::SickScanCommon::sopasCmdVec [private] |
Definition at line 299 of file sick_scan_common.h.
std::vector<std::vector<unsigned char> > sick_scan::SickScanCommon::sopasReplyBinVec [private] |
Definition at line 302 of file sick_scan_common.h.
std::vector<std::string> sick_scan::SickScanCommon::sopasReplyStrVec [private] |
Definition at line 303 of file sick_scan_common.h.
std::vector<std::string> sick_scan::SickScanCommon::sopasReplyVec [private] |
Definition at line 301 of file sick_scan_common.h.