开发者手册 - Samples

SDK目录中的范例代码根据目录分类,演示了SimOne 仿真产品的各类API在客户本地算法程序中的应用,例如调用传感器API来获取目标级别或者是物理级别传感器的数据,然后传送到客户的算法程序里面来测试无人驾驶算法,客户也可以使用传感器数据来作为传感器融合的raw data。

ADAS

AEB

算法构思

紧急刹车演示代码,您可以参考此代码来考虑接入您的算法到SimOne仿真场景中去。

算法流程图

获取对手车离主车的距离然后根据AEB算法来刹车。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

AVP

算法构思

自动泊车算法。

算法流程图

寻找停车区域,然后泊车算法运行。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

LKA

算法构思

自动车道保持巡航算法。

算法流程图

添加道路中心线的顶点来循迹。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

轨迹控制

ADAS/TrajectoryControl示例程序演示如何使用轨迹控制主车的运动。

如何运行该示例

由于示例程序中的轨迹为固定的,为了运行该示例,需要建立一个案例。

新建一个标准案例2.0进行编辑,下图为案例的配置信息。注意:地图使用三车道路口,主车选择API控制,主车的初始位置设置为轨迹开始的位置,初始速度为轨迹第一个点的初始速度。

编辑保存后,运行该案例,然后启动示例程序,可以看到车辆沿着程序中定义的轨迹运动,先直线前进140米左右向右变道,然后右拐。

通过轨迹控制主车的API

轨迹控制主车的API原型如下:

bool SetDriveTrajectory(int mainVehicleId,
SimOne_Data_Control_Trajectory \*pControlTrajectory)

用户的轨迹规划模块根据主车当前的位置朝向状态,规划出主车接下来的运动轨迹,轨迹包含一系列的轨迹点。规划出来的一条轨迹只需要通过API发送一次。

每一个轨迹点包含车辆期望的位置和朝向(Yaw),当前主车的速度、加速度,已经该轨迹点相对于当前轨迹起点的相对距离和相对时间。轨迹起点的相对距离和相对时间都为0。

示例中的三条轨迹是依次连接的,但用户的轨迹可以有重叠的部分,这样也更能保证车辆运动的连贯性。

轨迹控制的内部实现

SimOne内置了一个控制模块,根据用户轨迹得到车辆的控制信号,然后使用动力学控制车辆运动。在该示例中车辆速度恒定为10米/秒,所以右转时已经超出了车辆的控制极限,车辆右转时开到轨迹之外,然后由于控制模块的纠偏重新回到规划的轨迹上。

HDMap

算法构思

SimOne仿真案例启动时会将一个url地址发送到 HDMap API 端, 在地图加载过程中,HDMap API 首先按照 url 地址,通过 http 请求从数据平台将 SimOne 仿真案例运行时指定的xodr地图文件加载到内存, 之后根据主车在静态地图上的动态位置, 实时返回地图真值数据、道路路网、车道及车道线类型等消息提供给第三方驾驶算法来完成规划控制

算法流程图

HDMap API

API参考手册 - File SimOneHDMapAPI.h

  • 获取主车当前位置最近车道示例伪代码:

#include "SimOneServiceAPI.h"
#include "SimOneHDMapAPI.h"
#include "SimOneSensorAPI.h"
#include "SSD/SimPoint3D.h"
#include "SSD/SimString.h"

