39 #include <boost/crc.hpp> 45 bool& using_intensity,
bool& using_multiecho,
bool synchronize_time)
54 long baudrate_or_port = (long)ip_port;
55 const char *device = ip_address.c_str();
61 ss <<
"Could not open network Hokuyo:\n";
62 ss << ip_address <<
":" << ip_port <<
"\n";
64 throw std::runtime_error(ss.str());
67 initialize(using_intensity, using_multiecho, synchronize_time);
71 bool& using_intensity,
bool& using_multiecho,
bool synchronize_time)
79 long baudrate_or_port = (long)serial_baud;
80 const char *device = serial_port.c_str();
86 ss <<
"Could not open serial Hokuyo:\n";
87 ss << serial_port <<
" @ " << serial_baud <<
"\n";
91 throw std::runtime_error(ss.str());
94 initialize(using_intensity, using_multiecho, synchronize_time);
101 if (urg_data_size < 0)
112 std::stringstream ss;
113 ss <<
"Could not initialize Hokuyo:\n";
117 throw std::runtime_error(ss.str());
122 if (urg_data_size > 5000)
124 urg_data_size = 5000;
127 intensity_.resize(urg_data_size * URG_MAX_ECHO);
177 std::stringstream ss;
178 ss <<
"Could not start Hokuyo measurement:\n";
181 ss <<
"With Intensity" <<
"\n";
185 ss <<
"With MultiEcho" <<
"\n";
188 throw std::runtime_error(ss.str());
220 unsigned long long system_time_stamp = 0;
242 msg->header.stamp.fromNSec((uint64_t)system_time_stamp);
245 msg->ranges.resize(num_beams);
248 msg->intensities.resize(num_beams);
251 for (
int i = 0; i < num_beams; i++)
253 if (
data_[(i) + 0] != 0)
255 msg->ranges[i] =
static_cast<float>(
data_[i]) / 1000.0;
263 msg->ranges[i] = std::numeric_limits<float>::quiet_NaN();
284 unsigned long long system_time_stamp;
300 msg->header.stamp.fromNSec((uint64_t)system_time_stamp);
302 msg->ranges.reserve(num_beams);
305 msg->intensities.reserve(num_beams);
308 for (
size_t i = 0; i < num_beams; i++)
310 sensor_msgs::LaserEcho range_echo;
312 sensor_msgs::LaserEcho intensity_echo;
319 if (
data_[(URG_MAX_ECHO * i) + j] != 0)
321 range_echo.echoes.push_back(static_cast<float>(
data_[(URG_MAX_ECHO * i) + j]) / 1000.0
f);
324 intensity_echo.echoes.push_back(
intensity_[(URG_MAX_ECHO * i) + j]);
332 msg->ranges.push_back(range_echo);
335 msg->intensities.push_back(intensity_echo);
347 str_cmd.append(
"000EAR00A012");
356 response.erase(0, 1);
357 response.erase(response.size() - 1, 1);
360 std::stringstream ss;
361 ss << response.substr(response.size() - 4, 4);
363 ss >> std::hex >> crc;
366 std::string
msg = response.substr(0, response.size() - 4);
368 uint16_t checksum_result =
checkCRC(msg.data(), msg.size());
370 if (checksum_result != crc)
372 ROS_WARN(
"Received bad frame, incorrect checksum");
382 ss << response.substr(8, 2);
383 ss >> std::hex >> status.
status;
394 ss << response.substr(10, 1);
399 ss << response.substr(11, 2);
407 ss << response.substr(13, 1);
414 ss << response.substr(14, 2);
425 ss << response.substr(16, 1);
437 str_cmd.append(
"000EDL005BCB");
446 response.erase(0, 1);
447 response.erase(response.size() - 1, 1);
450 std::stringstream ss;
451 ss << response.substr(response.size() - 4, 4);
453 ss >> std::hex >> crc;
456 std::string
msg = response.substr(0, response.size() - 4);
458 uint16_t checksum_result =
checkCRC(msg.data(), msg.size());
460 if (checksum_result != crc)
462 ROS_WARN(
"Received bad frame, incorrect checksum");
471 ss << response.substr(8, 2);
472 ss >> std::hex >> status;
480 std::vector<UrgDetectionReport> reports;
481 msg = msg.substr(10);
485 for (
int i = 0; i < 30; i++)
494 uint16_t offset_pos = i * 64;
495 ss << msg.substr(offset_pos, 2);
496 ss >> std::hex >> area;
500 ss << msg.substr(offset_pos + 4, 4);
501 ss >> std::hex >> distance;
504 ss << msg.substr(offset_pos + 8, 4);
505 ss >> std::hex >> step;
506 ROS_DEBUG_STREAM(i <<
" Area: " << area <<
" Distance: " << distance <<
" Step: " << step);
512 r.
angle =
static_cast<float>(step) / 8.0;
514 reports.push_back(r);
517 for (
auto iter = reports.begin(); iter != reports.end(); ++iter)
521 if (iter->area == 0xFF)
526 if (iter - 1 == reports.begin())
528 ROS_WARN(
"All reports are empty, no detections available.");
532 if (iter - 1 != reports.begin())
550 char buffer[
sizeof(
"SCIP2.0\n")];
563 if (n > 0 && strcmp(buffer,
"SCIP2.0") == 0
574 boost::crc_optimal<16, 0x1021, 0, 0, true, true> crc_kermit_type;
575 crc_kermit_type.process_bytes(bytes, size);
576 return crc_kermit_type.checksum();
582 bool restart =
false;
593 write(sock, cmd.c_str(), cmd.size());
597 size_t total_read_len = 0;
602 while (total_read_len < expected_read)
604 read_len = read(sock, recvb + total_read_len, expected_read - total_read_len);
605 total_read_len += read_len;
608 ROS_ERROR(
"Read socket failed: %s", strerror(errno));
614 std::string recv_header(recvb, read_len);
616 std::stringstream ss;
617 ss << recv_header.substr(1, 4);
618 ss >> std::hex >> expected_read;
622 uint32_t arr_size = expected_read - 5;
625 if (arr_size > 10000)
627 ROS_ERROR(
"Buffer creation bounds exceeded, shouldn't allocate: %u bytes", arr_size);
635 data.reset(
new char[arr_size]);
640 expected_read = arr_size;
643 while (total_read_len < expected_read)
645 read_len = read(sock, data.get()+total_read_len, expected_read - total_read_len);
646 total_read_len += read_len;
650 ROS_ERROR(
"Read socket failed: %s", strerror(errno));
657 result += recv_header;
658 result += std::string(data.get(), expected_read);
679 return static_cast<double>(minr) / 1000.0;
687 return static_cast<double>(maxr) / 1000.0;
726 return 1.e-6 *
static_cast<double>(scan_usec);
736 return cluster_ * circle_fraction * scan_period /
static_cast<double>(max_step - min_step);
911 double circle_fraction = 0.0;
918 circle_fraction = (
getAngleMin() + 3.141592) / (2.0 * 3.141592);
930 std::vector<ros::Duration> time_offsets(num_measurements);
931 for (
size_t i = 0; i < num_measurements; i++)
935 ros::Duration adjusted_scan_offset = scan_offset - start_offset;
936 ros::Duration adjusted_post_offset = post_offset - start_offset;
938 average_offset.
fromSec((adjusted_post_offset.
toSec() + previous_offset.
toSec()) / 2.0);
940 time_offsets[i] = adjusted_scan_offset - average_offset;
942 previous_offset = adjusted_post_offset;
947 std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
957 std::stringstream ss;
958 ss <<
"Cannot get native clock offset while started.";
959 throw std::runtime_error(ss.str());
964 std::stringstream ss;
965 ss <<
"Cannot start time stamp mode.";
966 throw std::runtime_error(ss.str());
969 std::vector<ros::Duration> time_offsets(num_measurements);
970 for (
size_t i = 0; i < num_measurements; i++)
978 time_offsets[i] = laser_time - average_time;
983 std::stringstream ss;
984 ss <<
"Cannot stop time stamp mode.";
985 throw std::runtime_error(ss.str());
990 std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
991 return time_offsets[time_offsets.size() / 2];
998 std::stringstream ss;
999 ss <<
"Cannot get time stamp offset while started.";
1000 throw std::runtime_error(ss.str());
1005 std::vector<ros::Duration> time_offsets(num_measurements);
1006 for (
size_t i = 0; i < num_measurements; i++)
1009 unsigned long long system_time_stamp;
1031 std::stringstream ss;
1032 ss <<
"Cannot get scan to measure time stamp offset.";
1033 throw std::runtime_error(ss.str());
1037 laser_timestamp.
fromNSec(1e6 * (uint64_t)time_stamp);
1039 system_time.
fromNSec((uint64_t)system_time_stamp);
1041 time_offsets[i] = laser_timestamp - system_time;
1048 std::nth_element(time_offsets.begin(), time_offsets.begin() + time_offsets.size() / 2, time_offsets.end());
1049 return time_offsets[time_offsets.size() / 2];
1055 system_time.
fromNSec((uint64_t)system_time_stamp);
1056 stamp = system_time;
1058 const uint32_t t1 =
static_cast<uint32_t
>(time_stamp);
1061 const uint32_t mask = 0x00ffffff;
1062 double delta =
static_cast<double>(mask&(t1-t0))/1000.0;
1084 if (fabs((stamp-system_time).toSec()) > 0.1)
1089 stamp = system_time;
1090 ROS_INFO(
"%s: detected clock warp, reset EMA", __func__);
int urg_start_time_stamp_mode(urg_t *urg)
const char * urg_sensor_vendor(urg_t *urg)
std::string getIPAddress() const
int urg_get_multiecho(urg_t *urg, long data_multi[], long *time_stamp, unsigned long long *system_time_stamp)
const char * urg_error(const urg_t *urg)
int urg_rad2step(const urg_t *urg, double radian)
int urg_stop_time_stamp_mode(urg_t *urg)
double hardware_clock_adj_
void urg_step_min_max(const urg_t *urg, int *min_index, int *max_index)
ros::Duration user_latency_
Time & fromNSec(uint64_t t)
int urg_max_data_size(const urg_t *urg)
urg_connection_t connection
std::string getDeviceID()
bool setAngleLimitsAndCluster(double &angle_min, double &angle_max, int cluster)
double getAngleMax() const
int urg_start_measurement(urg_t *urg, urg_measurement_type_t type, int scan_times, int skip_scan)
std::string getProtocolVersion()
double getRangeMax() const
int serial_write(urg_serial_t *serial, const char *data, int size)
URGCWrapper(const std::string &ip_address, const int ip_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
double getAngleMinLimit() const
urg_measurement_type_t measurement_type_
ros::Duration getTimeStampOffset(size_t num_measurements)
int urg_stop_measurement(urg_t *urg)
int urg_get_multiecho_intensity(urg_t *urg, long data_multi[], unsigned short intensity_multi[], long *time_stamp, unsigned long long *system_time_stamp)
uint16_t checkCRC(const char *bytes, const uint32_t size)
calculate the crc of a given set of bytes.
std::vector< unsigned short > intensity_
long last_hardware_time_stamp_
void initialize(bool &using_intensity, bool &using_multiecho, bool synchronize_time)
int getSerialBaud() const
long urg_time_stamp(urg_t *urg)
double getScanPeriod() const
std::string getVendorName()
ros::Duration getUserTimeOffset() const
int urg_set_scanning_parameter(urg_t *urg, int first_step, int last_step, int skip_step)
const char * urg_sensor_firmware_date(urg_t *urg)
Duration & fromSec(double t)
bool getDL00Status(UrgDetectionReport &report)
ros::Time getSynchronizedTime(long time_stamp, long long system_time_stamp)
Get synchronized time stamp using hardware clock.
void urg_close(urg_t *urg)
double getTimeIncrement() const
const char * urg_sensor_status(urg_t *urg)
int urg_open(urg_t *urg, urg_connection_type_t connection_type, const char *device_or_address, long baudrate_or_port)
std::string getSensorStatus()
bool getAR00Status(URGStatus &status)
const char * urg_sensor_product_type(urg_t *urg)
int serial_readline(urg_serial_t *serial, char *data, int max_size, int timeout)
std::vector< long > data_
void urg_distance_min_max(const urg_t *urg, long *min_distance, long *max_distance)
const char * urg_sensor_firmware_version(urg_t *urg)
bool grabScan(const sensor_msgs::LaserScanPtr &msg)
#define ROS_DEBUG_STREAM(args)
bool isMultiEchoSupported()
std::string getFirmwareVersion()
std::string getSerialPort() const
double getRangeMin() const
int urg_get_distance(urg_t *urg, long data[], long *time_stamp, unsigned long long *system_time_stamp)
Duration & fromNSec(int64_t t)
ros::Duration getAngularTimeOffset() const
double urg_step2rad(const urg_t *urg, int step)
int urg_get_distance_intensity(urg_t *urg, long data[], unsigned short intensity[], long *time_stamp, unsigned long long *system_time_stamp)
std::string getFirmwareDate()
ros::Duration system_latency_
double getAngleIncrement() const
std::string frame_id_
Output frame_id for each laserscan.
void setFrameId(const std::string &frame_id)
const char * urg_sensor_serial_id(urg_t *urg)
ros::Duration getComputedLatency() const
bool isIntensitySupported()
const char * urg_sensor_protocol_version(urg_t *urg)
ros::Duration getNativeClockOffset(size_t num_measurements)
urg_connection_type_t type
double getAngleMin() const
const std::string response
std::string getSensorState()
void setUserLatency(const double latency)
std::string getProductName()
bool setToSCIP2()
Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode.
double getAngleMaxLimit() const
long urg_scan_usec(const urg_t *urg)
urg_tcpclient_t tcpclient
const char * urg_sensor_state(urg_t *urg)
ros::Duration computeLatency(size_t num_measurements)
std::string sendCommand(std::string cmd)
Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socke...