开发者上手 ¶
1. 关于 ¶
SimOne 是 51SIM 自主研发的一款集 静态和动态数据导入、测试场景案例编辑、传感器仿真、动力学仿真、可视化、测试与回放、虚拟数据集生成 等一体化的自动驾驶仿真与测试平台。平台提供了多种类型和语言的 API 接口实现外部算法系统与仿真平台的通讯机制,可以满足 L2/L3/L4 算法的测试与训练。仿真平台基本实现全模块开放性,可以支持 感知、融合、决策、规划及控制算法 的部分开环或整体闭环测试,主要应用场景如下:
-
感知算法 + 仿真平台开环 :满足目标识别和预测的测试,可拓展支持多传感器分布式及 HIL
-
融合算法 + 仿真平台开环 :通过获取单传感器目标级真值开展感知融合算法的测试和训练
-
决策规划控制算法 + 仿真平台开环 :跳过感知融合模块,利用多传感器融合后目标级真值开展相关算法的测试,可拓展支持无 GPU 的云端大规模部署和并发运行
-
感知融合决策规划控制算法 + 仿真平台闭环 :完整链路的闭环测试,可拓展整车在环 VIL
2. API 概览 ¶
2.1 多语言与框架技术接口 ¶
| 类别 | API 接口 | 描述 |
|---|---|---|
| 语言支持 | C++ | 为使用 C++开发的项目提供接口支持。 |
| Python | 提供 Python 语言的接口支持,方便进行快速开发和原型制作。 | |
| 运行控制 | Restful API | 提供基于 HTTP 的 Restful API,支持 Web 服务接口,控制 SimOne 界面的运行流程,比如可控制创建案例库,导入导出案例,运行停止案例等。 |
| API + 第三方中间件 | Simulink | 提供 Simulink 接口,适用于模拟和模型基础的设计。 |
| ROS1/2 | 支持 ROS1/2 框架,便于机器人操作系统中的应用开发。 |
2.2 功能支持 ¶
| API 类型 | API 接口 | 功能 |
|---|---|---|
|
1. 基础服务类
主要提供车辆选择、仿真工作模式设置和热区数据获取的功能。 |
ServiceAPI |
选择车辆:
选择具体的目标车辆进行控制,并订阅其状态更新
设置仿真工作模式: 根据需要选择帧同步(保证实时性和稳定性)或非帧同步(提高运行效率)模式 获取热区数据: 通过主动 API 调用或自动回调函数获取车辆及其周边环境的实时数据 |
|
2. 传感器类
为开发者提供了从 SimOne 仿真环境中获取各种传感器数据的能力。 |
SensorAPI |
获取目标级或物理级信息:
包括图像信息、激光雷达点云、毫米波雷达及超声波雷达目标级信息等
获取传感器真值数据: 既能满足感知算法接入测试,也能满足跳过感知,直接从决策算法接入的开环测试需求 环境信息配置与管理 :涉及获取和设置与仿真环境相关信息(如天气、光照和地面条件等),对于创建特定测试场景非常关键。 |
| StreamingAPI | 获取物理级传感器流式传输 :实时获取和自动回调图像及点云数据,支持多种格式。 | |
| V2XAPI | V2X 消息处理 :获取特定车辆 UPER 编码的 V2X 消息及更新通知。 | |
|
3. 控制通信类
通过控制信号输入驱动被测车辆运行,实现复杂交通场景模拟。 |
PNCAPI |
车辆状态与初始化
:涵盖选择测试车辆、初始化状态信息、设置起始位置和重置车辆状态的操作。
预警信息与控制策略 :包括设置和接收预警信息、控制车辆动作,以及规划控制输出的必要接口,确保测试车辆按照算 法进行动态响应。 |
|
4. 高精地图运行时类
为决策算法提供厘米级高精度地图信息,包括路网和交通元素,支持包括路径规划和定位在内的 多种 API 调用。 |
HDMapAPI |
地图与车道分析
:提供高精地图加载及车道详细信息查询,强化定位和路由能力。
环境识别与判断 :集成交通灯、标志、停车位等环境要素的识别,辅助决策及判断。 |
|
5. 评价算法类
获取用户自定义评价功能所需要的基本仿真数据以及评价需要的用户规控算法内部相关信号。 |
EvaluationAPI | 存取评价数据 :存取用户自定义的评价功能所需的数据,用于用户自定义的评价算法。 |
2.3 API 调用示例 ¶
注意
[SimOne-安装目录]/SimOne/SimOneAPI 中的范例代码根据目录分类,演示了 SimOne 仿真产品的各类 API 在客户本地算法程序中的应用。
下方链接主要为 API调用参考示例,具体可查看 API调用参考示例 。
| 示例 | 文件夹 | 描述 | 子文件夹 | 描述 |
|---|---|---|---|---|
| 算法示例 | ADAS | ADAS 基础算法对接 SimOne 仿真平台接口应用示例。 | ACC | 自适应巡航控制算法示例。 |
| AEB | 自动紧急制动算法示例。 | |||
| AEB-Daemon | 云仿真环境连续案例运行 AEB 算法示例。 | |||
| AEB-Evaluation | 以 AEB 算法为例,展示如何在用户算法内输出评价所需要的信号数据。 | |||
| AVP | 自动泊车算法示例。 | |||
| bin | ADAS 算法应用程序生成目录。 | |||
| Build | 用于存放构建和编译项目产生的文件目录。 | |||
| LKA | 自动车道保持巡航算法示例。 | |||
| TestEvaluation | 用于测试和示范如何利用 EvaluationAPI 获取评价所需要的数据。 | |||
| TrajectoryControl | 控制车辆行驶轨迹的系统或算法。 | |||
| util | 包含一系列辅助工具和实用程序的目录。 | |||
| Autopilot | 自动驾驶算法综合 | CurveSample | 全局路径规划和局部路径调整示例 | |
| LimitChangeLaneSample | 前方有障碍物示例 | |||
| TrafficLightSample | 获取场景中交通灯的相位状态示例 | |||
| 库 | include | 包含 SimOne 自带的库和第三方的调用的依赖库文件,主要包括一些 .h 和 .hpp 。 | ||
| lib | 包含 运行 SimOne 需要依赖的动态库,C++API 的头文件、数据结构文件,PythonAPI 的头文件、数据结构文件,PythonAPI 的算法示例。 | |||
| 适配第三方中间件 | Cyber | Apollo(r6.0.0)对接 SimOne 仿真平台基于 Cyber 中间件的接口示例。 | ||
| Matlab | SimOneAPI 在 Simulink 中的封装,包含模块接口和示例。 | |||
| ROS | 对接 SimOne 仿真平台基于 ROS1 中间件的接口示例。 | |||
| ROS2 | 对接 SimOne 仿真平台基于 ROS2 中间件的接口示例。 | |||
| SensorRaw | 物理级数据可视化接口示例。 | 3rdparty | 第三方插件 opencv,pcl | |
| SensorCamera | 物理级摄像头数据传输示例 | |||
| SensorLidar | 物理级激光雷达数据传输示例 | |||
| SensorLidarROS | 物理级激光雷达数据传输至 ROS 示例 | |||
| SensorRadar4D | 4D 毫米波雷达数据传输示例 | |||
| 功能模块示例 | Tutorial | SimOneAPI C++ 接口基础调用方法示例。 | Dynamics | 动力学 使用示例 |
| HDMap | HDMapAPI 使用示例 | |||
| PNC | PNCAPI 使用示例 | |||
| Sensor | 传感器 使用示例 | |||
| Traffic | 交通流 API 使用示例 | |||
| V2X | V2X 使用示例 | |||
3. 技术架构 ¶
3.1 技术架构图 ¶
3.2 自动驾驶算法联调的基本流程 ¶
以 Apollo 为例,可以通过设计一个 bridge 程序
CybertronBridgeApollo
,控制 Apollo 算法的启停,自动设置部分 Apollo 参数,结合 SimOne 案例集,达到
自动化测试
的目的。
CybertronBridgeApollo
桥接程序的主要工作包括两部分:
准备加载的信息
和
实时传递的数据。
-
控制流 :
-
在案例运行之前,必须加载某些信息,例如 车辆的具体参数、相机配置参数、地图 等。这类信息随着案例的不同或主车设置的变化而变化,但在案例运行过程中则保持不变。
-
这类信息被称作“控制流”,它们需要在案例启动之前预先设置好并传递给 Apollo。
-
-
数据流 :
-
案例运行时会实时产生另一些数据,例如 GPS 信息、主车底盘信息、图像及点云数据 。
-
这类信息被称作“数据流”,需要不断实时地传递给 Apollo 算法进行处理。
-
通过这种方式,
CybertronBridgeApollo
能够确保 Apollo 自动驾驶平台在测试案例运行时接收到所需的所有必要信息和实时数据,以确保正确地执行自动化测试。具体实现流程如下:
3.3 SimOne 支持的算法联调场景 ¶
3.3.1 只接入决策规划 ¶
-
示例伪代码: C++
// 主车Id
const char* mv_id = "0";
// 是否加入帧同步
bool isJoinTimeLoop = false;
// BridgeIO 服务 Ip
const char* serverIP = "127.0.0.1";
// 初始化 SimOneAPI
InitSimOneAPI("0", isJoinTimeLoop, serverIP);
// 回调方式获取底盘等gps数据
if (IsCallBackMode)
{
auto function = [](const char* mainVehicleId, SimOne_Data_Gps *pGps){
output_gps(pGps);
};
SetGpsUpdateCB(function);
}
// 非帧同步方式获取底盘等gps数据
else
{
std::unique_ptr<SimOne_Data_Gps> pGps = std::make_unique<SimOne_Data_Gps>();
int lastFrame = 0;
while(true)
{
bool flag = GetGps(mv_id, pGps.get());
if (flag && pGps->frame != lastFrame)
{
lastFrame = pGps->frame;
output_gps(pGps.get());
}
if (!flag)
{
std::cout<<"Get GPS Fail"<< std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
// 获取案例结束状态
if (SimOneAPI::GetCaseRunStatus() == ESimOne_Case_Status::ESimOne_Case_Status_Stop)
// 关闭 SimOneAPI
if (!SimOneAPI::TerminateSimOneAPI())
{
std::cout << "TerminateSimOneAPI Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
}
// GPS 数据:
void output_gps(SimOne_Data_Gps* pData)
{
std::cout<<"frame:"<< pData->frame << std::endl;
std::cout << "posX/Y/Z: [" << pData->posX << ", " << pData->posY << ", " << pData->posZ << "]" << std::endl;
std::cout << "oriX/Y/Z: [" << pData->oriX << ", " << pData->oriY << ", " << pData->oriZ << "]" << std::endl;
std::cout << "velX/Y/Z: [" << pData->velX << ", " << pData->velY << ", " << pData->velZ << "]" << std::endl;
std::cout << "throttle: " << pData->throttle << std::endl;
std::cout << "brake: " << pData->brake << std::endl;
std::cout << "steering: " << pData->steering << std::endl;
std::cout << "gear: " << pData->gear << std::endl;
std::cout << "accelX/Y/Z: " << pData->accelX << ", " << pData->accelY << ", " << pData->accelZ << "]" << std::endl;
std::cout << "angVelX/Y/Z: " << pData->angVelX << ", " << pData->angVelY << ", " << pData->angVelZ << "]" << std::endl;
std::cout << "wheelSpeedFL: " << pData->wheelSpeedFL << std::endl;
std::cout << "wheelSpeedFR: " << pData->wheelSpeedFR << std::endl;
std::cout << "wheelSpeedRL: " << pData->wheelSpeedRL << std::endl;
std::cout << "wheelSpeedRR: " << pData->wheelSpeedRR << std::endl;
std::cout << "engineRpm: " << pData->engineRpm << std::endl;
std::cout << "odometer: " << pData->odometer << std::endl;
}
// 调用第三方决策控制算法,通过获取到的数据去计算生成control,pose
{
// 方式一:通过设置位置点移动主车(无动力学)
std::unique_ptr<SimOne_Data_Pose_Control> pPose = std::make_unique<SimOne_Data_Pose_Control>();
[](pPose.get())
{
// 生成主车轨迹点,Eg:
// Position X on Opendrive (by meter)
pPose->posX = m_gps.posX + cos(m_gps.oriZ); // 基于主车当前位置 X 方向移动一米
// Position Y on Opendrive (by meter)
pPose->posY = m_gps.posY + sin(m_gps.oriZ);
// Position Z on Opendrive (by meter)
pPose->posZ = m_gps.posZ;
// Rotation X on Opendrive (by radian)
pPose->oriX = m_gps.oriX;
// Rotation Y on Opendrive (by radian)
pPose->oriY = m_gps.oriY;
// Rotation Z on Opendrive (by radian)
pPose->oriZ = m_gps.oriZ;
// Automatically set Z according to scene
pPose->autoZ = false;
};
// 方式二:通过油门、刹车、方向消息驱动主车(有动力学)
std::unique_ptr<SimOne_Data_Control> pCtrl = std::make_unique<SimOne_Data_Control>();
[](pCtrl.get())
{
// 生成控制消息,Eg:
pCtrl->timestamp = getCurrentTime(); // uint64 时间戳,单位us
pCtrl->throttleMode = ESimOne_Throttle_Mode::ESimOne_Throttle_Mode_Speed; // vehicle speed, m/s, in this mode, brake input is ignored
pCtrl->throttle = 10; // m/s double 油门开度 0-100。100表示最大油门驱动
pCtrl->steeringMode = ESimOne_Steering_Mode::ESimOne_Steering_Mode_SteeringWheelAngle; // steering wheel angle, degree
pCtrl->steering = 0;
pCtrl->isManualGear = false;
pCtrl->gear = ESimOne_Gear_Mode::ESimOne_Gear_Mode_Drive; // forward gear for automatic gear
}
// 方式三:通过规划轨迹点驱动主车(有动力学)
std::unique_ptr<SimOne_Data_Control_Trajectory> pTraj = std::make_unique<SimOne_Data_Control_Trajectory>();
[](pTraj.get())
{
// 生成规划轨迹,Eg:
float posx = m_gps.posX; // position x
float posy = m_gps.posY; // position y
float speed = 10; // m/s
float accel = 1; // accelelation m/s^2
float theta = m_gps.oriZ; // yaw rad
float kappa = 0; // curvature
float relative_time = 0; // time relative to the first trajectory point
float s = 0; // distance from the first trajectory point
pTraj->point_num = 10;
for (int i = 0; i < pTraj->point_num; i++)
{
pTraj->points[i].posx = posx;
pTraj->points[i].posy = posy;
pTraj->points[i].speed = speed;
pTraj->points[i].accel = accel;
pTraj->points[i].theta = theta;
pTraj->points[i].kappa = kappa;
pTraj->points[i].relative_time = relative_time;
pTraj->points[i].s = s;
posx = posx + cos(theta);
posy = posy + sin(theta);
relative_time += 1;
s += 1;
}
pTraj->isReverse = false;
}
}
/* 控制方式一:设置主车位置 API
* input param:
* mainVehicleId: Vehilcle index, configure order of web UI, starts from 0
* pPose: Pose to set
* return: Success or not
*/
if (!SimOneAPI::SetPose(0, &pose_ctl))
{
std::cout << "Set Pose failed!" << std::endl;
}
/* 控制方式二:主车控制 (通过油门、刹车、方向等消息驱动主车(有动力学),控制参数由算法端提供)
* input param:
* mainVehicleId: Vehilcle index, configure order of web UI, starts from 0
* pControl: vehicle control data
* return: Success or not
*/
if (!SetDrive(0, pCtrl.get()))
{
std::cout << "SetDrive Failed!" << std::endl;
}
/* 控制方式三:主车控制 (通过规划轨迹点驱动主车(有动力学),不可同时使用SetDrive)
* input param:
* mainVehicleId: Vehilcle index, configure order of web UI, starts from 0
* pControlTrajectory: vehicle planning trajectory
* return: Success or not
*/
if (!SetDriveTrajectory("0", pTraj.get()))
{
std::cout << "SetDrive Failed!" << std::endl;
}
3.3.2 感知算法训练 ¶
-
示例伪代码: C++
// 主车Id
const char* mv_id = "0";
// 是否加入帧同步
bool isJoinTimeLoop = false;
// BridgeIO 服务 Ip
const char* serverIP = "10.66.9.194";
// 初始化 SimOneAPI
InitSimOneAPI("0", isJoinTimeLoop, serverIP);
// 回调方式获取真值数据
if (IsCallBackMode)
{
auto function = [](const char* mainVehicleId, SimOne_Data_Obstacle *pObstacle) {
output_ground_truth(pObstacle);
};
SetGroundTruthUpdateCB(function);
}
// 非帧同步方式获取真值数据
else {
std::unique_ptr<SimOne_Data_Obstacle> pObstacle = std::make_unique<SimOne_Data_Obstacle>();
int lastFrame = 0;
while (true) {
bool flag = GetGroundTruth(mv_id, pObstacle.get());
if (flag && pObstacle->frame != lastFrame)
{
lastFrame = pObstacle->frame;
output_ground_truth(pObstacle.get());
}
if (!flag)
{
std::cout << "GetGroundTruth Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
}
// 真值数据:
void output_ground_truth(SimOne_Data_Obstacle* pObstacle)
{
std::cout <<"frame:"<< pObstacle->frame << std::endl;
std::cout << "obstacleSize: " << pObstacle->obstacleSize << std::endl;
for (int i=0; i<pObstacle->obstacleSize ; i++)
{
std::cout << "obstacle[" << i << "].id: " << pObstacle->obstacle[i].id << std::endl;
std::cout << "obstacle[" << i << "].viewId: " << pObstacle->obstacle[i].viewId << std::endl;
std::cout << "obstacle[" << i << "].type: " << pObstacle->obstacle[i].type << std::endl;
std::cout << "obstacle[" << i << "].theta: " << pObstacle->obstacle[i].theta << std::endl;
std::cout << "obstacle[" << i << "].posX/Y/Z: [" << pObstacle->obstacle[i].posX << ", " << pObstacle->obstacle[i].posY << ", " << pObstacle->obstacle[i].posZ << "]" << std::endl;
std::cout << "obstacle[" << i << "].oriX/Y/Z: [" << pObstacle->obstacle[i].oriX << ", " << pObstacle->obstacle[i].oriY << ", " << pObstacle->obstacle[i].oriZ << "]" << std::endl;
std::cout << "obstacle[" << i << "].velX/Y/Z: [" << pObstacle->obstacle[i].velX << ", " << pObstacle->obstacle[i].velY << ", " << pObstacle->obstacle[i].velZ << "]" << std::endl;
std::cout << "obstacle[" << i << "].length: " << pObstacle->obstacle[i].length << std::endl;
std::cout << "obstacle[" << i << "].width: " << pObstacle->obstacle[i].width << std::endl;
std::cout << "obstacle[" << i << "].height: " << pObstacle->obstacle[i].height << std::endl;
std::cout << "obstacle[" << i << "].accelX/Y/Z: [" << pObstacle->obstacle[i].accelX << ", " << pObstacle->obstacle[i].accelY << ", " << pObstacle->obstacle[i].accelZ << "]" << std::endl;
}
}
// 获取案例结束状态
if (SimOneAPI::GetCaseRunStatus() == ESimOne_Case_Status::ESimOne_Case_Status_Stop)
// 关闭 SimOneAPI
if (!SimOneAPI::TerminateSimOneAPI())
{
std::cout << "TerminateSimOneAPI Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
}
// 摄像头节点 udp server ip
const char* img_ip = "127.0.0.1";
// 摄像头节点 udp server port
unsigned short img_port = 123456;
// 回调方式获取摄像头传感器物理级数据
if (IsCallBackMode)
{
auto function = [](SimOne_Streaming_Image* pImage) {
output_image(pImage);
};
SetStreamingImageUpdateCB(img_ip, img_port, function);
}
// 非帧同步方式获取摄像头传感器物理级数据
else
{
std::unique_ptr<SimOne_Streaming_Image> pImage= std::make_unique<SimOne_Streaming_Image>();
int lastFrame = 0;
while (true)
{
bool flag = GetStreamingImage(img_ip, img_port, pImage.get());
if (flag && pImage->frame != lastFrame)
{
lastFrame = pImage->frame;
output_image(pImage.get());
}
if (!flag)
{
std::cout << "GetStreamingImage Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
}
// 图像数据:
void output_image(SimOne_Streaming_Image* pImage)
{
if (pImage->width != 0 && pImage->height != 0)
{
std::cout << "frame: " << pImage->frame << std::endl;
std::cout << "width: " << pImage->width << std::endl; // int Image resolution width 1920 max
std::cout << "height: " << pImage->height << std::endl; // int Image resolution height 1080 max
std::cout << "imageDataSize: " << pImage->imageDataSize << std::endl; // 1920 x 1080 x 3 max
std::cout << "imageData: " << pImage->imageData << std::endl;
}
}
// 激光雷达节点 udp server ip
const char* pcd_ip = "127.0.0.1";
// 激光雷达节点 udp server port
unsigned short pcd_port = 123456;
// 激光雷达节点 udp server info_port
unsigned short pcd_info_port = 654321;
// 回调方式获取激光雷达传感器物理级数据
if (IsCallBackMode)
{
auto function = [](SimOne_Streaming_Point_Cloud* pPointcloud) {
output_point_cloud(pPointcloud);
};
SetStreamingPointCloudUpdateCB(pcd_ip, pcd_port, pcd_info_port, function);
}
// 非帧同步方式获取激光雷达传感器物理级数据
else
{
std::unique_ptr<SimOne_Streaming_Point_Cloud> pPointCloud = std::make_unique<SimOne_Streaming_Point_Cloud>();
int lastFrame = 0;
while (true) {
bool flag = GetStreamingPointCloud(pcd_ip, pcd_port, pcd_info_port, pPointCloud.get());
if (flag && pPointCloud->frame != lastFrame)
{
lastFrame = pPointCloud->frame;
output_point_cloud(pPointcloud.get());
}
if (!flag)
{
std::cout << "GetStreamingPointCloud Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(1));
}
}
// 点云数据:
static std::string sNames[] = {"x", "y", "z", "intensity"};
static int sOffsets[] = {0, 4, 8, 12};
static int sDatatypes[] = {7, 7, 7, 7};
void output_point_cloud(SimOne_Streaming_Point_Cloud* pPointcloud)
{
std::cout << "frame: " << pPointcloud->frame << std::endl; // sequence number long long
std::cout << "pointStep: " << pPointcloud->pointStep << std::endl; // int
std::cout << "height: " << pPointcloud->height << std::endl; // int
std::cout << "width: " << pPointcloud->width << std::endl; // int
}
// 调用第三方感知算法函数, 对真值数据、物理集数据 进行感知训练
[](pObstacle, pImage, pPointCloud)
{
// 感知训练
}
3.3.3 融合算法训练 ¶
-
示例伪代码: C++
// 主车Id
const char* mv_id = "0";
// 是否加入帧同步
bool isJoinTimeLoop = false;
// BridgeIO 服务 Ip
const char* serverIP = "10.66.9.194";
// 初始化 SimOneAPI
InitSimOneAPI("0", isJoinTimeLoop, serverIP);
// 回调方式获得所有超声波雷达信息
if (IsCallBackMode)
{
auto function = [](const char* mainVehicleId, SimOne_Data_UltrasonicRadars* pUltrasonics)
{
output_ultrasonic_radars(pUltrasonics);
};
SetUltrasonicRadarsCB(function);
}
// 非帧同步方式获得所有超声波雷达信息
else
{
std::unique_ptr<SimOne_Data_UltrasonicRadars> pDetections = std::make_unique<SimOne_Data_UltrasonicRadars>();
int lastFrame = 0;
while (true)
{
bool flag = GetUltrasonicRadars(mv_id, pDetections.get());
if (flag && pDetections->frame != lastFrame)
{
lastFrame = pDetections->frame;
output_ultrasonic_radars(pDetections.get());
}
if (!flag)
{
std::cout << "GetUltrasonicRadars Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
// 超声波雷达数据
void output_ultrasonic_radars(SimOne_Data_UltrasonicRadars* pUltrasonicData)
{
std::cout <<"ultrasonicRadarNum: " << pUltrasonicData->ultrasonicRadarNum << std::endl;
for (int i = 0; i < pUltrasonicData->ultrasonicRadarNum; i++)
{
std::cout <<"frame:"<< pUltrasonicData->ultrasonicRadars[i].frame << std::endl;
std::cout <<"sensorId:"<< pUltrasonicData->ultrasonicRadars[i].sensorId << std::endl;
std::cout <<"obstacleNum:"<< pUltrasonicData->ultrasonicRadars[i].obstacleNum << std::endl;
for (int j = 0; j < pUltrasonicData->ultrasonicRadars[i].obstacleNum; j++)
{
std::cout << "obstacleDetections[" << j << "].obstacleRanges: "<< pUltrasonicData->ultrasonicRadars[i].obstacleDetections[j].obstacleRanges << std::endl;
std::cout << "obstacleDetections[" << j << "].x: "<< pUltrasonicData->ultrasonicRadars[i].obstacleDetections[j].x << std::endl;
std::cout << "obstacleDetections[" << j << "].y: "<< pUltrasonicData->ultrasonicRadars[i].obstacleDetections[j].y << std::endl;
std::cout << "obstacleDetections[" << j << "].z: "<< pUltrasonicData->ultrasonicRadars[i].obstacleDetections[j].z << std::endl;
}
}
}
// 回调方式获得所有毫米波雷达信息
if (IsCallBackMode)
{
auto function = [](const char* mainVehicleId, const char* sensorId, SimOne_Data_RadarDetection* pRadarData)
{
output_radar_detection(pRadarData);
};
SetRadarDetectionsUpdateCB(function);
}
// 非帧同步方式获得所有毫米波雷达信息
else
{
std::unique_ptr<SimOne_Data_RadarDetection> pRadarData = std::make_unique<SimOne_Data_RadarDetection>();
int lastFrame = 0;
while (true)
{
bool flag = GetRadarDetections(mv_id, "objectBasedRadar1", pRadarData.get());
if (flag && pRadarData->frame != lastFrame)
{
lastFrame = pRadarData->frame;
output_radar_detection(pRadarData.get());
}
if (!flag)
{
std::cout << "GetRadarDetections Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(30));
}
}
// 毫米波雷达数据
void output_radar_detection(SimOne_Data_RadarDetection* pRadarData)
{
std::cout<< "frame:" << pRadarData->frame << std::endl;
std::cout<< "detectNum :" << pRadarData->detectNum << std::endl;
for (int i = 0; i < pRadarData->detectNum; i++)
{
std::cout << "detections[" << i << "].ip: " << pRadarData->detections[i].id << std::endl;
std::cout << "detections[" << i << "].subId: " << pRadarData->detections[i].subId << std::endl;
std::cout << "detections[" << i << "].type: " << pRadarData->detections[i].type << std::endl;
std::cout << "detections[" << i << "].posX/Y/Z: [" << pRadarData->detections[i].posX << ", " << pRadarData->detections[i].posY << ", " << pRadarData->detections[i].posZ << "]"<< std::endl;
std::cout << "detections[" << i << "].velX/Y/Z: [" << pRadarData->detections[i].velX << ", " << pRadarData->detections[i].velY << ", " << pRadarData->detections[i].velZ << "]"<< std::endl;
std::cout << "detections[" << i << "].accelX/Y/Z: [" << pRadarData->detections[i].accelX << ", " << pRadarData->detections[i].accelY << ", " << pRadarData->detections[i].accelZ << "]"<< std::endl;
std::cout << "detections[" << i << "].oriX/Y/Z: [" << pRadarData->detections[i].oriX << ", " << pRadarData->detections[i].oriY << ", " << pRadarData->detections[i].oriZ << "]"<< std::endl;
std::cout << "detections[" << i << "].length: " << pRadarData->detections[i].length << std::endl;
std::cout << "detections[" << i << "].width: " << pRadarData->detections[i].width << std::endl;
std::cout << "detections[" << i << "].height: " << pRadarData->detections[i].height << std::endl;
std::cout << "detections[" << i << "].range: " << pRadarData->detections[i].range << std::endl;
std::cout << "detections[" << i << "].rangeRate: " << pRadarData->detections[i].rangeRate << std::endl;
std::cout << "detections[" << i << "].azimuth: " << pRadarData->detections[i].azimuth << std::endl;
std::cout << "detections[" << i << "].vertical: " << pRadarData->detections[i].vertical << std::endl;
std::cout << "detections[" << i << "].snrdb: " << pRadarData->detections[i].snrdb << std::endl;
std::cout << "detections[" << i << "].rcsdb: " << pRadarData->detections[i].rcsdb << std::endl;
std::cout << "detections[" << i << "].probability: " << pRadarData->detections[i].probability << std::endl;
}
}
// 回调方式获取目标级传感器检测到的感知真值
if (IsCallBackMode)
{
auto function = [](const char* MainVehicleID, const char* sensorId, SimOne_Data_SensorDetections* pGroundtruth)
{
output_sensor_detections(pGroundtruth);
};
SetSensorDetectionsUpdateCB(function);
}
// 非帧同步方式获取目标级传感器检测到的感知真值
else
{
std::unique_ptr<SimOne_Data_SensorDetections> pGroundtruth = std::make_unique<SimOne_Data_SensorDetections>();
int lastFrame = 0;
while (true)
{
// "sensorFusion1" "objectBasedCamera1" "objectBasedLidar1" "perfectPerception1"
bool flag = GetSensorDetections(mainVehicleId.c_str(), "perfectPerception1", pGroundtruth.get());
if (flag && pGroundtruth->frame != lastFrame)
{
lastFrame = pGroundtruth->frame;
output_sensor_detections(pGroundtruth.get());
}
if (!flag)
{
std::cout << "GetSensorDetections Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
// 目标极传感器真值数据
void output_sensor_detections(SimOne_Data_SensorDetections* pGroundtruth)
{
std::cout << "frame:"<< pGroundtruth->frame << std::endl;
std::cout << "objectSize: "<< pGroundtruth->objectSize << std::endl;
for (int i = 0; i < pGroundtruth->objectSize; i++)
{
std::cout << "objects[" << i << "].id" << pGroundtruth->objects[i].id << std::endl;
std::cout << "obstacles[" << i << "].type: " << pGroundtruth->objects[i].type << std::endl;
std::cout << "objects[" << i << "].posX/Y/Z: " << "[" << pGroundtruth->objects[i].posX << ", " << pGroundtruth->objects[i].posY << ", " << pGroundtruth->objects[i].posZ << "]" << std::endl;
std::cout << "objects[" << i << "].oriX/Y/Z: " << "[" << pGroundtruth->objects[i].oriX << ", " << pGroundtruth->objects[i].oriY << ", " << pGroundtruth->objects[i].oriZ << "]" << std::endl;
std::cout << "objects[" << i << "].length: " << pGroundtruth->objects[i].length << std::endl;
std::cout << "objects[" << i << "].width: " << pGroundtruth->objects[i].width << std::endl;
std::cout << "objects[" << i << "].height: " << pGroundtruth->objects[i].height << std::endl;
std::cout << "objects[" << i << "].range: " << pGroundtruth->objects[i].range << std::endl;
std::cout << "objects[" << i << "].velX/Y/Z: " << "[" << pGroundtruth->objects[i].velX << ", " << pGroundtruth->objects[i].velY << ", " << pGroundtruth->objects[i].velZ << "]" << std::endl;
std::cout << "objects[" << i << "].accelX/Y/Z: " << "[" << pGroundtruth->objects[i].accelX << ", " << pGroundtruth->objects[i].accelY << ", " << pGroundtruth->objects[i].accelZ << "]" << std::endl;
std::cout << "objects[" << i << "].probability: " << pGroundtruth->objects[i].probability << std::endl;
std::cout << "objects[" << i << "].relativePosX/Y/Z: " << "[" << pGroundtruth->objects[i].relativePosX << ", " << pGroundtruth->objects[i].relativePosY << ", " << pGroundtruth->objects[i].relativePosZ << "]" << std::endl;
std::cout << "objects[" << i << "].relativeRotX/Y/Z: " << "[" << pGroundtruth->objects[i].relativeRotX << ", " << pGroundtruth->objects[i].relativeRotY << ", " << pGroundtruth->objects[i].relativeRotZ << "]" << std::endl;
std::cout << "objects[" << i << "].relativeVelX/Y/Z: " << "[" << pGroundtruth->objects[i].relativeVelX << ", " << pGroundtruth->objects[i].relativeVelY << ", " << pGroundtruth->objects[i].relativeVelZ << "]" << std::endl;
std::cout << "objects[" << i << "].bbox2dMinX: " << pGroundtruth->objects[i].bbox2dMinX << std::endl;
std::cout << "objects[" << i << "].bbox2dMinY: " << pGroundtruth->objects[i].bbox2dMinY << std::endl;
std::cout << "objects[" << i << "].bbox2dMaxX: " << pGroundtruth->objects[i].bbox2dMaxX << std::endl;
std::cout << "objects[" << i << "].bbox2dMaxY: " << pGroundtruth->objects[i].bbox2dMaxY << std::endl;
}
}
// 调用第三方融合算法函数,对目标集数据进行融合处理
[](pUltrasonicData, pRadarData, pSensorData)
{
// 融合处理
}
// 获取案例结束状态
if (SimOneAPI::GetCaseRunStatus() == ESimOne_Case_Status::ESimOne_Case_Status_Stop)
// 关闭 SimOneAPI
if (!SimOneAPI::TerminateSimOneAPI())
{
std::cout << "TerminateSimOneAPI Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
}
3.3.4 感知决策规划闭环 ¶
-
示例伪代码: C++
// 主车Id
const char* mv_id = "0";
// 是否加入帧同步
bool isJoinTimeLoop = false;
// BridgeIO 服务 Ip
const char* serverIP = "10.66.9.194";
// 初始化 SimOneAPI
InitSimOneAPI("0", isJoinTimeLoop, serverIP);
// 调用第三方感知算法函数, 对真值数据、物理集数据 进行感知训练
perception_result = [](pObstacle, pImage, pPointCloud)
{
// 感知训练
}
// 调用第三方融合算法函数,对目标集数据进行融合处理
fusion_result = [](perception_result)
{
// 融合处理
}
// 调用第三方决策控制算法,通过获取到的数据去计算生成control,pose
{
// 方式一:通过设置位置点移动主车(无动力学)
[](fusion_result)
{
SimOne_Data_Pose_Control pose_ctl;
...
SimOneAPI::SetPose(0, &pose_ctl))
};
// 方式二:通过油门、刹车、方向等消息驱动主车(有动力学)
[](fusion_result)
{
SimOne_Data_Control ctrl;
...
SetDrive(0, &ctrl);
}
// 方式三:通过规划轨迹点驱动主车(有动力学)
[](pTraj.get())
{
SimOne_Data_Control_Trajectory traj;
...
SetDriveTrajectory("0", &traj);
}
}
// 获取案例结束状态
if (SimOneAPI::GetCaseRunStatus() == ESimOne_Case_Status::ESimOne_Case_Status_Stop)
// 关闭 SimOneAPI
if (!SimOneAPI::TerminateSimOneAPI())
{
std::cout << "TerminateSimOneAPI Failed!" << std::endl;
}
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
}
4. 附录 1:系统约定 ¶
4.1 坐标系统 ¶
对于高精度地图而言,系统提供两种坐标系统:
-
世界坐标系/站心直角坐标系(Local ENU) 世界坐标系为 x,y,z 右手坐标系
惯例适用于地理参考,即对应站心直角坐标系,x 为正东(East,E),y 为正北(North,N),z 为 Up(U)。
-
参考线坐标系/轨道系统 s-t 坐标系(Track System s-t coordinate)
路网运行时根据不同参考线基准分别定义了 2 个 s-t 坐标系:
-
以 道路参考线 为基准定义 s-t 坐标系
-
以 车道虚拟中心线 为基准定义 s-t 坐标系
-
4.1.1 空间直角坐标系 ¶
-
坐标轴 :空间任意选定一点 O,过点 O 作三条互相垂直的数轴 Ox,Oy,Oz,它们都以 O 为原点且具有相同的长度单位。这三条轴分别称作 x 轴(横轴),y 轴(纵轴),z 轴(竖轴)。
-
空间直角坐标系 O-xyz :它们的正方向 符合右手规则 ,即以右手握住 z 轴,当右手的四个手指 x 轴的正向以 90 度转向 y 轴正向时,大拇指的指向就是 z 轴的正向,这样就构成了一个空间直角坐标系。
-
原点 :定点 O 称为该坐标系的原点。
与之相对应的是左手空间直角坐标系。一般在数学中更常用右手空间直角坐标系。
4.1.2 传感器坐标系 ¶
4.2 单位 ¶
| 类别 | 名称 | 英文名称/缩写 | 单位 | 描述/备注 |
|---|---|---|---|---|
| 物理量 | 长度 | Length | m | 米,用来表示位置信息 |
| 角度 | Angle | rad | 弧度,用来表示物体对于中心位置的偏移角度 | |
| 速度 | Speed | m/s | 米/秒,用来表示速度,加速度,角速度等 | |
| 转速 | RPM | r/min | 转/分钟,用来表示轮子转速,发动机转速等 | |
| 控制参数 | 油门 | Throttle | 无单位 [0-1] | 0 表示没有油门,1 表示油门最大 |
| 刹车 | Brake | 无单位 [0-1] | 0 表示不踩刹车,1 表示刹车踩到底 | |
| 方向盘 | Steering | 无单位 [-1,1] | -1 表示左打 540°,1 表示右打 540° | |
| 方向盘度量 | ESteeringMode | 无单位 | 百分比,力矩,角度来表示方向盘的幅度 | |
| 状态信息 | 手刹 | Handbrake | - | true 或者 false,表示拉起和放下手刹 |
| 档位 | EGearMode | - | 表示车辆的挡位状态,如 P 档,N 档,D 档等 | |
| 目标物类型 | SimOne_Obstacle_Type | - | 目标物的类型,如车辆、行人 | |
| 交通灯状态 | SimOne_TrafficLight_Status | - | 交通信号灯状态,如红灯、绿灯 | |
| 信号数据 | 信噪比 | SNR | dB | 分贝,信号强度比的度量单位 |
| 散射截面 | RCS | mdb | 用来表示电磁波雷达截面散射面积 | |
| 数据规格 | 点云格式 | Point Step | - | 点云的数据规格,如 16 线,32 线 |
| 检测概率 | Probability | 无单位 [0-1] | 预测模型输出的目标检测置信度 | |
| 包围盒信息 | bbox2d | 坐标信息 | 用于描述对象在图像或空间中的覆盖范围 |
5. 附录 2:专业术语 ¶
5.1 帧同步与回调函数 ¶
SimOne 系统中的帧同步是基于虚拟时间的逻辑帧,这意味着整个系统的操作都是按帧进行的:
-
帧同步的概念:
-
系统中的每个动作都依赖于逻辑帧的执行。
-
一帧的执行时间在现实中可以很短(如 0.00001 秒)或很长(如 100000 秒),而与真实时间解耦。
-
通过基于帧的时间控制,可以灵活地调节仿真系统的运行速度,例如加速或减缓案例运行。
-
-
获取 SimOne 数据的方法:
-
回调函数 :当系统有新数据时,系统会通过注册的回调函数通知用户获取数据。
-
主动调用 API :用户可以主动调用 API(如:GetGps)来获取当前帧的数据。如果系统帧没有进步,连续调用将返回相同的数据。
-
-
帧同步和数据获取的结合:
-
使用帧同步 API,可控制 SimOne 系统案例的运行时间。在某个给定帧内的数据,无论调用多少次获取数据的 API,都将是相同的。
-
如果不使用帧同步控制,直接调用 API 或回调函数获取数据的方式更为直接,适用于仅需获取场景数据的使用案例。
-
5.2 传感器仿真(目标级与物理级) ¶
传感器在自动驾驶系统中的应用可以分为 目标级 和 物理级 两大类,它们分别服务于不同的应用场景,并通过特定的 API 激活方式来开始接收数据。以下是通过表格整理的内容概览:
| 传感器类型 | 激活 API |
|---|---|
|
目标级传感器
获取目标对象的信息(如位置、速度等) 用于传感器融合算法 |
将 enable 参数设置为 true 开始接收数据
SIMONE_NET_API bool SetSensorObjectbasedDataEnable(bool enable);
|
|
物理级传感器
提供图像和点云等物理信息 用于测试和验证感知算法 |
将 enable 参数设置为 true 开始接收数据
SIMONE_NET_API bool SetSensorPhysicalbasedDataEnable(bool enable);
|
注意
额外说明 :
在 使用 UDP 数据注入 方法 获取物理级传感器数据 时, 不需要激活传感器的 API ,因为 UDP 注入会直接提供所需的数据。这一方法简化了数据获取过程,适用于物理信息的直接采集。
-
UDP :即用户数据报协议(User Datagram Protocol),是一种简单的网络通信协议,允许应用程序在不建立稳定连接的情况下发送数据包。
6. FAQ ¶
参见 用户常见问题 。