int main(int argc, char* argv[])
{
        const char* mv_id = "0"; // 主车Id
        bool isJoinTimeLoop = false; // 是否加入帧同步
        const char* serverIP = "127.0.0.1"; // BridgeIO IP

    // Step1: 初始化 SimOne API
    InitSimOneAPI(mv_id, isJoinTimeLoop, serverIP);

    // Step2: 加载高精度地图,地图文件由 SimOne 仿真 Web 端建立案例时指定
        int timeout = 20; // HDMap加载超时时间设置,若超时函数将返回推出
        if (!SimOneAPI::LoadHDMap(timeout)) // 从数据平台获取运行案例地图文件并加载到内存
        {
                std::cout << "LoadHDMap Failed!" << std::endl;
        return 0;
        }

        std::unique_ptr<SimOne_Data_Gps> pGPS = std::make_unique<SimOne_Data_Gps>();
        while (true)
        {
        // Step3: 获取主车GPS信息
                if (!GetGps(0/*vehicleId*/, pGPS.get()))
                {
                        std::cout << "Get GPS Failed!" << std::endl;
                }
        else
        {
            // 传入参数 主车当前位置(3D 点)
            SSD::SimPoint3D pos(pGps->posX, pGps->posY, pGps->posZ);
            // 传出参数 车道线ID,格式为 roadId_sectionIndex_laneId E.g.道路参考线右侧第一条车道表示为“1_0_-1”;左侧第二条车道表示为“1_0_2”
            SSD::SimString laneId;
            // 传出参数 主车位置相对检出车道的s-t坐标值
            double s, t;
            // 传出参数 主车位置相对检出车道所在道路中心线的s-t坐标值 (模糊值),通过调用 GetRoadST API 可获取更为精确的值
            double s_toCenterLine, t_toCenterLine;

            // Step 4: 获取最接近输入点的车道,所属车道优先
            if (!GetNearMostLane(pos, laneId, s, t, s_toCenterLine, t_toCenterLine))
                {
                std::cout << "Error: lane is not found." << std::endl;
                }
            else
            {
                std::cout << "lane id: " << laneId.GetString() << std::endl;;
                std::cout << "s: " << s << "    t: " << t << std::endl;
                std::cout << "s_toCenterLine: " << s_toCenterLine << "  t_toCenterLine: " << t_toCenterLine << std::endl;
            }
        }

                std::this_thread::sleep_for(std::chrono::milliseconds(100));
        }

        return 0;
}

编译环境

  • HDMap API Tutorial 示例工程目录结构

Tutorial
    ├── bin
    │   ├── DynamicsTest
    │   ├── HDMap
    │   ├── logServer.txt
    │   ├── log_taskImage.txt
    │   ├── PNCSample
    │   ├── SensorSample
    │   └── SensorV2X
    ├── Build
    │   ├── build_debug.bat
    │   ├── build_release
    │   ├── build_release.bat
    │   ├── CMakeLists.txt
    │   ├── gen_make_debug.sh
    │   ├── gen_make_release.sh
    │   ├── gen_vs_proj_debug.bat
    │   ├── gen_vs_proj_release.bat
    │   ├── rebuild_debug.sh
    │   └── rebuild_release.sh
    ├── HDMap
    │   ├── CMakeLists.txt
    │   ├── gen_vs_proj.bat
    │   ├── include
    │   ├── src

    bin:目标生成目录
    Build: 编译目录
    HDMap: HDMap API 示例源码目录
  • 编译:

    CMakeList.txt 支持生成windows / ubuntu 的项目工程

    Windows:
    1. 进入Build目录,运行 gen_vs_proj_debug.bat 或 gen_vs_proj_release.bat 生成 Visual Studio 工程

    2. 打开 Visual Studio 示例工程, 选择 HDMap 工程编译

    Linux:
    1. cd Build

    2. ./gen_make_debug.sh (或 ./gen_make_release.sh)

    3. cd build_debug(或 cd build_release)

    4. make -j4

使用流程

  • HDMap API

    1. 加载高精度地图:

      SIMONE_API bool LoadHDMap(int timeOutSeconds);

    2. 调用相应HDMap API获取地图信息:
      最接近输入点的车道,所属车道优先
      临近车道列表
      视野范围内所有车道
      离最近车道左右边缘线的距离
      车道信息(包含车道ID,左右边缘线,虚拟中心线)
      车道连接信息
      车道类型
      车道宽度
      相对于车道虚拟中心线的ST坐标
      相对于道路参考线的ST坐标
      局部坐标
      查询指定车道是否存在于地图之中
      地图中停车位列表
      路网路径规划
      规划路径所途径道路的ID列表
      输入点左右两侧车道标线信息
      地图中信号灯列表
      地图中交通标志列表
      交通灯给定作用车道的关联停止线列表
      交通灯给定作用车道的关联人行横道线列表
      指定车道所在道路上的网状线列表
      输入点投影到指定车道中心线上的点和切线方向
      路网指定坐标点的高程列表
      所有车道线信息列表。
      所有Junction ID列表。
      道路长度
      指定车道线所在Section的所有车道线ID列表
      判断指定道路是否是双向道路
      车道长度
      判断车道是否为机动车道
      判断车道是否在交叉路口内
      判断坐标点是否在车道内
      主车位置所在车道信息(包含车道ID,左右边缘线,虚拟中心线)
      
  • API测试:
    • 启动Sim-One,新建测试案例

    • 新建测试主车(配置控制系统为 手动 / API 控制)

    • 运行案例(选择主车为该主车)

    • 编译测试代码,SDK/bin目录下生成可执行文件

    • 运行示例程序 ,查看运行结果

SensorROS(ubuntu)

算法构思

ROS API 通过获取 SimOne 仿真感知数据,并将数据转换为标准 ROS 消息格式发布到指定 Topic 上。驾驶算法订阅相应 Topic 消息,将数据解析传入到规控/感知模块做算法相关训练。算法最终将解算后的控制消息发布到仿真主车控制消息 Topic,ROS API 订阅后将控制参数传入仿真主车动力学节点来驱动 SimOne 场景中的主车行使。驾驶算法可单独订阅个别 Topic 消息验证局部模块的正确性,也可形成算法、仿真的完整闭环实现驾驶算法的整体验证。

具体开发教程还可参考ROS_BRIDGE.md

算法流程图

编译环境

  • 软件环境:
    • 操作系统:Ubuntu18.04

    • ROS 软件版本:Melodic

    • 编程语言:C++

  • ROS Msg 消息转换

    • 将 SimOne API 数据格式转为 ROS 可发布/订阅的标准数据格式:

      1. 对照 SimOne API 接口数据,按照 C++ 数据类型与 ROS msg 数据类型的映射关系,编写 ROS API msg 消息文件

      2. 创建 ROS 工程 Worksapce

        mkdir -p ~/catkin_ws/src cd ~/catkin_ws/src catkin_init_workspace

      3. 创建功能包

        cd ~/catkin_ws/src catkin_create_pkg <package_name> roscpp std_msgs

      4. 将编写好的msg消息文件放入功能包

        mkdir ~/catkin_ws/src/<package_name>/msg

      5. 在~/catkin_ws/src/<package_name>/package.xml添加功能依赖

        <build_depend>message_generation</build_depend> <exec_depend>message_runtime</exec_depend>

      6. 在~/catkin_ws/src/<package_name>/CMakeLists.txt添加编译选项

        find_package(catkin REQUIRED COMPONENTS
            roscpp
            std_msgs
            message_generation
        )
        
        add_message_files(FILES
            <ROS API msg 消息文件 .msg>
        )
        
        generate_messages(DEPENDENCIES
            std_msgs
        )
        
        catkin_package(
            CATKIN_DEPENDS roscpp std_msgs message_runtime
        )
        
      7. 编译功能包

        cd ~/catkin_ws catkin_make

      8. 编译工作空间

        cd ~/catkin_ws catkin_make

      9. 检查msg文件生成的 C++ 头文件

        ~/catkin_ws/devel/include/<package_name>/

      10. 将生成的 C++ 头文件融入 ROS API 工程

  • ROS API 工程结构

ROS/
├── CMakeLists.txt   # 工程编译脚本
├── gen_make_debug.sh  # debug 工程编译环境生成脚本
├── gen_make_release.sh  # release 工程编译环境生成脚本
├── include     # 工程头文件
├── lib      # 工程依赖库
├── run      # ROS API 节点可执行程序生成目录
└── src      # ROS API 工程源文件
  • ROS API 工程编译:

    执行 gen_make_debug.sh / gen_make_release.sh

    cd build_debug / build_release

    make # ROS API 节点程序生成路径: run/trans_node_ros

  • SimOne ROS Bridge执行流程:

    1. 通过Sim-One API获取仿真感知数据

      主车Gps消息回调 bool SetGpsUpdateCB(void(cb)(const char mainVehicleId, SimOne_Data_Gps pGps)); 获取仿真感知物体真值回调 bool SetGroundTruthUpdateCB(void(*cb)(const char mainVehicleId, SimOne_Data_Obstacle pObstacle)); 获取摄像头图像数据回调 bool SetStreamingImageUpdateCB(const char ip, unsigned short port, void(cb)(SimOne_Streaming_Image *pImage)); 获取激光雷达点云数据回调 bool SetStreamingPointCloudUpdateCB(const char ip, unsigned short port, unsigned short infoPort, void(cb)(SimOne_Streaming_Point_Cloud *pPointCloud)); 获取毫米波雷达目标信息回调 bool SetRadarDetectionsUpdateCB(void(*cb)(const char mainVehicleId, const char* sensorId, SimOne_Data_RadarDetection pDetections)); 获取目标及传感器真知数据回调 bool SetSensorDetectionsUpdateCB(void(*cb)(const char mainVehicleId, const char* sensorId, SimOne_Data_SensorDetections pGroundtruth)); 获取感知车道与车道线数据回调 bool GetSensorLaneInfo(const char mainVehicleId, const char* sensorId, SimOne_Data_LaneInfo *pLaneInfo);

    2. 通过ROS Publisher将感知消息发布到相应Topic上

      发布Gps消息 pub_gps = handle_gps.advertise<msg_gen::gps>(gps_topic.c_str(), 1); pub_gps_p->publish(gps_d); 发布仿真感知物体真值消息 pub_ground_truth = handle_ground_truth.advertise<msg_gen::obstacle>(ground_truth_topic.c_str(), 1); pub_ground_truth_p->publish(obstacle_d); 发布摄像头图像数据消息 pub_image = handle_image.advertise<sensor_msgs::Image>(image_topic.c_str(), 1); pub_image_p->publish(img_d); 发布激光雷达点云数据消息 pub_point_cloud = handle_point_cloud.advertise<sensor_msgs::PointCloud2>(point_cloud_topic.c_str(), 1); pub_point_cloud_p->publish(point_cloud_d); 发布毫米波雷达目标信息 pub_radar = handle_radar.advertise<msg_gen::radardetection>(radar_topic.c_str(), 1); pub_radar_p->publish(radar_detection_d); 发布目标及传感器真值消息 pub_sensor = handle_sensor.advertise<msg_gen::sensordetections>(sensor_topic.c_str(), 1); pub_sensor_p->publish(sensor_detections_d); 发布感知车道/车道线消息 pub_laneinfo = handle_laneinfo.advertise<msg_gen::laneinfo>(lane_info_topic.c_str(), 1); pub_laneinfo_p->publish(lane_info_d);

    3. 通过ROS Subscriber订阅主车控制相关Topic

      订阅主车控制消息(离散点 控制) sub_ctl = handle_ctl.subscribe(ctl_topic.c_str(), 1, &ros_trans_node::rcv_ctl_cb, this); 订阅主车控制消息(油门/刹车/方向 控制) sub_pose_ctl = handle_pose_ctl.subscribe(pose_ctl_topic.c_str(), 1, &ros_trans_node::rcv_pose_ctl_cb, this);

    4. 通过Sim-One API设置主车控制参数

      根据离散点设置主车位置 SimOneAPI::SetPose(0, &pose_ctl); 设置主车控制参数 SimOneAPI::SetDrive(vehicle_id.c_str(), pCtrl.get());

  • SimOne ROS Bridge 运行:
    1. 启动 roscore

    2. 执行 trans_node_ros 运行时程序将读取config.ini配置文件参数
      config.ini运行参数配置文件:

      [BridgeIO]# Sim-One API 客户端连接设置 BridgeIO_IP=10.66.9.111# SimOne BridgeIO 节点IP [HostVehicle]# Sim-One 仿真主车设置 Vehicle_ID=0# Sim-One 仿真主车ID [Sensor]# Sim-One 传感器通信配置 IMG_IP=10.66.9.244# 图像数据 UDP 接收端 IP IMG_PORT=13944# 图像数据 UDP 接收端 Port PCD_IP=10.66.9.244# 点云数据 UDP 接收端 IP PCD_PORT=6699# 点云数据 UDP 接收端 Port PCD_PORT_INFO=7788# 点云数据 UDP 接收端 InfoPort [ROS]# ROS 消息配置 GPS_Topic=/gps# Gps消息发布Topic GroundTruth_Topic=/ground_truth# 感知物体真值消息发布Topic Image_Topic=/image# 图像数据消息发布Topic PointCloud_Topic=/point_cloud# 点云数据消息发布Topic Radar_Topic=/radar_detection# 毫米波雷达数据消息发布Topic Sensor_Topic=/sensor_detection# 目标及传感器真值数据消息发布Topic LaneInfo_Topic=/lane_info# 感知车道/车道线数据消息发布Topic CTL_Topic=/control# 主车控制(油门/刹车/方向)数据消息订阅Topic POSE_CTL_Topic=/pose_control# 主车控制(离散点)数据消息订阅Topic

