文章目录
地图格式差异
https://mp.weixin.qq.com/s/EgsdlDhd8lIXU3bnTYJh0w
Apollo
地图格式对OpenDRIVE
都有哪些改动,改动的原因或初衷是什么,改动有什么优势?- 主要改动和扩展了以下几个方面:
- 一是地图元素形状的表述方式。以车道边界为例,标准OpenDRIVE采用基于Reference Line的曲线方程和偏移的方式来表达边界形状,而Apollo OpenDrive采用绝对坐标序列的方式描述边界形状;
- 二是元素类型的扩展。例如新增了对于禁停区、人行横道、减速带等元素的独立描述;
- 三是扩展了对于元素之间相互关系的描述。比如新增了junction与junction内元素的关联关系等;除此之外还有一些配合无人驾驶算法的扩展,比如增加了车道中心线到真实道路边界的距离、停止线与红绿灯的关联关系等。改动和扩展后的规格在实现上更加的简单,同时也兼顾了无人驾驶的应用需求。
apollo 高精地图规范
格式
- 百度高精地图数据格式采用(
XML
)文件格式的数据组织方式,是基于国际通用的OpenDrive
规范,并根据百度自动驾驶业务需求拓展修改而成。 - Apollo高精地图文件的整体结构如下所示:
坐标
- 百度高精地图坐标采用
WGS84
经纬度坐标表示。WGS84
为一种大地坐标系,也是目前广泛使用的GPS
全球卫星定位系统使用的坐标系。
车道
- 道路的
reference line
存储在ID
为0的车道中,其他车道只存储当前车道的一个边界。例如,reference line
右侧的车道只存储车道的右侧边界。 - 车道 ID 的命名规则:
- lane section 内唯一
- 数值连续的
- reference line 所在 lane 的 ID 为 0
- reference line 左侧 lane 的 ID 向左侧依次递增 (正t轴方向)
- reference line 右侧 lane 的 ID 向右侧依次递减(负 t 轴方向)
- reference line 必须定义在<center>节点内
路口区域(Juction)
- 基本的原理比较简单,路口区域用Junction结构表达。在Junction内,incoming Road通过Connecting Roads与out-going道路相连。下图展示了一个比较复杂的路口:
高精地图在Apollo的存在形式
-
在Apollo发布的Docker镜像中,也包含了地图的部分。Apollo在启动时,你可以按照如下方式为启动的镜像挂载地图:
apollo@baidu:~/apollo$ bash docker/scripts/dev_start.sh --map sunnyvale_big_loop
-
如果不指定挂载的地图,默认挂载以下地图:
map_volume-sunnyvale_big_loop-latest
map_volume-sunnyvale_loop-latest
-
一段道路的相关自动驾驶地图可以放置在如下结构的目录中:
sunnyvale_big_loop ├── background.jpg ├── background.png ├── base_map.bin ├── base_map.lb1 ├── base_map.txt ├── base_map.xml # Defined by FLAGS_base_map_filename ├── default_end_way_point.txt # Defined by FLAGS_end_way_point_filename ├── grid_map ├── local_map ├── map.json ├── routing_map.bin # Defined by FLAGS_routing_map_filename ├── routing_map.txt ├── sim_map.bin # Defined by FLAGS_sim_map_filename ├── sim_map.txt └── speed_control.pb.txt
-
可以将可用地图文件名指定为备选列表:
--base_map_filename="base.xml|base.bin|base.txt"
-
然后Apollo会找到第一个可用的文件加载。一般来说,按照以下扩展顺序加载:
x.xml # An OpenDrive formatted map. x.bin # A binary pb map. x.txt # A text pb map.
base_map, routing_map和sim_map之间的差异
base_map
是最完整的地图,包含所有道路和车道几何形状和标识。其他版本的地图均基于base_map
生成。routing_map
包含base_map
中车道的拓扑结构,可以有以下命令生成:
dir_name=modules/map/data/demo # example map directory
./scripts/generate_routing_topo_graph.sh --map_dir ${dir_name}
sim_map
是一个适用于Dreamview
视觉可视化,基于base_map
的轻量版本。减少了数据密度,以获得更好的运行时性能。可以由以下命令生成:
dir_name=modules/map/data/demo # example map directory
bazel-bin/modules/map/tools/sim_map_generator --map_dir=${dir_name} --output_dir=${dir_name}
高精地图在Apollo中的流转形式
xml
格式的地图见modules/map/data/sunnyvale_big_loop/base_map.xml
文件。那接下来我们就看下从XML
解析到proto的过程。- XML解析为Proto
- 主要是由方法opendrive_adapter.cc中的以下方法解析并读取:
OpendriveAdapter::LoadData(const std::string& filename,apollo::hdmap::Map* pb_map)
- 解析过程主要分为以下四个过程:
根目录 + header + 道路 + 路口 等节点的获取
- 系统内格式
- 不管原始数据格式为什么,在Apollo内部的数据地图的格式为proto。以下为Apollo高精地图的对象定义:
获取高精地图元素
对地图的操作方法
- 有了原始从xml格式到protobuf的数据之后,就可以访问这些高精地图的元素,Apollo高精地图提供如下的方法获取元素:
LoadMapFromFile (const std::string &map_filename) 从本地文件加载地图 GetLaneById (const Id &id) const GetJunctionById (const Id &id) const GetSignalById (const Id &id) const GetCrosswalkById (const Id &id) const GetStopSignById (const Id &id) const GetYieldSignById (const Id &id) const GetClearAreaById (const Id &id) const GetSpeedBumpById (const Id &id) const GetOverlapById (const Id &id) const GetRoadById (const Id &id) const // 在确定范围获取所有车道 GetLanes (const apollo::common::PointENU &point, double distance, std::vector< LaneInfoConstPtr > *lanes) const // 在确定范围获取所有路口区域 GetJunctions (const apollo::common::PointENU &point, double distance, std::vector< JunctionInfoConstPtr > *junctions) const // 在确定范围内获取所有人行道 GetCrosswalks (const apollo::common::PointENU &point, double distance, std::vector< CrosswalkInfoConstPtr > *crosswalks) const // 获取确定范围的所有信号灯 GetSignals (const apollo::common::PointENU &point, double distance, std::vector< SignalInfoConstPtr > *signals) const // 获取确定范围内的所有停止标识 GetStopSigns (const apollo::common::PointENU &point, double distance, std::vector< StopSignInfoConstPtr > *stop_signs) const // 获取确定范围内的所有避让标识 GetYieldSigns (const apollo::common::PointENU &point, double distance, std::vector< YieldSignInfoConstPtr > *yield_signs) const // 获取确定范围内的所有禁止停车标识 GetClearAreas (const apollo::common::PointENU &point, double distance, std::vector< ClearAreaInfoConstPtr > *clear_areas) const // 获取确定范围内的所有减速带 GetSpeedBumps (const apollo::common::PointENU &point, double distance, std::vector< SpeedBumpInfoConstPtr > *speed_bumps) const // 获取确定范围内的所有道路 GetRoads (const apollo::common::PointENU &point, double distance, std::vector< RoadInfoConstPtr > *roads) const // 获取从目标点的最近车道 GetNearestLane (const apollo::common::PointENU &point, LaneInfoConstPtr *nearest_lane, double *nearest_s, double *nearest_l) const // 判断车辆姿态,获取在一定范围内最近的车道 GetNearestLaneWithHeading (const apollo::common::PointENU &point, const double distance, const double central_heading, const double max_heading_difference, LaneInfoConstPtr *nearest_lane, double *nearest_s, double *nearest_l) const // 判断车辆姿态,获取所有车道 GetLanesWithHeading (const apollo::common::PointENU &point, const double distance, const double central_heading, const double max_heading_difference, std::vector< LaneInfoConstPtr > *lanes) const // 获取确定范围内的所有道路和路口边界 GetRoadBoundaries (const apollo::common::PointENU &point, double radius, std::vector< RoadROIBoundaryPtr > *road_boundaries, std::vector< JunctionBoundaryPtr > *junctions) const // 如果有两个与一条停止线相关的信号,则在车道上的某个范围内前进最近的信号,返回两个信号。 GetForwardNearestSignalsOnLane (const apollo::common::PointENU &point, const double distance, std::vector< SignalInfoConstPtr > *signals) const
- 提供高精地图元素获取的方法实现类:
apollo::hdmap::HDMapImpl
详见apollo::hdmap::HDMapImpl Class Reference
获取元素实例
modules/planning/reference_line/reference_line_provider.cc
bool ReferenceLineProvider::GetReferenceLinesFromRelativeMap( const relative_map::MapMsg &relative_map, std::list<ReferenceLine> *reference_line, std::list<hdmap::RouteSegments> *segments) { if (relative_map.navigation_path_size() <= 0) { return false; } auto *hdmap = HDMapUtil::BaseMapPtr(); for (const auto path_pair : relative_map.navigation_path()) { const auto &lane_id = path_pair.first; const auto &path_points = path_pair.second.path().path_point(); // 从高精地图中获取对应车道 auto lane_ptr = hdmap->GetLaneById(hdmap::MakeMapId(lane_id)); RouteSegments segment; segment.emplace_back(lane_ptr, 0.0, lane_ptr->total_length()); segment.SetCanExit(true); segment.SetId(lane_id); segment.SetNextAction(routing::FORWARD); segment.SetIsOnSegment(true); segment.SetStopForDestination(false); segment.SetPreviousAction(routing::FORWARD); segments->emplace_back(segment); std::vector<ReferencePoint> ref_points; for (const auto &path_point : path_points) { ref_points.emplace_back( MapPathPoint{Vec2d{path_point.x(), path_point.y()}, path_point.theta(), LaneWaypoint(lane_ptr, path_point.s())}, path_point.kappa(), path_point.dkappa(), 0.0, 0.0); } reference_line->emplace_back(ref_points.begin(), ref_points.end()); } return true; }
使用其他地图
- 更改全局
flagfile
: modules/common/data/global_flagfile.txt 这是所有模块的基本flag文件,保持了整体系统的统一。 - 作为flag标记传递,这样只影响单个进程:
<binary> --map_dir=/path/to/your/map
- 覆盖模块所属的flag文件,生成位置:
modules//conf/.conf
- 明显地,这个文件也只影响单个模块
--flagfile=modules/common/data/global_flagfile.txt # Override values from the global flagfile. --map_dir=/path/to/your/map
- 明显地,这个文件也只影响单个模块