51 #pragma warning(disable: 4996) 52 #pragma warning(disable: 4267) 53 #pragma warning(disable: 4101) // C4101: "e" : Unreferenzierte lokale Variable 54 #define _WIN32_WINNT 0x0501 62 #include <boost/asio.hpp> 63 #include <boost/lambda/lambda.hpp> 66 #include <boost/lexical_cast.hpp> 71 #include "sick_scan/rosconsole_simu.hpp" 84 return (diagnostic_msgs::DiagnosticStatus::ERROR);
90 bool emulateReply(
UINT8 *requestData,
int requestLen, std::vector<unsigned char> *replyVector)
94 std::vector<std::string> keyWordList;
95 std::vector<std::string> answerList;
97 keyWordList.push_back(
"sMN SetAccessMode");
98 answerList.push_back(
"sAN SetAccessMode 1");
100 keyWordList.push_back(
"sWN EIHstCola");
101 answerList.push_back(
"sWA EIHstCola");
103 keyWordList.push_back(
"sRN FirmwareVersion");
104 answerList.push_back(
"sRA FirmwareVersion 8 1.0.0.0R");
106 keyWordList.push_back(
"sRN OrdNum");
107 answerList.push_back(
"sRA OrdNum 7 1234567");
109 keyWordList.push_back(
"sWN TransmitTargets 1");
110 answerList.push_back(
"sWA TransmitTargets");
112 keyWordList.push_back(
"sWN TransmitObjects 1");
113 answerList.push_back(
"sWA TransmitObjects");
115 keyWordList.push_back(
"sWN TCTrackingMode 0");
116 answerList.push_back(
"sWA TCTrackingMode");
118 keyWordList.push_back(
"sRN SCdevicestate");
119 answerList.push_back(
"sRA SCdevicestate 1");
121 keyWordList.push_back(
"sRN DItype");
122 answerList.push_back(
"sRA DItype D RMS3xx-xxxxxx");
124 keyWordList.push_back(
"sRN ODoprh");
125 answerList.push_back(
"sRA ODoprh 451");
127 keyWordList.push_back(
"sMN mSCloadappdef");
128 answerList.push_back(
"sAN mSCloadappdef");
131 keyWordList.push_back(
"sRN SerialNumber");
132 answerList.push_back(
"sRA SerialNumber 8 18020073");
134 keyWordList.push_back(
"sMN Run");
135 answerList.push_back(
"sAN Run 1s");
137 keyWordList.push_back(
"sRN ODpwrc");
138 answerList.push_back(
"sRA ODpwrc 20");
140 keyWordList.push_back(
"sRN LocationName");
141 answerList.push_back(
"sRA LocationName B not defined");
143 keyWordList.push_back(
"sEN LMDradardata 1");
144 answerList.push_back(
"sEA LMDradardata 1");
146 for (
int i = 0; i < requestLen; i++)
148 request += (char) requestData[i];
150 for (
int i = 0; i < keyWordList.size(); i++)
152 if (request.find(keyWordList[i]) != std::string::npos)
155 reply += answerList[i];
156 reply += (char) 0x03;
160 replyVector->clear();
161 for (
int i = 0; i < reply.length(); i++)
163 replyVector->push_back((
unsigned char) reply[i]);
175 socket_(io_service_),
176 deadline_(io_service_),
179 timelimit_(timelimit)
183 if ((cola_dialect_id ==
'a') || (cola_dialect_id ==
'A'))
188 if ((cola_dialect_id ==
'b') || (cola_dialect_id ==
'B'))
203 deadline_.expires_at(boost::posix_time::pos_infin);
214 using boost::asio::ip::tcp;
215 using boost::lambda::var;
216 using boost::lambda::_1;
251 if ((cola_dialect_id ==
'a') || (cola_dialect_id ==
'A'))
253 this->m_protocol =
CoLa_A;
257 this->m_protocol =
CoLa_B;
313 if (i >= m_numberOfBytesInReceiveBuffer)
316 m_numberOfBytesInReceiveBuffer = 0;
321 UINT32 newLen = m_numberOfBytesInReceiveBuffer - i;
323 m_numberOfBytesInReceiveBuffer = newLen;
336 if (i >= m_numberOfBytesInReceiveBuffer)
358 if (magicWord != 0x02020202)
365 if (magicWord == 0x02020202)
383 memmove(&(m_receiveBuffer[0]), &(m_receiveBuffer[i]), bytesToMove);
392 printInfoMessage(
"SickScanCommonNw::findFrameInReceiveBuffer: Frame cannot be decoded yet, only " +
399 payloadlength = colab::getIntegerFromBuffer<UINT32>(
m_receiveBuffer, pos);
401 "SickScanCommonNw::findFrameInReceiveBuffer: Decoded payload length is " + ::
toString(payloadlength) +
405 if (payloadlength > (
sizeof(m_receiveBuffer) - 9))
409 "SickScanCommonNw::findFrameInReceiveBuffer: Frame too big for receive buffer. Frame discarded with length:" 418 "SickScanCommonNw::findFrameInReceiveBuffer: Frame not complete yet. Waiting for the rest of it (" +
424 frameLen = payloadlength + 9;
438 for (
UINT16 i = 8; i < (frameLen - 1); i++)
442 temp_xor = temp_xor ^ temp;
446 if (temp_xor != checkSum)
448 printWarning(
"SickScanCommonNw::findFrameInReceiveBuffer: Wrong checksum, Frame discarded.");
472 "SickScanCommonNw::processFrame: Calling processFrame_CoLa_A() with " + ::
toString(frame.
size()) +
" bytes.",
479 "SickScanCommonNw::processFrame: Calling processFrame_CoLa_B() with " + ::
toString(frame.
size()) +
" bytes.",
496 bool beVerboseHere =
false;
498 "SickScanCommonNw::readCallbackFunction(): Called with " +
toString(numOfBytes) +
" available bytes.",
503 UINT32 bytesToBeTransferred = numOfBytes;
504 if (remainingSpace < numOfBytes)
506 bytesToBeTransferred = remainingSpace;
516 if (bytesToBeTransferred > 0)
520 m_numberOfBytesInReceiveBuffer += bytesToBeTransferred;
534 printInfoMessage(
"SickScanCommonNw::readCallbackFunction(): No complete frame in input buffer, we are done.",
544 "SickScanCommonNw::readCallbackFunction(): Processing a frame of length " + ::
toString(frame.
size()) +
545 " bytes.", beVerboseHere);
547 UINT32 bytesToMove = m_numberOfBytesInReceiveBuffer - size;
549 m_numberOfBytesInReceiveBuffer = bytesToMove;
567 sscanf(
port_.c_str(),
"%d", &portInt);
572 ROS_INFO(
"Sensor emulation is switched on - network traffic is switched off.");
583 ROS_WARN(
"Disconnecting TCP-Connection.");
609 deadline_.expires_at(boost::posix_time::pos_infin);
620 ret = this->
recvQueue.getNumberOfEntriesInQueue();
625 bool *exception_occured,
bool isBinary)
628 deadline_.expires_from_now(boost::posix_time::milliseconds(timeout_ms));
629 const char end_delim =
static_cast<char>(0x03);
631 ec_ = boost::asio::error::would_block;
638 int waitingTimeInMs = 1;
640 for (i = 0; i < timeout_ms; i += waitingTimeInMs)
642 if (
false == this->
recvQueue.isQueueEmpty())
650 ROS_ERROR(
"no answer received after %zu ms. Maybe sopas mode is wrong.\n", timeout_ms);
653 boost::condition_variable cond_;
656 *bytes_read = datagramWithTimeStamp.
datagram.size();
657 memcpy(buffer, &(datagramWithTimeStamp.
datagram[0]), datagramWithTimeStamp.
datagram.size());
668 ROS_ERROR(
"sendSOPASCommand: socket not open");
675 bool cmdIsBinary =
false;
683 for (
int i = 0; i < 4; i++)
685 if (request[i] == 0x02)
701 if (cmdIsBinary ==
false)
703 msgLen = strlen(request);
708 for (
int i = 4; i < 8; i++)
710 dataLen |= ((
unsigned char) request[i] << (7 - i) * 8);
712 msgLen = 8 + dataLen + 1;
721 bool debugBinCmd =
false;
724 printf(
"=== START HEX DUMP ===\n");
725 for (
int i = 0; i < msgLen; i++)
727 unsigned char *ptr = (
UINT8 *) request;
728 printf(
"%02x ", ptr[i]);
730 printf(
"\n=== END HEX DUMP ===\n");
741 boost::asio::write(
socket_, boost::asio::buffer(request, msgLen));
743 catch (boost::system::system_error &e)
745 ROS_ERROR(
"write error for command: %s", request);
753 const int BUF_SIZE = 65536;
754 char buffer[BUF_SIZE];
767 "sendSOPASCommand: no full reply available for read after timeout.");
774 reply->resize(bytes_read);
776 std::copy(buffer, buffer + bytes_read, &(*reply)[0]);
785 bool isBinaryProtocol,
int *numberOfRemainingFifoEntries)
787 if (NULL != numberOfRemainingFifoEntries)
789 *numberOfRemainingFifoEntries = 0;
797 uint32_t nanoSec = timeStamp.
nsec;
798 double waitTime10Hz = 10.0 * (double) nanoSec / 1E9;
800 uint32_t waitTime = (int) waitTime10Hz;
802 double waitTimeUntilNextTime10Hz = 1 / 10.0 * (1.0 - (waitTime10Hz - waitTime));
814 std::vector<unsigned char> dataBuffer;
815 #if 1 // prepared for reconnect 816 bool retVal = this->
recvQueue.waitForIncomingObject(maxWaitInMs);
819 ROS_WARN(
"Timeout during waiting for new datagram");
828 if (NULL != numberOfRemainingFifoEntries)
830 *numberOfRemainingFifoEntries = this->
recvQueue.getNumberOfEntriesInQueue();
832 recvTimeStamp = datagramWithTimeStamp.
timeStamp;
833 dataBuffer = datagramWithTimeStamp.
datagram;
838 long size = dataBuffer.size();
839 memcpy(receiveBuffer, &(dataBuffer[0]), size);
840 *actual_length = size;
845 char szFileName[255];
846 sprintf(szFileName,
"/tmp/dg%06d.bin", cnt++);
850 fout = fopen(szFileName,
"wb");
853 fwrite(receiveBuffer, *actual_length, 1, fout);
861 ROS_ERROR(
"get_datagram: socket not open");
869 std::vector<unsigned char> reply;
873 bool exception_occured =
false;
875 char *buffer =
reinterpret_cast<char *
>(receiveBuffer);
877 if (
readWithTimeout(timeout, buffer, bufferSize, actual_length, &exception_occured, isBinaryProtocol) !=
880 ROS_ERROR_THROTTLE(1.0,
"get_datagram: no data available for read after %zu ms", timeout);
891 ROS_INFO(
"Failure - attempting to reconnect");
SickScanCommonTcp(const std::string &hostname, const std::string &port, int &timelimit, SickGenericParser *parser, char cola_dialect_id)
std::vector< unsigned char > exampleData(65536)
virtual ~SickScanCommonTcp()
int getReadTimeOutInMs()
get timeout in milliseconds
bool emulateReply(UINT8 *requestData, int requestLen, std::vector< unsigned char > *replyVector)
bool init(std::string ipAddress, unsigned short portNumber, Tcp::DisconnectFunction disconnectFunction, void *obj)
boost::asio::ip::tcp::socket socket_
static int getDiagnosticErrorCode()
void sendCommandBuffer(UINT8 *buffer, UINT16 len)
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.
bool getEmulSensor()
get emulation flag (using emulation instead of "real" scanner - currently implemented for radar ...
static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes)
#define printInfoMessage(a, b)
bool setReadCallbackFunction(Tcp::ReadFunction readFunction, void *obj)
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.
static void disconnectFunctionS(void *obj)
BYTE * getRawData()
get SOPAS raw data include header and CRC
#define ROS_ERROR_THROTTLE(rate,...)
diagnostic_updater::Updater diagnostics_
int getProtocolType(void)
get protocol type as enum
void disconnectFunction()
Queue< DatagramWithTimeStamp > recvQueue
UINT32 m_alreadyReceivedBytes
void setProtocolType(SopasProtocol cola_dialect_id)
set protocol type as enum
std::vector< unsigned char > datagram
boost::asio::deadline_timer deadline_
UINT32 m_numberOfBytesInReceiveBuffer
Number of bytes in buffer.
static SickScanRadarSingleton * getInstance()
void setReplyMode(int _mode)
void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes)
Unknown Command Language.
boost::system::error_code ec_
void setEmulation(bool _emul)
static long receivedDataLen
int numberOfDatagramInInputFifo()
void processFrame(ros::Time timeStamp, SopasEventMessage &frame)
Class that represents a message that was sent by a sensor. (Event message)
virtual int close_device()
virtual int init()
init routine of scanner
bool connect()
Connects to a sensor via tcp and reads the device name.
bool disconnect()
Closes the connection to the LMS. This is the opposite of init().
virtual int init_device()
#define ROS_INFO_THROTTLE(rate,...)
SopasEventMessage findFrameInReceiveBuffer()
virtual int stop_scanner()
Stops sending scan data.
Mutex m_receiveDataMutex
Access mutex for buffer.
void broadcast(int lvl, const std::string msg)
void setEmulSensor(bool _emulFlag)
Set emulation flag (using emulation instead of "real" scanner - currently implemented for radar...
UINT8 m_receiveBuffer[480000]
Low-Level receive buffer for all data.
std::vector< unsigned char > receivedData(65536)
int readWithTimeout(size_t timeout_ms, char *buffer, int buffer_size, int *bytes_read=0, bool *exception_occured=0, bool isBinary=false)
void printWarning(std::string message)
void simulateAsciiDatagram(unsigned char *receiveBuffer, int *actual_length)
void sleep(double seconds)
void handleRead(boost::system::error_code error, size_t bytes_transfered)