使用流程

在SimOne 中运行案例,在Ubuntu中运行算法。

  • API测试:
    • 启动Sim-One,新建测试案例

    • 新建测试主车(加载相关传感器,配置控制系统为 手动 / API 控制)

    • 运行案例(选择主车为该主车)

    • 运行SimOne ROS Bridge

    • 启动第三方算法

  • 消息验证
    • 图像数据:rviz 可视化工具订阅 Image Topic 消息显示图像

    • 点运数据:rviz 可视化工具订阅 PointCloud Topic 消息显示点云图像

    • 结构化数据:rostopic echo 命令监听相应 Topic 查看数据输出

      source ~/catkin_ws/devel/setup.bash rostopic echo /gps

Sensor_Raw

Camera

用法简述

物理级摄像头数据传输的演示代码,您可以参考此代码来实时发送摄像头仿真图像至您的算法或控制器。

../../_images/camera_raw.png

在传感器配置页面正确填写接收端的ip和端口,SimOne将通过udp协议发送数据。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

Lidar

用法简述

物理级激光雷达数据传输的演示代码,您可以参考此代码来实时发送激光雷达仿真点云数据至您的算法或控制器。

../../_images/lidar_raw.png

在传感器配置页面正确填写接收端的ip和端口,SimOne将通过udp协议发送数据。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

LidarROS

用法简述

../../_images/lidar_raw.png

物理级激光雷达数据传输至ros的演示代码,您可以参考此代码来实时发送激光雷达仿真点云数据至您的ros系统。

在传感器配置页面正确填写接收端的ip和端口,SimOne将通过udp协议发送数据。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

PNC

算法构思

决策规划控制算法利用多传感器融合后的目标级真值数据,开展相关算法验证。SimOne 仿真主车控制 API 提供了 离散点、油门/刹车/方向、规划轨迹 等驱动方式,算法的控制消息通过 API 将规划控制消息传入 SimOne 仿真系统来验证主车控制结果的准确性。

算法流程图

PNC API

 // 主车Id
 const char* mv_id = "0";
 // 是否加入帧同步
 bool isJoinTimeLoop = false;
 // BridgeIO 服务 Ip
     const char* serverIP = "10.66.9.194";
 // 初始化 SimOneAPI
 InitSimOneAPI("0", isJoinTimeLoop, serverIP);

 // 控制方式一: 设置主车位置 API
std::unique_ptr<SimOne_Data_Pose_Control> pPose = std::make_unique<SimOne_Data_Pose_Control>();
[](pPose.get())
{
   // 控制算法输出主车轨迹点,Eg:
  pPose->posX; // Position X on Opendrive (by meter)
  pPose->posY; // Position Y on Opendrive (by meter)
  pPose->posZ; // Position Z on Opendrive (by meter)
  pPose->oriX; // Rotation X on Opendrive (by radian)
  pPose->oriY; // Rotation Y on Opendrive (by radian)
  pPose->oriZ; // Rotation Z on Opendrive (by radian)
  pPose->autoZ; // Automatically set Z according to scene
};
// mainVehicleId[input param]: Vehilcle index, configure order of web UI, starts from 0
// pPose[input param]: Pose to set
 if (!SimOneAPI::SetPose(0, &pose_ctl))
 {
   std::cout << "Set Pose failed!" << std::endl;
 }

