36 #include <std_msgs/UInt16.h>
37 #include <sensor_msgs/LaserScan.h>
38 #include <boost/asio.hpp>
44 : port_(port), baud_rate_(baud_rate), shutting_down_(false), serial_(io, port_)
46 serial_.set_option(boost::asio::serial_port_base::baud_rate(baud_rate_));
49 boost::asio::write(serial_, boost::asio::buffer(
"b", 1));
52 LFCDLaser::~LFCDLaser()
54 boost::asio::write(serial_, boost::asio::buffer(
"e", 1));
57 void LFCDLaser::poll(sensor_msgs::LaserScan::Ptr scan)
60 uint8_t start_count = 0;
61 bool got_scan =
false;
62 boost::array<uint8_t, 2520> raw_bytes;
63 uint8_t good_sets = 0;
64 uint32_t motor_speed = 0;
68 while (!shutting_down_ && !got_scan)
71 boost::asio::read(serial_, boost::asio::buffer(&raw_bytes[start_count],1));
75 if(raw_bytes[start_count] == 0xFA)
80 else if(start_count == 1)
82 if(raw_bytes[start_count] == 0xA0)
89 boost::asio::read(serial_,boost::asio::buffer(&raw_bytes[2], 2518));
91 scan->angle_increment = (2.0*M_PI/360.0);
92 scan->angle_min = 0.0;
93 scan->angle_max = 2.0*M_PI-scan->angle_increment;
94 scan->range_min = 0.12;
95 scan->range_max = 3.5;
96 scan->ranges.resize(360);
97 scan->intensities.resize(360);
100 for(uint16_t i = 0; i < raw_bytes.size(); i=i+42)
102 if(raw_bytes[i] == 0xFA && raw_bytes[i+1] == (0xA0 + i / 42))
105 motor_speed += (raw_bytes[i+3] << 8) + raw_bytes[i+2];
107 for(uint16_t j = i+4; j < i+40; j=j+6)
109 index = 6*(i/42) + (j-4-i)/6;
112 uint8_t byte0 = raw_bytes[j];
113 uint8_t byte1 = raw_bytes[j+1];
114 uint8_t byte2 = raw_bytes[j+2];
115 uint8_t byte3 = raw_bytes[j+3];
118 uint16_t intensity = (byte1 << 8) + byte0;
122 uint16_t range = (byte3 << 8) + byte2;
124 scan->ranges[359-index] = range / 1000.0;
125 scan->intensities[359-index] = intensity;
129 rpms=motor_speed / good_sets / 10;
130 scan->time_increment = (float)(1.0 / (rpms*6));
131 scan->scan_time = scan->time_increment * 360;
142 int main(
int argc,
char **argv)
144 ros::init(argc, argv,
"hlds_laser_publisher");
150 std::string frame_id;
152 std_msgs::UInt16 rpms;
154 priv_nh.
param(
"port", port, std::string(
"/dev/ttyUSB0"));
155 priv_nh.
param(
"baud_rate", baud_rate, 230400);
156 priv_nh.
param(
"frame_id", frame_id, std::string(
"laser"));
158 boost::asio::io_service io;
168 sensor_msgs::LaserScan::Ptr scan(
new sensor_msgs::LaserScan);
169 scan->header.frame_id = frame_id;
172 rpms.data=laser.
rpms;
174 motor_pub.publish(rpms);
180 catch (boost::system::system_error ex)
182 ROS_ERROR(
"An exception was thrown: %s", ex.what());