Apollo自动驾驶的点云CNN分割

原创文章,转载请注明: 转载自慢慢的回味

本文链接地址: Apollo自动驾驶的点云CNN分割

点云分割的主要方法为:1、映射3D点云到2D的索引图上,对每个索引图上的像素点里面的点云进行高度,强度,数量的统计;2、对2D索引图进行CNN推断,从而得到每个像素点倾向的中心点,方向,所属类型的概率等;3、通过SPP引擎集群2D索引图上的像素点;4、对每个集群里的每个像素点求所属类型概率的平均值,从而得到集群所属的类型,点云的范围,中心点,高度等。从而完成了物体的识别。

这儿以单元测试cnn_segmentation_test.cc的测试cnn_segmentation_sequence_test为例来分析Apollo自动驾驶的点云CNN分割。

CNN分割测试用例
TEST(CNNSegmentationTest, cnn_segmentation_sequence_test) {
  unsetenv("CYBER_PATH");
  unsetenv("MODULE_PATH");
//设置工作目录和配置文件路经
  FLAGS_work_root =
      "/apollo/modules/perception/testdata/"
      "lidar/lib/segmentation/cnnseg/";
  FLAGS_config_manager_path = "../../../../../production/conf";
//实例化一个CNN分割类实例
  auto segmentation = std::shared_ptr<cnnsegmentation>(new CNNSegmentation);
  LidarDetectorOptions options;
  EXPECT_FALSE(segmentation->Detect(options, nullptr));
  LidarFrame frame_data;
  EXPECT_FALSE(segmentation->Detect(options, &frame_data));
  frame_data.cloud = base::PointFCloudPool::Instance().Get();
  frame_data.world_cloud = base::PointDCloudPool::Instance().Get();
  EXPECT_FALSE(segmentation->Detect(options, &frame_data));
 
//初始化CNN分割实例,包括参数加载,特征提取初始化,CNN推测初始化。见下面详细注解。
  EXPECT_TRUE(segmentation->Init());
  EXPECT_TRUE(segmentation->InitClusterAndBackgroundSegmentation());
 
  std::string pcd_path =
      "/apollo/modules/perception/testdata/lidar/app/data/";
  std::vector<std::string> pcd_file_names;
  common::GetFileList(pcd_path, ".pcd", &pcd_file_names);
  std::string file_name;
  std::sort(pcd_file_names.begin(), pcd_file_names.end(),
            [](const std::string& lhs, const std::string& rhs) {
              if (lhs.length() < rhs.length()) {
                return true;
              } else if (lhs.length() == rhs.length()) {
                return lhs <= rhs;
              } else {
                return false;
              }
            });
  for (size_t i = 0; i < pcd_file_names.size(); ++i) {
    std::shared_ptr<lidarframe> frame(new LidarFrame);
    frame->cloud = base::PointFCloudPool::Instance().Get();
    frame->world_cloud = base::PointDCloudPool::Instance().Get();
//加载点云文件,比如这儿为/apollo/modules/perception/testdata/lidar/app/data/0001_00.pcd,可视化的结果如下图
    if (!LoadPCDFile(pcd_file_names[i], frame->cloud)) {
      continue;
    }
    frame->world_cloud->resize(frame->cloud->size());
//侦测当前帧中的对象,见下面代码详解
    EXPECT_TRUE(segmentation->Detect(options, frame.get()));
//打印侦测到的对象信息,见下面代码详解
    PrintObjects((frame.get())->segmented_objects);
  }
}
</lidarframe></std::string></cnnsegmentation>

测试用例PCD文件可视化结果
继续阅读“Apollo自动驾驶的点云CNN分割”本作品采用知识共享署名 4.0 国际许可协议进行许可。

Apollo二次规划算法(piecewise jerk speed optimizer)解析

原创文章,转载请注明: 转载自慢慢的回味

本文链接地址: Apollo二次规划算法(piecewise jerk speed optimizer)解析

Apollo里面最重要的模块就是感知和规划模块,规划模块最重要的是路径规划和速度规划任务,对应ROS机器人里面的局部规划。Apollo的规划模块首先根据当前的情况进行多场景(scenario)调度,每个场景又包含一个或者多个阶段(stage),每个阶段又由多个具有独立功能的小模块任务(task)完成。前面介绍了路径规划piecewise jerk speed optimizer这个任务,这篇文章就解读一下速度规划piecewise jerk speed optimizer这个任务。SL规划保证车辆的横向偏移足够平滑,ST规划保证车辆的前进方向速度变化足够平滑。


继续阅读“Apollo二次规划算法(piecewise jerk speed optimizer)解析”本作品采用知识共享署名 4.0 国际许可协议进行许可。

Cartesian与Frenet坐标系转换公式推导

原创文章,转载请注明: 转载自慢慢的回味

本文链接地址: Cartesian与Frenet坐标系转换公式推导

车在道路上行驶,以车的视角来看,车就如同在一条光滑的曲线上移动,且不时带有左右偏移。为了算法简单,我们选择了Frenet坐标系,它可以把直角坐标系下的复杂轨迹转换为只有S,L两个维度的简单曲线。

Frenet坐标系简介

如下图所示,3维空间中一条连续可微的曲线K,P为曲线K上的一个点,方格背景平面为曲线K在点P处的运动平面。\vec{T}为曲线K在点P处的切向量,即质点再P处的运动方向;\vec{N}为K在P处的法向量,垂直于质点运动方向\vec{T}\vec{N}\vec{T}在同一运动平面;\vec{B}为曲线K在P处的副法向量,且同时垂直于\vec{T}\vec{N},即垂直于运动平面。


Frenet的定义公式如下:

    \[ \begin{Bmatrix} \frac{d\vec{T}}{ds}= & \kappa\vec{N} \\ \frac{d\vec{N}}{ds}= & -\kappa\vec{T}+\tau\vec{B} \\ \frac{d\vec{B}}{ds}= & -\tau\vec{N} \end{Bmatrix} \]

其中,\frac{d}{ds}表示某一方向向量对弧长s的导数,\kappa为曲率为曲线相对于直线的弯曲程度,当为0时为直线,表述为曲线运动方向的变化关于弧长的导数(\kappa = \left\| \frac {d\mathbf {T} }{ds}}\right\|),\tau为挠率是曲线不能形成在同一平面内运动曲线的度量值,挠率越趋于0,则曲线越趋近于在同一平面内运动。Apollo的运动在大地上,局部路面可看作一个平面,挠率可设定为0,而Frenet公式可简化为:

(1)   \[ \begin{Bmatrix} \frac{d\vec{T}}{ds}= & \kappa\vec{N} \\ \frac{d\vec{N}}{ds}= & -\kappa\vec{T} \end{Bmatrix}  \right  \]

继续阅读“Cartesian与Frenet坐标系转换公式推导”本作品采用知识共享署名 4.0 国际许可协议进行许可。

Apollo无人车的消息流转

原创文章,转载请注明: 转载自慢慢的回味

本文链接地址: Apollo无人车的消息流转

Apollo由无数的组件构成,每个组件独立运行,通过消息来进行相互依赖。每个组件构建在Cyber RT框架上,处理一组输入并产生其输出数椐。Launch 文件提供组件入口,DAG 文件配置组件依赖的消息输入等。

使用 Cyber RT 创建新的组件

要创建并启动一个算法组件,需要通过以下 4 个步骤:

– 初如化组件的目录结构
– 实现组件类
– 设置配置文件
– 启动组件

以cyber/examples/common_component_example目录下的样例程序为例:

– C++头文件: common_component_example.h
– C++源文件: common_component_example.cc
– Bazel 构建文件: BUILD
– DAG 文件: common.dag
– Launch 文件: common.launch

实现组件类
头文件

如何实现`common_component_example.h`:

– 继承 Component 类
– 定义自己的 `Init` 和 `Proc` 函数。Proc 需要指定输入数椐类型。
– 使用`CYBER_REGISTER_COMPONENT`宏定义把组件类注册成全局可用。

#include <memory>
 
#include "cyber/component/component.h"
#include "cyber/examples/proto/examples.pb.h"
 
using apollo::cyber::Component;
using apollo::cyber::ComponentBase;
using apollo::cyber::examples::proto::Driver;
 
class CommonComponentSample : public Component<Driver, Driver> {
 public:
  bool Init() override;
  bool Proc(const std::shared_ptr<Driver>& msg0,
            const std::shared_ptr<Driver>& msg1) override;
};
CYBER_REGISTER_COMPONENT(CommonComponentSample)
源文件

对于源文件 `common_component_example.cc`, `Init` 和 `Proc` 这两个函数需要实现。

#include "cyber/examples/common_component_example/common_component_example.h"
 