// 控制方式二:主车控制 (通过油门、刹车、方向等消息驱动主车(有动力学),控制参数由算法端提供)
std::unique_ptr<SimOne_Data_Control> pCtrl = std::make_unique<SimOne_Data_Control>();
[](pCtrl.get())
{
   // ToDo: 控制算法输出控制消息
   // Eg:
   pCtrl->timestamp; // uint64  时间戳,单位us
   pCtrl->throttleMode = ESimOne_Throttle_Mode::ESimOne_Throttle_Mode_Speed; // vehicle speed, m/s,   in this mode, brake input is ignored
   pCtrl->throttle; // m/s  double 油门开度 0-100。100表示最大油门驱动
   pCtrl->steeringMode = ESimOne_Steering_Mode::ESimOne_Steering_Mode_SteeringWheelAngle; // steering wheel angle, degree
   pCtrl->steering;
   pCtrl->isManualGear = false;
   pCtrl->gear = ESimOne_Gear_Mode::ESimOne_Gear_Mode_Drive; // forward gear for automatic gear
}
// mainVehicleId[input param]: Vehilcle index, configure order of web UI, starts from 0
// pControl[input param]: vehicle control data
 if (!SetDrive(0, pCtrl.get()))
 {
   std::cout << "SetDrive Failed!" << std::endl;
 }

// 控制方式三:主车控制 (通过规划轨迹点驱动主车(有动力学),不可同时使用SetDrive)
std::unique_ptr<SimOne_Data_Control_Trajectory> pTraj = std::make_unique<SimOne_Data_Control_Trajectory>();
[](pTraj.get())
{
   // ToDo: 控制算法输出规划轨迹
   // Eg:
   for (int i = 0; i < pTraj->point_num; i++)
   {
      pTraj->points[i].posx; // position x
      pTraj->points[i].posy; // position y
      pTraj->points[i].speed; // m/s
      pTraj->points[i].accel; // accelelation m/s^2
      pTraj->points[i].theta; // yaw   rad
      pTraj->points[i].kappa; // curvature
      pTraj->points[i].relative_time; // time relative to the first trajectory point
      pTraj->points[i].s; // distance from the first trajectory point
      pTraj->isReverse = false;
   }
}
// mainVehicleId[input param]: Vehilcle index, configure order of web UI, starts from 0
// pControlTrajectory[input param]: vehicle planning trajectory
 if (!SetDriveTrajectory("0", pTraj.get()))
 {
   std::cout << "SetDrive Failed!" << std::endl;
 }

编译环境

  • PNC API Tutorial 示例工程目录结构

Tutorial
 ├── bin
 │   ├── DynamicsTest
 │   ├── HDMap
 │   ├── logServer.txt
 │   ├── log_taskImage.txt
 │   ├── PNCSample
 │   ├── SensorSample
 │   └── SensorV2X
 ├── Build
 │   ├── build_debug.bat
 │   ├── build_release
 │   ├── build_release.bat
 │   ├── CMakeLists.txt
 │   ├── gen_make_debug.sh
 │   ├── gen_make_release.sh
 │   ├── gen_vs_proj_debug.bat
 │   ├── gen_vs_proj_release.bat
 │   ├── rebuild_debug.sh
 │   └── rebuild_release.sh
 ├── PNC
 │   ├── CMakeLists.txt
 │   ├── gen_vs_proj.bat
 │   ├── include
 │   └── src

bin:目标生成目录
Build: 编译目录
HDMap: HDMap API 示例源码目录
  • 编译:

    CMakeList.txt 支持生成windows / ubuntu 的项目工程

    Windows:
    1. 进入Build目录,运行 gen_vs_proj_debug.bat 或 gen_vs_proj_release.bat 生成 Visual Studio 工程

    2. 打开 Visual Studio 示例工程, 选择 HDMap 工程编译

    Linux:
    1. cd Build

    2. ./gen_make_debug.sh (或 ./gen_make_release.sh)

    3. cd build_debug(或 cd build_release)

    4. make -j4

使用流程

  • API测试:
    • 启动Sim-One,新建测试案例

    • 新建测试主车(配置控制系统为 手动 / API 控制)

    • 运行案例(选择主车为该主车)

    • 编译测试代码,SDK/bin目录下生成可执行文件

    • 运行示例程序 ,查看运行结果

V2X

V2XADAS

算法构思

国标中有五种消息BSM、RSI、RSM、SPAT、MAP

