紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
使用OS0-128激光雷达跑ALOAM,怎么修改
-
我修改了launch文件和scanRegistration.cpp文件,没有跑成功。
<launch> <param name="scan_line" type="int" value="128" /> <!-- if 1, do mapping 10 Hz, if 2, do mapping 5 Hz. Suggest to use 1, it will adjust frequence automaticlly --> <param name="mapping_skip_frame" type="int" value="1" /> <!-- remove too closed points --> <param name="minimum_range" type="double" value="5"/> <remap from="/velodyne_points" to="/os_cloud_node/points"/> <param name="mapping_line_resolution" type="double" value="0.4"/> <param name="mapping_plane_resolution" type="double" value="0.8"/> <node pkg="aloam_velodyne" type="ascanRegistration" name="ascanRegistration" output="screen" /> <node pkg="aloam_velodyne" type="alaserOdometry" name="alaserOdometry" output="screen" /> <node pkg="aloam_velodyne" type="alaserMapping" name="alaserMapping" output="screen" /> <arg name="rviz" default="true" /> <group if="$(arg rviz)"> <node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find aloam_velodyne)/rviz_cfg/aloam_velodyne.rviz" /> </group> </launch>
bool halfPassed = false; int count = cloudSize; PointType point; std::vector<pcl::PointCloud<PointType>> laserCloudScans(N_SCANS); for (int i = 0; i < cloudSize; i++) { point.x = laserCloudIn.points[i].x; point.y = laserCloudIn.points[i].y; point.z = laserCloudIn.points[i].z; float angle = atan(point.z / sqrt(point.x * point.x + point.y * point.y)) * 180 / M_PI; int scanID = 0; if (N_SCANS == 16) { scanID = int((angle + 15) / 2 + 0.5); //确定每一个点的scanID,与垂直角度有关,确定这个点属于那个scan if (scanID > (N_SCANS - 1) || scanID < 0) { count--; //有效点减一 continue; } } else if (N_SCANS == 32) { scanID = int((angle + 92.0/3.0) * 3.0 / 4.0); if (scanID > (N_SCANS - 1) || scanID < 0) { count--; continue; } } else if (N_SCANS == 64) { if (angle >= -8.83) scanID = int((2 - angle) * 3.0 + 0.5); else scanID = N_SCANS / 2 + int((-8.83 - angle) * 2.0 + 0.5); // use [0 50] > 50 remove outlies if (angle > 2 || angle < -24.33 || scanID > 50 || scanID < 0) { count--; continue; } } else if (N_SCANS == 128) { scanID = int((angle + 45) / 2 + 0.5); if (scanID > (N_SCANS - 1) || scanID < 0) { count--; continue; } } else { printf("wrong scan number\n"); ROS_BREAK(); } //printf("angle %f scanID %d \n", angle, scanID); float ori = -atan2(point.y, point.x); if (!halfPassed) { if (ori < startOri - M_PI / 2) { ori += 2 * M_PI; } else if (ori > startOri + M_PI * 3 / 2) { ori -= 2 * M_PI; } if (ori - startOri > M_PI) { halfPassed = true; } } else { ori += 2 * M_PI; if (ori < endOri - M_PI * 3 / 2) { ori += 2 * M_PI; } else if (ori > endOri + M_PI / 2) { ori -= 2 * M_PI; } } float relTime = (ori - startOri) / (endOri - startOri); point.intensity = scanID + scanPeriod * relTime;// intensity字段的整数部分存放scanID,小数部分存放归一化后的fireID laserCloudScans[scanID].push_back(point); // 将点根据scanID放到对应的子点云laserCloudScans中 }
主要修改了launch文件里面的线数,和更改了话题,scanRegistration.cpp文件里面按照16线的格式增加了128线的scanID。
-
@小丑汪 不好意思哈,没有这方面的经验,看看其他小伙伴有没有知道的
-
好的,谢谢大佬,我再看看
-
-
@小丑汪 大佬,请问您后来修改成功了吗,我也遇到了同样的问题。