48 diagnosticPub_(NULL), expectedFrequency_(15.0), parser_(parser)
51 dynamic_reconfigure::Server<sick_tim::SickTimConfig>::CallbackType
f;
78 const char requestScanData0[] = {
"\x02sEN LMDscandata 0\x03\0"};
82 printf(
"\nSOPAS - Error stopping streaming scan data!\n");
84 printf(
"\nSOPAS - Stopped streaming scan data.\n");
94 std::vector<unsigned char> access_reply;
95 int result =
sendSOPASCommand(
"\x02sMN SetAccessMode 03 F4724744\x03\0", &access_reply);
98 ROS_ERROR(
"SOPAS - Error setting access mode");
99 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error setting access mode.");
103 if (access_reply_str !=
"sAN SetAccessMode 1")
105 ROS_ERROR_STREAM(
"SOPAS - Error setting access mode, unexpected response : " << access_reply_str);
106 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error setting access mode.");
113 std::vector<unsigned char> reboot_reply;
117 ROS_ERROR(
"SOPAS - Error rebooting scanner");
122 if (reboot_reply_str !=
"sAN mSCreboot")
124 ROS_ERROR_STREAM(
"SOPAS - Error rebooting scanner, unexpected response : " << reboot_reply_str);
125 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error setting access mode.");
129 ROS_INFO(
"SOPAS - Rebooted scanner");
141 printf(
"sick_tim driver exiting.\n");
149 ROS_FATAL(
"Failed to init device: %d", result);
154 ROS_FATAL(
"Failed to init scanner: %d", result);
164 const char requestDeviceIdent[] =
"\x02sRI0\x03\0";
165 std::vector<unsigned char> identReply;
169 ROS_ERROR(
"SOPAS - Error reading variable 'DeviceIdent'.");
170 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error reading variable 'DeviceIdent'.");
176 const char requestSerialNumber[] =
"\x02sRN SerialNumber\x03\0";
177 std::vector<unsigned char> serialReply;
181 ROS_ERROR(
"SOPAS - Error reading variable 'SerialNumber'.");
182 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error reading variable 'SerialNumber'.");
196 const char requestFirmwareVersion[] = {
"\x02sRN FirmwareVersion\x03\0"};
200 ROS_ERROR(
"SOPAS - Error reading variable 'FirmwareVersion'.");
201 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error reading variable 'FirmwareVersion'.");
207 const char requestDeviceState[] = {
"\x02sRN SCdevicestate\x03\0"};
208 std::vector<unsigned char> deviceStateReply;
212 ROS_ERROR(
"SOPAS - Error reading variable 'devicestate'.");
213 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error reading variable 'devicestate'.");
215 std::string deviceStateReplyStr =
replyToString(deviceStateReply);
221 if (deviceStateReplyStr ==
"sRA SCdevicestate 0")
225 else if (deviceStateReplyStr ==
"sRA SCdevicestate 1")
229 else if (deviceStateReplyStr ==
"sRA SCdevicestate 2")
239 ROS_WARN_STREAM(
"Laser reports unknown devicestate : " << deviceStateReplyStr);
245 const char requestScanData[] = {
"\x02sEN LMDscandata 1\x03\0"};
249 ROS_ERROR(
"SOPAS - Error starting to stream 'LMDscandata'.");
250 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"SOPAS - Error starting to stream 'LMDscandata'.");
259 std::string reply_str;
260 for (std::vector<unsigned char>::const_iterator it = reply.begin(); it != reply.end(); it++)
264 reply_str.push_back(*it);
272 char device_string[7];
273 int version_major = -1;
274 int version_minor = -1;
276 if (sscanf(identStr.c_str(),
"sRA 0 6 %6s E V%d.%d", device_string,
277 &version_major, &version_minor) == 3
278 && strncmp(
"TiM3", device_string, 4) == 0
279 && version_major >= 2 && version_minor >= 50)
281 ROS_ERROR(
"This scanner model/firmware combination does not support ranging output!");
282 ROS_ERROR(
"Supported scanners: TiM5xx: all firmware versions; TiM3xx: firmware versions < V2.50.");
283 ROS_ERROR(
"This is a %s, firmware version %d.%d", device_string, version_major, version_minor);
294 unsigned char receiveBuffer[65536];
295 int actual_length = 0;
296 static unsigned int iteration_count = 0;
298 int result =
get_datagram(receiveBuffer, 65536, &actual_length);
301 ROS_ERROR(
"Read Error when getting datagram: %i.", result);
302 diagnostics_.
broadcast(diagnostic_msgs::DiagnosticStatus::ERROR,
"Read Error when getting datagram.");
305 if(actual_length <= 0)
309 if (iteration_count++ % (
config_.skip + 1) != 0)
314 std_msgs::String datagram_msg;
315 datagram_msg.data = std::string(
reinterpret_cast<char*
>(receiveBuffer));
319 sensor_msgs::LaserScan
msg;
324 char* buffer_pos = (
char*)receiveBuffer;
326 while( (dstart = strchr(buffer_pos, 0x02)) && (dend = strchr(dstart + 1, 0x03)) )
328 size_t dlength = dend - dstart;
334 buffer_pos = dend + 1;
342 if (conf.min_ang > conf.max_ang)
344 ROS_WARN(
"Maximum angle must be greater than minimum angle. Adjusting min_ang.");
345 conf.min_ang = conf.max_ang;