BSM:即Basic Safety Message,基础安全消息,包括速度,转向,刹车,双闪,位置等等,多被用在V2V场景即变道预警,盲区预警,交叉路口碰撞预警等等;

RSI:即Road Side Information,路侧信息,用于事件的下方,路侧RSU集成,平台下发,多被用于V2I场景即道路施工,限速标志,超速预警,公交车道预警等等;

RSM:即Road Safety Message,路侧安全消息,也是V2I,主要对接路侧的边缘设备,用于事件的识别,比如,车辆发生事故,车辆异常,异物闯入等等;

SPAT:即Signal phase timing message,交通灯相位与时序消息,也是V2I,路侧RSU集成信号机,或者信号机通过UU方式传入到平台,用于车速引导,绿波推送场景等等;

MAP:即MAP,地图消息,地图消息和SPAT消息一起使用,MAP消息可以描述一个路口,和该路口的红绿灯也存在对应关系;

SimOne 仿真 V2X 传感器节点综合仿真系统内部的感知、交通流,路侧设备以及路网等数据,按照国标 V2X 数据格式转换为相应类型的消息,通过 SimOne V2X API 输出给使用了 V2X 消息的 Adas 算法来做训练

算法流程图

V2XAPI

 // 主车Id
 const char* mv_id = "0";
 // 是否加入帧同步
 bool isJoinTimeLoop = false;
 // BridgeIO 服务 Ip
     const char* serverIP = "127.0.0.1";
 // 初始化 SimOneAPI
 InitSimOneAPI("0", isJoinTimeLoop, serverIP);

 // 回调方式获取真值数据
if (IsCallBackMode) {
             auto function = [](const char* mainVehicleId, const char* sensorId, SimOne_Data_V2XNFS *pDetections) {
                     std::cout << "sensorId:" << sensorId << std::endl;
      std::cout <<" SetV2XInfoUpdateCB strlen= " << pDetections->V2XMsgFrameSize << std::endl;
      std::cout  << "MsgFrameData: " << pDetections->MsgFrameData << std::endl;
             };

   // 获得对应车辆编号V2X中的UPER编码之后的v2x消息更新回调
             SetV2XInfoUpdateCB(function);
     }
     else {
             std::unique_ptr<SimOne_Data_V2XNFS> pDetections = std::make_unique<SimOne_Data_V2XNFS>();
             while (true)
   {
                // 获得对应车辆编号V2X中的UPER编码之后的v2x消息
                     if (GetV2XInfo(mv_id, "obu1" /*V2X Sensor ID*/, ESimOne_V2X_MessageFrame_PR::ESimOne_V2X_MessageFrame_PR_rsiFrame /* V2X 消息类型 */, pDetections.get()))
      {
                             std::cout << "GetV2XInfo strlen = " << strlen(pDetections->MsgFrameData) << std::endl;
         std::cout << "MsgFrameData: " << pDetections->MsgFrameData << std::endl;
                             std::this_thread::sleep_for(std::chrono::milliseconds(20));
                     }
                     else {
                             std::cout << "GetV2XInfo Fail" << std::endl;
                     }
                     std::this_thread::sleep_for(std::chrono::milliseconds(10));
             }
     }

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

  • V2X Tutorial 示例工程目录结构

Tutorial
 ├── bin
 │   ├── DynamicsTest
 │   ├── HDMap
 │   ├── logServer.txt
 │   ├── log_taskImage.txt
 │   ├── PNCSample
 │   ├── SensorSample
 │   └── SensorV2X
 ├── Build
 │   ├── build_debug.bat
 │   ├── build_release
 │   ├── build_release.bat
 │   ├── CMakeLists.txt
 │   ├── gen_make_debug.sh
 │   ├── gen_make_release.sh
 │   ├── gen_vs_proj_debug.bat
 │   ├── gen_vs_proj_release.bat
 │   ├── rebuild_debug.sh
 │   └── rebuild_release.sh
 └── V2X
     └── V2XADAS

bin:目标生成目录
Build: 编译目录
HDMap: HDMap API 示例源码目录

