赞
踩
参考引用
首先感谢 CMU 团队的开源工作,本博客是为了方便在实车部署时遇到问题后查找相关思路用,相关问答全部来自 TARE机器人自主导航系统社区-CSDN社区云,问答汇总截止到 2024年3月25日,后面不定期更新
问:keypose 指的是什么呢,cell 中 keypose_id 只有一个吗?
答:你好,keypose 指的是 SLAM 在产生关键帧的时候机器人所在的位置。当 loop closure 发生的时候,所有的 keypose 会被一起调整。这里 cell 里面存的 keypose 本意是想存一个能观测到这个 cell 的机器人的位置,但后来可能没有用这个数据
问:keypose_graph 的问题
答:keypose_graph 是用来搜索路径用的,相当于一个 roadmap。keypose 最开始是从 SLAM 端来的,如果 SLAM 算法提供闭环检测的话,keypose 就是关键帧对应的机器人位姿。在开源的版本里省去了对闭环的处理所以直接从机器人的轨迹上取点了。普通点是保留了机器人周围的可行驶视点。keypose_graph_cloud 内有两类,is_keypose 和 普通节点。keypose 是机器人行进轨迹上按一定频率留下来的点;其他普通节点是在 global planning里,以视点候选点为节点求出 cells 之间的路径后,在这些路径上留下来的点
bool kUseCoverageBoundaryOnFrontier;
bool kUseCoverageBoundaryOnObjectSurface;
for (int xi = 0; xi < 2; xi++) { for (int y = 0; y < vp_.kNumber.y(); y++) { for (int z = 0; z < vp_.kNumber.z(); z++) { int x = x_indices[xi]; Eigen::Vector3i end_sub(x, y, z); int array_ind = grid_->GetArrayInd(end_sub); if (!checked[array_ind]) { CheckViewPointLineOfSightHelper(robot_sub, end_sub, max_sub, min_sub); checked[array_ind] = true; } } } } for (int x = 0; x < vp_.kNumber.x(); x++) { for (int yi = 0; yi < 2; yi++) { for (int z = 0; z < vp_.kNumber.z(); z++) { int y = y_indices[yi]; Eigen::Vector3i end_sub(x, y, z); int array_ind = grid_->GetArrayInd(end_sub); if (!checked[array_ind]) { CheckViewPointLineOfSightHelper(robot_sub, end_sub, max_sub, min_sub); checked[array_ind] = true; } } } } for (int x = 0; x < vp_.kNumber.x(); x++) { for (int y = 0; y < vp_.kNumber.y(); y++) { for (int zi = 0; zi < 2; zi++) { int z = z_indices[zi]; Eigen::Vector3i end_sub(x, y, z); int array_ind = grid_->GetArrayInd(end_sub); if (!checked[array_ind]) { CheckViewPointLineOfSightHelper(robot_sub, end_sub, max_sub, min_sub); checked[array_ind] = true; } } } }
问:判断 surface 的距离约束和角度约束的参数是在哪设置
答:参数 kSensorRange 对应的是 D。在开源的代码中我们省去了对角度的约束,因为在实验当中约束角度带来的效果并不明显
问:在测试 tare 的时候出现了问题。就是 roslaunch vehicle_simulator system_garage.launch 之后。仿真环境正常启动,再然后在 tare 工作空间下 roslaunch tare_planner explore_garage.launch 之后,出现了 or-tools 求解器报错的问题,进程直接死了。导致探索没有办法进行
答:百度符号报错如何解决,发现 so 链接到了我之前的一个库,我的解决方法是在 zshrc 文件中去掉了 source 所有的 ros 工程,然后重新编译
问:小车的 terrain-map 在地面没有障碍物的情况下,仍然出现红点,如图所示,这因为什么呢,我已经调节了 vehicleHeight(平地面/轮胎底部到传感器中心的距离)为真实高度
答:地面没有障碍物仍然出现红点。你可以查看一下机器人运动过程中激光雷达的原始点云中是不是会出现一些噪点,从上面图看,机器人周围不可通过的点挺多的,这些点肯定都是真实扫描到的(假设你的定位是没有问题的)
问:当行人从小车周围经过后,留下的小红点多久会消失呢,如果要让这些点云能够快点消失,应该调节那些参数啊?
答:terrain_analysis 对于动态障碍物留下的点的消除效果并不出众,只能消除部分的点,并且是否消除这些点是与时间无关的,只和激光的视角有关,如果机器人静止的时候不能消除,那就需要让机器人运动一下,再查看是否消除
问:我们正在适配你们的 Autonomous Exploration Development Environment 和 TARE 算法到我们的实地 Jackal 机器人上,我们配备的是 ouster OS1-32 3D Lidar。现在遇到如下几个问题
1、我们的机器人雷达高度据地面为 0.335m,我们也实际修改了 terrain_analysis 中 vehicleHeight = 0.335, minRelZ = -0.335, and maxRelZ = 0.2. 其他参数与预设值一致。于是我们得到了如下 terrain_map
发现周围的墙壁变得非常矮,而重新将 vehicleHeight 改为较大数值如 10 时,周围墙壁又能按正常高度显示,如下图,请问这是什么原因呢?
2、我们得到的 terrain_map 在现实中地面上有许多的空白地区,尤其是机器人本身脚下及远处尤为严重,并不像 simulation 里所展示的 terrain_map 绿色区域填充了整个地面,并且实际前方并没有障碍物的区域也显示为了红色或黄色,请问有何潜在原因呢?结果如下图
sensor_scan 同时刻返回点云图如下:
3、在现有情况下,TARE 仍旧可发出 waypoint 进行导航,但是在 waypoint 会逐渐移动到障碍物中,然后就显示探索停止,返回原点。目前使用的 planning 参数基于 matterport 设置。请问有哪有参数可以做调整呢?
答
sample_range = std::min(parameters_.kGreedyViewPointSampleRange, sample_range);
std::random_device rd;//获取随机数种子
std::mt19937 gen(rd());
std::uniform_int_distribution<int> gen_next_queue_idx(0, sample_range - 1);//生成0到sample_range之间的均匀离散分布函数
int queue_idx = gen_next_queue_idx(gen);//在(0,sample_range - 1)生成随机数,然后赋予queue_idx
int cur_ind = queue_copy[queue_idx].second;
void SensorCoveragePlanner3D::CountDirectionChange() { Eigen::Vector3d current_moving_direction_ = Eigen::Vector3d(pd_.robot_position_.x, pd_.robot_position_.y, pd_.robot_position_.z) - Eigen::Vector3d(pd_.last_robot_position_.x, pd_.last_robot_position_.y, pd_.last_robot_position_.z); if (current_moving_direction_.norm() > 0.5) { if (pd_.moving_direction_.dot(current_moving_direction_) < 0) { direction_change_count_++; direction_no_change_count_ = 0; if (direction_change_count_ > pp_.kDirectionChangeCounterThr) { if (!use_momentum_) { momentum_activation_count_++; } use_momentum_ = true; } } else { direction_no_change_count_++; if (direction_no_change_count_ > pp_.kDirectionNoChangeCounterThr) { direction_change_count_ = 0; use_momentum_ = false; } } pd_.moving_direction_ = current_moving_direction_; } pd_.last_robot_position_ = pd_.robot_position_; std_msgs::Int32 momentum_activation_count_msg; momentum_activation_count_msg.data = momentum_activation_count_; momentum_activation_count_pub_.publish(momentum_activation_count_msg); }
问
答
问
答
我的毛毛虫现象解决了,原来很简单,在Rviz里的 registered_scan 对应的参数decay time设置成了10,改成0就行了。不明白参数设置成10是有什么特殊目的,这是话题延时
答:path generator里的参数dis是和环境相关的,这个参数影响的是做碰撞检测的范围,我们设置的默认参数适用于大多数的环境,如果你的环境非常开阔或者车速非常的高,可以设置一些大的参数值,不然效果确实会有影响
问
答
if (pathID >= 0 && pathID < pathNum && groupID >= 0 && groupID < groupNum) {
pathList[pathID] = groupID;
endDirPathList[pathID] = 2.0 * atan2(endY, endX) * 180 / PI;
}
问
答
for (int i = 0; i < planarVoxelNum; i++) { if (planarVoxelEdge[i] > noDataBlockSkipNum) { int indX = int(i / planarVoxelWidth); int indY = i % planarVoxelWidth; point.x = planarVoxelSize * (indX - planarVoxelHalfWidth) + vehicleX; point.y = planarVoxelSize * (indY - planarVoxelHalfWidth) + vehicleY; point.z = vehicleZ; point.intensity = vehicleHeight; point.x -= planarVoxelSize / 4.0; point.y -= planarVoxelSize / 4.0; terrainCloudElev->push_back(point); point.x += planarVoxelSize / 2.0; terrainCloudElev->push_back(point); point.y += planarVoxelSize / 2.0; terrainCloudElev->push_back(point); point.x -= planarVoxelSize / 2.0; terrainCloudElev->push_back(point); } }
int ViewPointManager::GetViewPointCoveredPointNum(const std::vector<bool>&point_list, int viewpoint_index, bool use_array_ind) {
int covered_point_num = 0;
for (const auto& point_ind : GetViewPointCoveredPointList(viewpoint_index, use_array_ind)) {
MY_ASSERT(misc_utils_ns::InRange<bool>(point_list, point_ind));
if (!point_list[point_ind]) {
covered_point_num++;
}
}
return covered_point_num;
}
问
答
问
答
if (fabs(dirDiff) < dirDiffThre && dis > stopDisThre) {
if (vehicleSpeed < joySpeed3) vehicleSpeed += maxAccel / 100.0;
else if (vehicleSpeed > joySpeed3) vehicleSpeed -= maxAccel / 100.0;
} else {
if (vehicleSpeed > 0) vehicleSpeed -= maxAccel / 100.0;
else if (vehicleSpeed < 0) vehicleSpeed += maxAccel / 100.0;
}
问
答
问:如图所示,我看代码中scale取的是0.65,这个值的大小会对产生的路径组有什么影响呢?
答
问:在这个判断条件内,定义了三种情况,当满足其中一个时,就不处理这次路径,请问这里angDiff,和dirToVehicle两个参数的含义是什么呢,这三种情况分别对应的又是什么呢?
答
问
答
问
答
问
答
问:在可视化工具中,有一个地方不是很明白,就是探索体积随时间的变化曲线,这个探索体积是如何求得呢?给定扫描得到的点云怎么计算体积大小?
答
问
答
问:您好,我使用了16线激光雷达,使用local_planner时无法绕开这些矮障碍物,请问 在terrain_analysis中能否准确识别出这种5cm左右的障碍物,需要改参数吗?
答:你好,可以尝试将local planner里的obstacleHeightThre改成0.05,如果定位准确的话,应该是可以识别的
问
答
答
答
问:最近在测试 far_planner + fast-lio 实车试验,目前采用的是matterport.config参数,发现在直线上表现良好,遇到转弯或是远距离行驶,就会出现较多噪点,无法获取路线,视频是手动遥控无人小车进行测试录屏,望大佬分析一下 是什么原因造成的,能从那些方面入手 调整参数或者代码
答
答:感谢回复,是地面不平整导致车抖动厉害,目前通过设置点云处理高度解决
Copyright © 2003-2013 www.wpsshop.cn 版权所有,并保留所有权利。