Apollo 10.0
自动驾驶开放平台
apollo::common::VehicleConfigHelper类 参考

@Brief This is a helper class that can load vehicle configurations. 更多...

#include <vehicle_config_helper.h>

apollo::common::VehicleConfigHelper 的协作图:

静态 Public 成员函数

static void Init ()
 Initialize vehicle configurations with default configuration file pointed by gflags FLAGS_vehicle_config_path.
 
static void Init (const VehicleConfig &config)
 Initialize vehicle configurations with config
 
static void Init (const std::string &config_file)
 Initialize vehicle configurations with config_file.
 
static const VehicleConfigGetConfig ()
 Get the current vehicle configuration.
 
static double MinSafeTurnRadius ()
 Get the safe turning radius when the vehicle is turning with maximum steering angle.
 
static common::math::Box2d GetBoundingBox (const common::PathPoint &path_point)
 Get the box (four corners: ABCD) of the vehicle.
 

详细描述

@Brief This is a helper class that can load vehicle configurations.

The vehicle configurations are defined modules/common/configs/proto/vehicle_config.proto

在文件 vehicle_config_helper.h45 行定义.

成员函数说明

◆ GetBoundingBox()

common::math::Box2d apollo::common::VehicleConfigHelper::GetBoundingBox ( const common::PathPoint path_point)
static

Get the box (four corners: ABCD) of the vehicle.

参数
path_pointof a vehicle (which contains point X and heading).
返回
a box2d which contains the ABCD points info.

在文件 vehicle_config_helper.cc65 行定义.

66 {
67 const auto &vehicle_param = vehicle_config_.vehicle_param();
68 math::Vec2d point(path_point.x(), path_point.y());
69 return common::math::Box2d(
70 point, path_point.theta(), vehicle_param.front_edge_to_center(),
71 vehicle_param.back_edge_to_center(), vehicle_param.width());
72}
optional VehicleParam vehicle_param

◆ GetConfig()

const VehicleConfig & apollo::common::VehicleConfigHelper::GetConfig ( )
static

Get the current vehicle configuration.

返回
the current VehicleConfig instance reference.

在文件 vehicle_config_helper.cc47 行定义.

47 {
48 if (!is_init_) {
49 Init();
50 }
51 return vehicle_config_;
52}
static void Init()
Initialize vehicle configurations with default configuration file pointed by gflags FLAGS_vehicle_con...

◆ Init() [1/3]

void apollo::common::VehicleConfigHelper::Init ( )
static

Initialize vehicle configurations with default configuration file pointed by gflags FLAGS_vehicle_config_path.

The code will crash if FLAGS_vehicle_config_path does not exist or it points to a file with invalid format.

在文件 vehicle_config_helper.cc33 行定义.

33{ Init(FLAGS_vehicle_config_path); }

◆ Init() [2/3]

void apollo::common::VehicleConfigHelper::Init ( const std::string &  config_file)
static

Initialize vehicle configurations with config_file.

The code will crash if config_file does not exist or config_file has invalid format.

参数
config_fileThe configuration file path. The format of the file is defined by protobuf file modules/common/configs/proto/vehicle_config.proto.

在文件 vehicle_config_helper.cc35 行定义.

35 {
36 VehicleConfig params;
37 ACHECK(cyber::common::GetProtoFromFile(config_file, &params))
38 << "Unable to parse vehicle config file " << config_file;
39 Init(params);
40}
#define ACHECK(cond)
Definition log.h:80
bool GetProtoFromFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as a representation of protobufs,...
Definition file.cc:132

◆ Init() [3/3]

void apollo::common::VehicleConfigHelper::Init ( const VehicleConfig config)
static

Initialize vehicle configurations with config

参数
configA VehicleConfig class instance. The VehicleConfig class is defined by modules/common/configs/proto/vehicle_config.proto.

在文件 vehicle_config_helper.cc42 行定义.

42 {
43 vehicle_config_ = vehicle_params;
44 is_init_ = true;
45}

◆ MinSafeTurnRadius()

double apollo::common::VehicleConfigHelper::MinSafeTurnRadius ( )
static

Get the safe turning radius when the vehicle is turning with maximum steering angle.

The calculation is described by the following figure.



   front of car
A +----------+ B
  |          |
  /          / turn with maximum steering angle
  |          |
  |          |
  |          |
  |    X     |                                       O
  |<-->.<----|-------------------------------------->* (turn center)
  |          |   VehicleParam.min_turn_radius()
  |          |
D +----------+ C
   back of car

 

In the above figure, The four corner points of the vehicle is A, B, C, and D. XO is VehicleParam.min_turn_radius(), X to AD is left_edge_to_center, X to AB is VehicleParam.front_edge_to_center(). Then AO = sqrt((XO + left_edge_to_center) ^2 + front_edge_to_center^2).

返回
AO in the above figure, which is the minimum turn radius when the vehicle turns with maximum steering angle

在文件 vehicle_config_helper.cc54 行定义.

54 {
55 const auto &param = vehicle_config_.vehicle_param();
56 double lat_edge_to_center =
57 std::max(param.left_edge_to_center(), param.right_edge_to_center());
58 double lon_edge_to_center =
59 std::max(param.front_edge_to_center(), param.back_edge_to_center());
60 return std::sqrt((lat_edge_to_center + param.min_turn_radius()) *
61 (lat_edge_to_center + param.min_turn_radius()) +
62 lon_edge_to_center * lon_edge_to_center);
63}

该类的文档由以下文件生成: