autoware第二个问题,就是避障问题。这个问题问的人还是挺多的,大多刚接触autoware的都挂在避障这里,然而要实现避障还需要修改某些源码才能实现
以下就是我修改过的代码
话题订阅部分,lidar_kf_contour_track需要订阅前面lidar_euclideam_cluster_detect聚类后的结果,原本的lidar_kf_contour_track_core.cpp订阅的话题是/cloud_clusters,这个话题是没有发布者的,订阅的有问题,需要改成下面那个
lidar_euclideam_cluster_detect也要修改,吧下面颜色部分加上去,具体是在lidar_euclideam_cluster_detect.cpp中的publishCloudClusters函数里面
void publishCloudClusters(const ros::Publisher *in_publisher, const autoware_msgs::CloudClusterArray &in_clusters,
const std::string &in_target_frame, const std_msgs::Header &in_header)
{
if (in_target_frame != in_header.frame_id)
{
..............
cluster_transformed.dimensions = i->dimensions;
cluster_transformed.eigen_values = i->eigen_values;
cluster_transformed.eigen_vectors = i->eigen_vectors;
//ADD
cluster_transformed.avg_point.point.x = cluster_transformed.centroid_point.point.x;
cluster_transformed.avg_point.point.y = cluster_transformed.centroid_point.point.y;
cluster_transformed.avg_point.point.z = cluster_transformed.centroid_point.point.z;
cluster_transformed.indicator_state = 3;
static unsigned int id=0;
cluster_transformed.id = id++;
cluster_transformed.convex_hull = i->convex_hull;
cluster_transformed.bounding_box.pose.position = i->bounding_box.pose.position;
if(_pose_estimation)
{
cluster_transformed.bounding_box.pose.orientation = i->bounding_box.pose.orientation;
}
else
{
cluster_transformed.bounding_box.pose.orientation.w = _initial_quat_w;
}
clusters_transformed.clusters.push_back(cluster_transformed);
}
catch (tf::TransformException &ex)
{
ROS_ERROR("publishCloudClusters: %s", ex.what());
}
}
in_publisher->publish(clusters_transformed);
publishDetectedObjects(clusters_transformed);
} else
{
in_publisher->publish(in_clusters);
publishDetectedObjects(in_clusters);
}
}
以下为实现避障需要勾选的节点(后续会详细介绍)
1.方式一:waypoint避障或者停障方式(astar_avoid中取消勾选enable avoid 为停障,勾选为避障模式)
2.方式二:waypoint用录制好的路线+避障(遇到障碍物绕过)(不常见,不推荐使用,方法跟方式三类似,意在使用waypoint_loader提供全局路径)
3方式三:op_planner导航+避障
另外,参数上特别特别需要注意一点就是:
lidar_eucllidean_cluster_detect节点app参数中[output_frame]需要改成map,即把聚类后的结果投影到map层,我们的地图才接受到相应的聚类结果,才能避障,autoware默认的是velodyne,这个是无法进行避障的!我看网上很多人这个参数是错的!!!!