Skip to content

Commit

Permalink
feat:add rs-bpearl support
Browse files Browse the repository at this point in the history
What happened.

Close #10, #11, #12
(BREAKING CHANGE: isolate scope bindings definition has changed.)

Signed-off-by: Tony Zhang <hitxfd.tony@gmail.com>
  • Loading branch information
Tony-HIT committed Sep 11, 2019
1 parent 06d8504 commit aa2cee7
Show file tree
Hide file tree
Showing 15 changed files with 222 additions and 133 deletions.
9 changes: 9 additions & 0 deletions changelog_cn.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,3 +37,12 @@
* 10.规范化代码。
* 11.增加根据水平角度分帧的功能。

### V4.1.0(2019-09-11)
---
* 1.修复不同回波模式下packet_rate参数计算错误问题。
* 2.新增从RS32线的difop包中读取角度标定值。
* 3.更改打印信息输出内容,便于识别打印信息来源。
* 4.更改三角函数计算到查表方式,优化代码执行效率。
* 5.更改不同雷达镜头到转体中心的坐标换。
* 6.修改默认分帧方式到角度分帧,且修改包数分帧的报数对应18K点频设备。
* 7.新增RSBPEARL配置。
9 changes: 9 additions & 0 deletions changelog_en.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,13 @@ first release for mutil node version
* 10.Normalize the code
* 11.Add the horizontal angle framing code

### V4.1.0(2019-09-11)
---
* 1.Fix bug: fix the packet_rate calculation bug for different return mode.
* 2.Add the function for reading the calibrated angle from difop of RS32.
* 3.Update the log format to make it more clear to know the source of the information.
* 4.Change the trigonometric function calculation to look-up table, this can improve the code performance efficiency.
* 5.Change the coordinate transformation compensation for different lidars.
* 6.Change the scan split way to angle by default. Change the packet_rate value corresponding to 18K sampling rate.
* 7.Add RSBPEARL configuration support.

9 changes: 7 additions & 2 deletions rslidar_driver/src/rsdriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

