Apollo 10.0
自动驾驶开放平台
|
The class of vehicle state. 更多...
#include <vehicle_state_provider.h>
Public 成员函数 | |
Status | Update (const localization::LocalizationEstimate &localization, const canbus::Chassis &chassis) |
Constructor by information of localization and chassis. | |
void | Update (const std::string &localization_file, const std::string &chassis_file) |
Update VehicleStateProvider instance by protobuf files. | |
double | timestamp () const |
const localization::Pose & | pose () const |
const localization::Pose & | original_pose () const |
virtual | ~VehicleStateProvider ()=default |
Default destructor. | |
double | x () const |
Get the x-coordinate of vehicle position. | |
double | y () const |
Get the y-coordinate of vehicle position. | |
double | z () const |
Get the z coordinate of vehicle position. | |
double | kappa () const |
Get the kappa of vehicle position. | |
double | roll () const |
Get the vehicle roll angle. | |
double | pitch () const |
Get the vehicle pitch angle. | |
double | yaw () const |
Get the vehicle yaw angle. | |
double | heading () const |
Get the heading of vehicle position, which is the angle between the vehicle's heading direction and the x-axis. | |
double | linear_velocity () const |
Get the vehicle's linear velocity. | |
double | angular_velocity () const |
Get the vehicle's angular velocity. | |
double | linear_acceleration () const |
Get the vehicle's linear acceleration. | |
double | gear () const |
Get the vehicle's gear position. | |
double | steering_percentage () const |
Get the vehicle's steering angle. | |
void | set_linear_velocity (const double linear_velocity) |
Set the vehicle's linear velocity. | |
math::Vec2d | EstimateFuturePosition (const double t) const |
Estimate future position from current position and heading, along a period of time, by constant linear velocity, linear acceleration, angular velocity. | |
math::Vec2d | ComputeCOMPosition (const double rear_to_com_distance) const |
Compute the position of center of mass(COM) of the vehicle, given the distance from rear wheels to the center of mass. | |
const VehicleState & | vehicle_state () const |
The class of vehicle state.
It includes basic information and computation about the state of the vehicle.
在文件 vehicle_state_provider.h 第 46 行定义.
|
virtualdefault |
Default destructor.
double apollo::common::VehicleStateProvider::angular_velocity | ( | ) | const |
Get the vehicle's angular velocity.
在文件 vehicle_state_provider.cc 第 181 行定义.
math::Vec2d apollo::common::VehicleStateProvider::ComputeCOMPosition | ( | const double | rear_to_com_distance | ) | const |
Compute the position of center of mass(COM) of the vehicle, given the distance from rear wheels to the center of mass.
rear_to_com_distance | Distance from rear wheels to the vehicle's center of mass. |
在文件 vehicle_state_provider.cc 第 247 行定义.
math::Vec2d apollo::common::VehicleStateProvider::EstimateFuturePosition | ( | const double | t | ) | const |
Estimate future position from current position and heading, along a period of time, by constant linear velocity, linear acceleration, angular velocity.
t | The length of time period. |
在文件 vehicle_state_provider.cc 第 215 行定义.
double apollo::common::VehicleStateProvider::gear | ( | ) | const |
Get the vehicle's gear position.
在文件 vehicle_state_provider.cc 第 189 行定义.
double apollo::common::VehicleStateProvider::heading | ( | ) | const |
Get the heading of vehicle position, which is the angle between the vehicle's heading direction and the x-axis.
在文件 vehicle_state_provider.cc 第 171 行定义.
double apollo::common::VehicleStateProvider::kappa | ( | ) | const |
Get the kappa of vehicle position.
the positive or negative sign is decided by the vehicle heading vector along the path
在文件 vehicle_state_provider.cc 第 175 行定义.
double apollo::common::VehicleStateProvider::linear_acceleration | ( | ) | const |
Get the vehicle's linear acceleration.
在文件 vehicle_state_provider.cc 第 185 行定义.
double apollo::common::VehicleStateProvider::linear_velocity | ( | ) | const |
Get the vehicle's linear velocity.
在文件 vehicle_state_provider.cc 第 177 行定义.
const localization::Pose & apollo::common::VehicleStateProvider::original_pose | ( | ) | const |
在文件 vehicle_state_provider.cc 第 203 行定义.
double apollo::common::VehicleStateProvider::pitch | ( | ) | const |
const localization::Pose & apollo::common::VehicleStateProvider::pose | ( | ) | const |
在文件 vehicle_state_provider.cc 第 199 行定义.
double apollo::common::VehicleStateProvider::roll | ( | ) | const |
void apollo::common::VehicleStateProvider::set_linear_velocity | ( | const double | linear_velocity | ) |
Set the vehicle's linear velocity.
linear_velocity | The value to set the vehicle's linear velocity. |
在文件 vehicle_state_provider.cc 第 207 行定义.
double apollo::common::VehicleStateProvider::steering_percentage | ( | ) | const |
Get the vehicle's steering angle.
在文件 vehicle_state_provider.cc 第 191 行定义.
double apollo::common::VehicleStateProvider::timestamp | ( | ) | const |
在文件 vehicle_state_provider.cc 第 195 行定义.
Status apollo::common::VehicleStateProvider::Update | ( | const localization::LocalizationEstimate & | localization, |
const canbus::Chassis & | chassis | ||
) |
Constructor by information of localization and chassis.
localization | Localization information of the vehicle. |
chassis | Chassis information of the vehicle. |
在文件 vehicle_state_provider.cc 第 31 行定义.
void apollo::common::VehicleStateProvider::Update | ( | const std::string & | localization_file, |
const std::string & | chassis_file | ||
) |
Update VehicleStateProvider instance by protobuf files.
localization_file | the localization protobuf file. |
chassis_file | The chassis protobuf file |
const VehicleState & apollo::common::VehicleStateProvider::vehicle_state | ( | ) | const |
在文件 vehicle_state_provider.cc 第 211 行定义.
double apollo::common::VehicleStateProvider::x | ( | ) | const |
Get the x-coordinate of vehicle position.
在文件 vehicle_state_provider.cc 第 159 行定义.
double apollo::common::VehicleStateProvider::y | ( | ) | const |
Get the y-coordinate of vehicle position.
在文件 vehicle_state_provider.cc 第 161 行定义.
double apollo::common::VehicleStateProvider::yaw | ( | ) | const |
Get the vehicle yaw angle.
As of now, use the heading instead of yaw angle. Heading angle with East as zero, yaw angle has North as zero
在文件 vehicle_state_provider.cc 第 169 行定义.
double apollo::common::VehicleStateProvider::z | ( | ) | const |
Get the z coordinate of vehicle position.
在文件 vehicle_state_provider.cc 第 163 行定义.