bool CommonComponentSample::Init() {
  AINFO << "Commontest component init";
  return true;
}
 
bool CommonComponentSample::Proc(const std::shared_ptr<Driver>& msg0,
                                 const std::shared_ptr<Driver>& msg1) {
  AINFO << "Start common component Proc [" << msg0->msg_id() << "] ["
        << msg1->msg_id() << "]";
  return true;
}

继续阅读“Apollo无人车的消息流转”本作品采用知识共享署名 4.0 国际许可协议进行许可。

Apollo二次规划算法(piecewise jerk path optimizer)解析

原创文章,转载请注明: 转载自慢慢的回味

本文链接地址: Apollo二次规划算法(piecewise jerk path optimizer)解析

Apollo里面最重要的模块就是感知和规划模块,规划模块最重要的是路径规划和速度规划任务,对应ROS机器人里面的局部规划。Apollo的规划模块首先根据当前的情况进行多场景(scenario)调度,每个场景又包含一个或者多个阶段(stage),每个阶段又由多个具有独立功能的小模块任务(task)完成。这篇文章就主要解读一下路径规划piecewise jerk path optimizer这个任务。任务最终会生成轨迹(trajectory):每个点的位姿和速度信息,进而输出给控制模块去控制车辆。

任务代码调用入口

比如通过测试用例可得到如下的堆栈:

apollo::planning::PiecewiseJerkPathOptimizer::Process(apollo::planning::PiecewiseJerkPathOptimizer * const this, const apollo::planning::SpeedData & speed_data, const apollo::planning::ReferenceLine & reference_line, const apollo::common::TrajectoryPoint & init_point, const bool path_reusable, apollo::planning::PathData * const final_path_data) (piecewise_jerk_path_optimizer.cc:61)
apollo::planning::PathOptimizer::Execute(apollo::planning::PathOptimizer * const this, apollo::planning::Frame * frame, apollo::planning::ReferenceLineInfo * const reference_line_info) (path_optimizer.cc:45)
apollo::planning::scenario::lane_follow::LaneFollowStage::PlanOnReferenceLine(apollo::planning::scenario::lane_follow::LaneFollowStage * const this, const apollo::common::TrajectoryPoint & planning_start_point, apollo::planning::Frame * frame, apollo::planning::ReferenceLineInfo * reference_line_info) (lane_follow_stage.cc:167)
apollo::planning::scenario::lane_follow::LaneFollowStage::Process(apollo::planning::scenario::lane_follow::LaneFollowStage * const this, const apollo::common::TrajectoryPoint & planning_start_point, apollo::planning::Frame * frame) (lane_follow_stage.cc:116)
apollo::planning::scenario::Scenario::Process(apollo::planning::scenario::Scenario * const this, const apollo::common::TrajectoryPoint & planning_init_point, apollo::planning::Frame * frame) (scenario.cc:76)
apollo::planning::PublicRoadPlanner::Plan(apollo::planning::PublicRoadPlanner * const this, const apollo::common::TrajectoryPoint & planning_start_point, apollo::planning::Frame * frame, apollo::planning::ADCTrajectory * ptr_computed_trajectory) (public_road_planner.cc:38)
apollo::planning::OnLanePlanning::Plan(apollo::planning::OnLanePlanning * const this, const double current_time_stamp, const std::vector<apollo::common::TrajectoryPoint, std::allocator<apollo::common::TrajectoryPoint> > & stitching_trajectory, apollo::planning::ADCTrajectory * const ptr_trajectory_pb) (on_lane_planning.cc:572)
apollo::planning::OnLanePlanning::RunOnce(apollo::planning::OnLanePlanning * const this, const apollo::planning::LocalView & local_view, apollo::planning::ADCTrajectory * const ptr_trajectory_pb) (on_lane_planning.cc:417)
apollo::planning::PlanningTestBase::RunPlanning(apollo::planning::PlanningTestBase * const this, const std::__cxx11::string & test_case_name, int case_num, bool no_trajectory_point) (planning_test_base.cc:229)
apollo::planning::SunnyvaleBigLoopTest_keep_clear_02_Test::TestBody(apollo::planning::SunnyvaleBigLoopTest_keep_clear_02_Test * const this) (sunnyvale_big_loop_test.cc:191)

继续阅读“Apollo二次规划算法(piecewise jerk path optimizer)解析”本作品采用知识共享署名 4.0 国际许可协议进行许可。