编译:
   CMakeList.txt 支持生成windows / ubuntu 的项目工程

   Windows:
      1. 进入Build目录,运行 gen_vs_proj_debug.bat 或 gen_vs_proj_release.bat 生成 Visual Studio 工程
      2. 打开 Visual Studio 示例工程, 选择 V2X 工程编译

   Linux:
      1. cd Build
      2. ./gen_make_debug.sh (或  ./gen_make_release.sh)
      3. cd build_debug(或 cd build_release)
      4. make -j4

使用流程

  • API测试:
    • 启动Sim-One,新建测试案例(案例交通参与者设置OBU)

    • 新建测试主车(启用OBU 配置控制系统为 手动 / API 控制)

    • 运行案例(选择主车为该主车)

    • 编译测试代码,SDK/bin目录下生成可执行文件

    • 运行示例程序 ,查看运行结果

Traffic

算法构思

动态交通流API可以让用户控制场景里面的对手车的轨迹。

算法流程图

对手车的轨迹在外部json文件里面配置。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在场景中需要使用交通流案例,把类型设置为api。

../../_images/trafficflow-api.png

Dynamics

算法构思

分别使用SimOneNetAPI测试配置车辆的加速,制动性能以及操稳。

算法流程图

百公里加速测试; 百公里加速后制动测试; 阶跃,斜坡以及sine扫频转向测试。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne中运行案例,在VS中运行算法。如果指定结果保存路径,测试的结果将在路径下生产CSV文件,如果无指定路径,将在默认exe路径下保存。另外,测试中包含对转向系统的时域扫频测试,可以参照文件中包含的PostProcessing.m文件在MATLAB中进行频域后处理。 在保存数据时,在执行exe文件后加上 -csvPath“文件名.csv”这样便会在相应路径下生成测试结果。

Autopilot

CurveSample

算法构思

综合演示SimOne API的例子。

算法流程图

获取一个从起点到终点的roadId集合作为规划的参考。这个集合包含从起点到终点的所有途径的道路的编号。

你可以把naviRoadIdList理解为一个全局规划的路径集合,相当于高德地图,或者百度地图返回给你一个从起点到终点的road id 的集合,供您参考,然后你自己再设计一个局部规划路径的方法GetReferencePath, 来和这个baseline的数据集 naviRoadIdList [roadId] 进行对比,做出你自己的判断,决策,选取哪个roadid作为后继车道,继续往后找后继车道(roadId_sectionIndex_laneId),直到终点。

GetReferencePath 函数的功能在于实时获取主车所在roadId, 和先前地图系统里面的返回的道路编号集合naviRoadIdList进行对比。

1.获取主车所在车道 laneName, GetNearMostLane

2.把当前车道的centerLine顶点添加到path变量。AddSamples

3.While (index < (int)naviRoadIdList.size()) {

​ long roadId = naviRoadIdList[index];

​ long nextRoadId = naviRoadIdList[index + 1];

循环查找正确的后继道路

GetValidSuccessor(id, roadId, nextRoadId, successorId) }

  1. 设计GetValidSuccessor()函数,不同赛题需设计各自的规划方法,本题中该函数工作思路如下:局部规划路径,找到下一个后继道路和

naviRoadIdList返回的全局道路,做对比。

设计GetValidSuccessor()函数,该函数工作思路如下:局部规划路径,找到下一个后继道路和naviRoadIdList返回的全局道路,做对比。

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

LimitChangeLaneSample

算法构思

算法流程图

计算A,B,C点,后将S->A->B->C->E作为算法设计的路径

M点(目标障碍物)投影到车道“1_0_-1”的虚拟中心线得到B点

M点同车道s方向后退30米,得到A点

M点同车道s方向前进30米,得到C点

M点(目标障碍物)投影到车道“1_0_-1”的虚拟中心线得到B点获取B点位置。

A点到B点的插值距离,这里用直线, 你也可以用Clothoid螺旋曲线

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

PredefinedRouteSample

算法构思

得到既定的在网页上编辑的轨迹点。

算法流程图

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

TrafficLightSample

算法构思

获取场景中交通灯的相位状态。

算法流程图

编译环境

CMakeList.txt 支持生成windows / ubuntu 的项目工程。

使用流程

在SimOne 中运行案例,在VS中运行算法。

Matlab

使用说明

请参考软件在环测试中的simulink联合仿真部分。