namespace rslidar_driver
{
static const unsigned int POINTS_ONE_CHANNEL_PER_SECOND = 20000;
static const unsigned int POINTS_ONE_CHANNEL_PER_SECOND = 18000;
static const unsigned int BLOCKS_ONE_CHANNEL_PER_PKT = 12;

rslidarDriver::rslidarDriver(ros::NodeHandle node, ros::NodeHandle private_nh)
Expand Down Expand Up @@ -52,6 +52,11 @@ rslidarDriver::rslidarDriver(ros::NodeHandle node, ros::NodeHandle private_nh)
packet_rate = 1500;
model_full_name = "RS-LiDAR-32";
}
else if (config_.model == "RSBPEARL")
{
packet_rate = 1500;
model_full_name = "RSBPEARL";
}
else
{
ROS_ERROR_STREAM("[driver] unknown LIDAR model: " << config_.model);
Expand Down Expand Up @@ -209,7 +214,7 @@ bool rslidarDriver::poll(void)
{
packets_rate = ceil(packets_rate/2);
}
else if (config_.model == "RS32" && (mode == 0))
else if ((config_.model == "RS32" || config_.model == "RSBPEARL") && (mode == 0))
{
packets_rate = packets_rate*2;
}
Expand Down
33 changes: 33 additions & 0 deletions rslidar_pointcloud/data/rs_bpearl/ChannelNum.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81
32 changes: 32 additions & 0 deletions rslidar_pointcloud/data/rs_bpearl/angle.csv
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
89.5,0
86.6875,0
83.875,0
81.0625,0
78.25,0
75.4375,0
72.625,0
69.8125,0
67,0
64.1875,0
61.375,0
58.5625,0
55.75,0
52.9375,0
50.125,0
47.3125,0
44.5,0
41.6875,0
38.875,0
36.0625,0
33.25,0
30.4375,0
27.625,0
24.8125,0
22,0
19.1875,0
16.375,0
13.5625,0
10.75,0
7.9375,0
5.125,0
2.3125,0
66 changes: 33 additions & 33 deletions rslidar_pointcloud/data/rs_lidar_32/ChannelNum.csv
Original file line number Diff line number Diff line change
@@ -1,33 +1,33 @@
382,382,382,382,382,382,382,382,382,383,382,383,383,384,384,384,384,385,385,386,386,387,388,389,389,391,391,392,394,395,397,399,401,403,405,407,408,410,411,413,414,417,418,420,422,424,425,428,429,431,431
419,419,419,419,419,419,419,419,419,419,420,420,420,421,420,421,420,420,421,421,422,422,423,423,424,425,426,427,428,430,432,433,434,436,437,439,441,443,443,446,446,449,450,452,454,456,458,460,462,464,464
394,394,394,394,394,394,394,394,394,394,394,395,395,395,396,395,396,395,397,397,398,398,398,400,400,402,402,404,405,406,408,409,411,413,414,416,418,419,421,423,424,427,427,430,432,435,435,438,440,442,442
393,393,393,393,393,393,393,393,393,393,393,393,393,394,394,394,393,394,393,395,395,395,395,397,396,398,399,399,402,402,404,405,407,408,408,411,413,414,416,417,418,420,421,424,425,427,429,431,433,435,435
398,398,398,398,398,398,398,398,398,399,398,397,400,398,398,399,400,399,401,401,401,401,403,403,403,405,405,406,408,409,410,411,412,414,416,419,420,421,423,425,426,429,429,430,432,434,435,438,439,442,442
415,415,415,415,415,415,415,415,415,415,414,414,415,415,415,415,416,416,417,417,418,418,418,419,420,421,421,423,424,425,426,428,429,431,433,435,436,438,439,442,442,444,445,446,448,449,451,453,455,457,457
407,407,407,407,407,407,407,407,407,407,408,408,408,408,409,408,408,407,409,409,409,409,410,411,412,412,414,415,416,418,419,420,422,423,426,427,430,431,433,435,435,439,439,442,444,446,448,451,453,454,454
415,415,415,415,415,415,415,415,415,416,414,414,416,415,415,416,416,416,417,418,418,418,419,419,420,422,422,423,426,426,427,428,430,433,434,436,438,439,440,443,443,446,447,447,449,451,453,454,457,458,458
396,396,396,396,396,396,396,396,396,397,396,395,397,396,396,396,397,397,397,398,398,398,399,400,399,402,402,403,405,406,406,408,410,411,413,416,417,419,421,422,424,427,427,428,430,432,434,436,438,439,439
414,414,414,414,414,414,414,414,414,415,415,416,415,416,416,416,415,416,416,417,417,417,418,419,419,420,422,422,424,425,427,428,430,432,432,435,436,439,439,442,442,445,446,449,450,452,455,456,458,461,461
390,390,390,390,390,390,390,390,390,391,392,391,392,392,392,392,391,392,392,392,392,393,393,394,395,395,397,398,399,400,401,403,403,406,407,409,411,413,414,416,417,419,421,422,425,426,429,431,433,435,435
400,400,400,400,400,400,400,400,400,401,399,398,401,399,399,400,401,400,401,402,402,402,403,403,404,405,406,407,409,409,411,412,413,415,417,419,421,422,424,426,427,429,430,431,433,434,437,438,440,442,442
385,385,385,385,385,385,385,385,385,386,388,387,388,388,388,388,387,387,388,388,389,388,389,390,390,391,393,393,396,396,398,399,401,402,403,405,408,409,410,413,414,416,418,420,421,424,427,428,431,432,432
412,412,412,412,412,412,412,412,412,412,412,412,413,412,413,413,412,412,413,413,414,414,414,416,415,417,418,419,421,422,423,425,426,427,429,432,433,435,436,438,439,441,442,445,446,449,450,452,454,455,455
414,414,414,414,414,414,414,414,414,414,416,416,416,415,416,416,416,415,416,417,416,416,417,418,418,419,421,422,423,425,426,428,428,431,431,433,435,438,439,441,442,445,445,448,450,452,455,458,459,461,461
408,408,408,408,408,408,408,408,408,409,409,408,410,409,409,410,409,409,409,410,410,411,411,412,412,414,415,415,417,419,420,422,423,424,426,428,430,432,434,435,436,439,439,443,444,446,449,450,452,454,454
353,353,353,353,353,353,353,353,353,353,350,351,352,352,353,353,354,354,356,357,358,358,360,361,361,362,363,364,366,367,368,370,372,376,377,378,380,382,383,385,386,389,390,392,394,396,396,399,401,404,404
428,428,428,428,428,428,428,428,428,428,426,427,428,428,427,428,429,428,429,431,430,431,431,432,433,434,435,436,438,439,440,441,443,446,447,449,451,453,455,455,457,460,460,461,464,466,466,470,471,473,473
367,367,367,367,367,367,367,367,367,366,365,365,367,366,366,367,368,367,369,370,370,371,371,373,373,374,374,376,377,379,379,382,383,385,387,389,390,391,393,394,396,398,400,400,403,404,405,407,410,412,412
406,406,406,406,406,406,406,406,406,407,404,406,406,406,407,406,408,407,409,409,409,410,410,412,411,413,414,415,417,418,419,421,422,424,426,427,429,431,432,434,434,437,439,438,441,442,445,446,449,450,450
380,380,380,380,380,380,380,380,380,380,380,381,381,381,381,382,381,382,382,384,383,384,385,386,387,387,389,390,391,392,394,395,397,400,400,402,405,406,407,409,410,412,414,417,418,420,422,424,426,428,428
416,416,416,416,416,416,416,416,416,416,414,415,417,415,416,416,417,417,418,419,419,419,420,421,421,423,423,424,426,427,428,429,431,433,434,437,438,440,441,443,444,447,448,448,450,452,453,456,457,460,460
370,370,370,370,370,370,370,370,370,371,371,370,372,371,372,372,372,372,373,373,374,374,375,376,376,377,378,380,381,382,384,385,387,388,390,392,393,396,396,398,399,401,403,405,406,409,409,412,414,416,416
422,422,422,422,422,422,422,422,422,422,421,420,422,421,421,422,422,423,423,424,424,424,426,426,426,428,429,429,432,433,434,435,437,439,441,443,445,447,448,450,450,453,455,455,456,459,460,463,464,467,467
395,395,395,395,395,395,395,395,395,395,395,395,395,396,395,396,395,395,396,397,396,398,397,399,399,400,402,402,404,405,405,408,408,411,412,415,415,418,419,421,421,424,426,427,429,431,433,434,437,438,438
417,417,417,417,417,417,417,417,417,418,417,418,419,418,419,419,419,419,419,420,420,421,421,422,423,423,425,426,427,428,430,432,433,435,436,438,439,442,443,445,445,448,450,451,454,455,457,459,461,463,463
392,392,392,392,392,392,392,392,392,392,390,391,392,392,392,392,393,393,393,395,394,395,396,397,397,398,399,400,401,403,404,405,407,409,411,412,414,416,417,419,420,422,423,423,425,428,429,430,433,435,435
409,409,409,409,409,409,409,409,409,409,410,409,410,410,410,411,410,410,411,411,412,412,412,414,414,415,416,417,420,420,422,423,425,426,428,430,431,434,435,437,438,440,442,444,446,448,449,452,454,455,455
394,394,394,394,394,394,394,394,394,394,394,394,395,396,395,395,396,395,396,397,397,398,398,399,399,400,402,403,404,406,407,408,411,411,413,416,417,419,419,422,423,424,426,429,430,432,433,436,437,440,440
407,407,407,407,407,407,407,407,407,407,406,406,407,406,407,407,407,408,408,409,409,409,410,411,411,413,413,414,416,418,418,419,422,423,425,427,428,430,432,434,434,437,438,439,440,442,443,447,448,450,450
384,384,384,384,384,384,384,384,384,385,384,385,385,385,386,386,385,385,386,387,387,388,388,390,389,391,391,393,394,395,397,398,399,402,402,404,406,408,409,410,412,414,415,417,419,421,422,424,426,427,427
410,410,410,410,410,410,410,410,410,410,408,409,410,409,409,410,411,411,411,412,412,413,413,414,414,416,416,418,420,420,422,422,424,426,428,429,431,433,434,436,437,439,441,441,443,444,447,449,450,453,453
31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0
31,32,33,34,35,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,79,80,81
4 changes: 0 additions & 4 deletions rslidar_pointcloud/data/rs_lidar_32/ChannelNumDistance.csv

This file was deleted.

64 changes: 32 additions & 32 deletions rslidar_pointcloud/data/rs_lidar_32/CurveRate.csv
Original file line number Diff line number Diff line change
@@ -1,32 +1,32 @@
2.69231
0.50725
1.79487
0.67308
0.6422
1.34615
0.8046
1.34615
0.7
0.52239
0.72165
0.79545
1.66667
0.79545
0.83333
0.79545
0.58824
0.4698
0.84337
1.22807
0.59829
0.53435
1
0.79545
0.54264
0.79545
1.07692
0.74468
1.12903
0.61404
1.32075
1.09375
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
1
2 changes: 0 additions & 2 deletions rslidar_pointcloud/data/rs_lidar_32/HorizAngle.csv

This file was deleted.

2 changes: 0 additions & 2 deletions rslidar_pointcloud/data/rs_lidar_32/limit.csv

This file was deleted.

30 changes: 30 additions & 0 deletions rslidar_pointcloud/launch/rs_bpearl.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
<launch>
<arg name="model" default="RSBPEARL" />
<arg name="device_ip" default="192.168.1.200" />
<arg name="msop_port" default="6699" />
<arg name="difop_port" default="7788" />
<arg name="cut_angle" default="0" doc="If set at [0, 360), cut at specific angle feature activated, otherwise use the fixed packets number mode."/>
<arg name="lidar_param_path" default="$(find rslidar_pointcloud)/data/rs_bpearl/"/>

<node name="rslidar_node" pkg="rslidar_driver" type="rslidar_node" output="screen" >
<param name="model" value="$(arg model)"/>
<param name="device_ip" value="$(arg device_ip)" />
<param name="msop_port" value="$(arg msop_port)" />
<param name="difop_port" value="$(arg difop_port)"/>
<param name="cut_angle" value="$(arg cut_angle)"/>
<!--param name="pcap" value="path_to_pcap"/-->
</node>

<node name="cloud_node" pkg="rslidar_pointcloud" type="cloud_node" output="screen" >
<param name="model" value="$(arg model)"/>
<param name="angle_path" value="$(arg lidar_param_path)/angle.csv" />
<param name="channel_path" value="$(arg lidar_param_path)/ChannelNum.csv" />
<param name="max_distance" value="150"/>
<param name="min_distance" value="0.1"/>
<param name="resolution_type" value="0.5cm"/>
<param name="intensity_mode" value="3"/>
</node>

<node name="rviz" pkg="rviz" type="rviz" args="-d $(find rslidar_pointcloud)/rviz_cfg/rslidar.rviz" />

</launch>
Loading

1 comment on commit aa2cee7

@Abhilash-aid
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hi guys,

can any one help me on this?, I am running my B_Pearl Lidar wit ROS Rviz and it is showing a wrong point cloud.

Please sign in to comment.