36 #include "sensor_msgs/LaserScan.h" 37 #include "std_srvs/Empty.h" 41 #define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0])) 44 #define DEG2RAD(x) ((x)*M_PI/180.) 53 double scan_time,
bool inverted,
54 float angle_min,
float angle_max,
58 static int scan_count = 0;
59 sensor_msgs::LaserScan scan_msg;
61 scan_msg.header.stamp = start;
62 scan_msg.header.frame_id = frame_id;
65 bool reversed = (angle_max > angle_min);
67 scan_msg.angle_min = M_PI - angle_max;
68 scan_msg.angle_max = M_PI - angle_min;
70 scan_msg.angle_min = M_PI - angle_min;
71 scan_msg.angle_max = M_PI - angle_max;
73 scan_msg.angle_increment =
74 (scan_msg.angle_max - scan_msg.angle_min) / (
double)(node_count-1);
76 scan_msg.scan_time = scan_time;
77 scan_msg.time_increment = scan_time / (double)(node_count-1);
78 scan_msg.range_min = 0.15;
79 scan_msg.range_max = max_distance;
81 scan_msg.intensities.resize(node_count);
82 scan_msg.ranges.resize(node_count);
83 bool reverse_data = (!inverted && reversed) || (inverted && !reversed);
85 for (
size_t i = 0; i < node_count; i++) {
86 float read_value = (float) nodes[i].
dist_mm_q2/4.0
f/1000;
87 if (read_value == 0.0)
88 scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
90 scan_msg.ranges[i] = read_value;
91 scan_msg.intensities[i] = (float) (nodes[i].
quality >> 2);
94 for (
size_t i = 0; i < node_count; i++) {
95 float read_value = (float)nodes[i].
dist_mm_q2/4.0
f/1000;
96 if (read_value == 0.0)
97 scan_msg.ranges[node_count-1-i] = std::numeric_limits<float>::infinity();
99 scan_msg.ranges[node_count-1-i] = read_value;
100 scan_msg.intensities[node_count-1-i] = (float) (nodes[i].
quality >> 2);
110 rplidar_response_device_info_t devinfo;
115 ROS_ERROR(
"Error, operation time out. RESULT_OPERATION_TIMEOUT! ");
117 ROS_ERROR(
"Error, unexpected error, code: %x",op_result);
123 printf(
"RPLIDAR S/N: ");
124 for (
int pos = 0; pos < 16 ;++pos) {
125 printf(
"%02X", devinfo.serialnum[pos]);
128 ROS_INFO(
"Firmware Ver: %d.%02d",devinfo.firmware_version>>8, devinfo.firmware_version & 0xFF);
129 ROS_INFO(
"Hardware Rev: %d",(
int)devinfo.hardware_version);
136 rplidar_response_device_health_t healthinfo;
138 if (
IS_OK(op_result)) {
139 ROS_INFO(
"RPLidar health status : %d", healthinfo.status);
141 ROS_ERROR(
"Error, rplidar internal error detected. Please reboot the device to retry.");
148 ROS_ERROR(
"Error, cannot retrieve rplidar health code: %x", op_result);
154 std_srvs::Empty::Response &res)
165 std_srvs::Empty::Response &res)
185 int main(
int argc,
char * argv[]) {
188 std::string channel_type;
190 std::string serial_port;
191 int tcp_port = 20108;
192 int serial_baudrate = 115200;
193 std::string frame_id;
194 bool inverted =
false;
195 bool angle_compensate =
true;
196 float max_distance = 8.0;
197 int angle_compensate_multiple = 1;
198 std::string scan_mode;
202 nh_private.param<std::string>(
"channel_type", channel_type,
"serial");
203 nh_private.param<std::string>(
"tcp_ip", tcp_ip,
"192.168.0.7");
204 nh_private.param<
int>(
"tcp_port", tcp_port, 20108);
205 nh_private.param<std::string>(
"serial_port", serial_port,
"/dev/ttyUSB0");
206 nh_private.param<
int>(
"serial_baudrate", serial_baudrate, 115200);
207 nh_private.param<std::string>(
"frame_id", frame_id,
"laser_frame");
208 nh_private.param<
bool>(
"inverted", inverted,
false);
209 nh_private.param<
bool>(
"angle_compensate", angle_compensate,
false);
210 nh_private.param<std::string>(
"scan_mode", scan_mode, std::string());
217 if(channel_type ==
"tcp"){
230 if(channel_type ==
"tcp"){
233 ROS_ERROR(
"Error, cannot bind to the specified serial port %s.",serial_port.c_str());
242 ROS_ERROR(
"Error, cannot bind to the specified serial port %s.",serial_port.c_str());
266 if (scan_mode.empty()) {
267 op_result = drv->
startScan(
false ,
true , 0, ¤t_scan_mode);
269 std::vector<RplidarScanMode> allSupportedScanModes;
272 if (
IS_OK(op_result)) {
274 for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
275 if (iter->scan_mode == scan_mode) {
276 selectedScanMode = iter->id;
281 if (selectedScanMode ==
_u16(-1)) {
282 ROS_ERROR(
"scan mode `%s' is not supported by lidar, supported modes:", scan_mode.c_str());
283 for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
284 ROS_ERROR(
"\t%s: max_distance: %.1f m, Point number: %.1fK", iter->scan_mode,
285 iter->max_distance, (1000/iter->us_per_sample));
289 op_result = drv->
startScanExpress(
false , selectedScanMode, 0, ¤t_scan_mode);
297 angle_compensate_multiple = (int)(1000*1000/current_scan_mode.
us_per_sample/10.0/360.0);
298 if(angle_compensate_multiple < 1)
299 angle_compensate_multiple = 1;
301 ROS_INFO(
"current scan mode: %s, max_distance: %.1f m, Point number: %.1fK , angle_compensate: %d", current_scan_mode.
scan_mode,
306 ROS_ERROR(
"Can not start scan: %08x!", op_result);
311 double scan_duration;
319 scan_duration = (end_scan_time - start_scan_time).toSec();
326 if (angle_compensate) {
328 const int angle_compensate_nodes_count = 360*angle_compensate_multiple;
329 int angle_compensate_offset = 0;
334 for( ; i < count; i++ ) {
337 int angle_value = (int)(angle * angle_compensate_multiple);
338 if ((angle_value - angle_compensate_offset) < 0) angle_compensate_offset = angle_value;
339 for (j = 0; j < angle_compensate_multiple; j++) {
341 int angle_compensate_nodes_index = angle_value-angle_compensate_offset+j;
342 if(angle_compensate_nodes_index >= angle_compensate_nodes_count)
343 angle_compensate_nodes_index = angle_compensate_nodes_count-1;
344 angle_compensate_nodes[angle_compensate_nodes_index] = nodes[i];
349 publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
350 start_scan_time, scan_duration, inverted,
351 angle_min, angle_max, max_distance,
354 int start_node = 0, end_node = 0;
366 publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +1,
367 start_scan_time, scan_duration, inverted,
368 angle_min, angle_max, max_distance,
376 start_scan_time, scan_duration, inverted,
377 angle_min, angle_max, max_distance,
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)=0
void publish(const boost::shared_ptr< M > &message) const
bool getRPLIDARDeviceInfo(RPlidarDriver *drv)
int main(int argc, char *argv[])
virtual u_result grabScanDataHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)=0
bool stop_motor(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void publish_scan(ros::Publisher *pub, rplidar_response_measurement_node_hq_t *nodes, size_t node_count, ros::Time start, double scan_time, bool inverted, float angle_min, float angle_max, float max_distance, std::string frame_id)
static void DisposeDriver(RPlidarDriver *drv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)=0
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual u_result stopMotor()=0
Stop RPLIDAR's motor when using accessory board.
#define RPLIDAR_STATUS_ERROR
virtual u_result startMotor()=0
Start RPLIDAR's motor when using accessory board.
#define RPLIDAR_SDK_VERSION
#define RESULT_OPERATION_TIMEOUT
virtual u_result startScan(bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)=0
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual u_result ascendScanData(rplidar_response_measurement_node_hq_t *nodebuffer, size_t count)=0
virtual u_result getAllSupportedScanModes(std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)=0
Get all scan modes that supported by lidar.
virtual u_result getDeviceInfo(rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)=0
static float getAngle(const rplidar_response_measurement_node_t &node)
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
virtual bool isConnected()=0
Returns TRUE when the connection has been established.
#define RESULT_OPERATION_FAIL
bool start_motor(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
virtual u_result connect(const char *, _u32, _u32 flag=0)=0
ROSCPP_DECL void spinOnce()
bool checkRPLIDARHealth(RPlidarDriver *drv)
virtual u_result getHealth(rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)=0