Apollo  6.0
Open source self driving car software
Public Member Functions | List of all members
apollo::common::VehicleStateProvider Class Reference

The class of vehicle state. It includes basic information and computation about the state of the vehicle. More...

#include <vehicle_state_provider.h>

Collaboration diagram for apollo::common::VehicleStateProvider:
Collaboration graph

Public Member Functions

Status Update (const localization::LocalizationEstimate &localization, const canbus::Chassis &chassis)
 Constructor by information of localization and chassis. More...
 
void Update (const std::string &localization_file, const std::string &chassis_file)
 Update VehicleStateProvider instance by protobuf files. More...
 
double timestamp () const
 
const localization::Pose & pose () const
 
const localization::Pose & original_pose () const
 
virtual ~VehicleStateProvider ()=default
 Default destructor. More...
 
double x () const
 Get the x-coordinate of vehicle position. More...
 
double y () const
 Get the y-coordinate of vehicle position. More...
 
double z () const
 Get the z coordinate of vehicle position. More...
 
double kappa () const
 Get the kappa of vehicle position. the positive or negative sign is decided by the vehicle heading vector along the path. More...
 
double roll () const
 Get the vehicle roll angle. More...
 
double pitch () const
 Get the vehicle pitch angle. More...
 
double 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. More...
 
double heading () const
 Get the heading of vehicle position, which is the angle between the vehicle's heading direction and the x-axis. More...
 
double linear_velocity () const
 Get the vehicle's linear velocity. More...
 
double angular_velocity () const
 Get the vehicle's angular velocity. More...
 
double linear_acceleration () const
 Get the vehicle's linear acceleration. More...
 
double gear () const
 Get the vehicle's gear position. More...
 
double steering_percentage () const
 Get the vehicle's steering angle. More...
 
void set_linear_velocity (const double linear_velocity)
 Set the vehicle's linear velocity. More...
 
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. More...
 
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. More...
 
const VehicleState & vehicle_state () const
 

Detailed Description

The class of vehicle state. It includes basic information and computation about the state of the vehicle.

Constructor & Destructor Documentation

◆ ~VehicleStateProvider()

virtual apollo::common::VehicleStateProvider::~VehicleStateProvider ( )
virtualdefault

Default destructor.

Member Function Documentation

◆ angular_velocity()

double apollo::common::VehicleStateProvider::angular_velocity ( ) const

Get the vehicle's angular velocity.

Returns
The vehicle's angular velocity.

◆ ComputeCOMPosition()

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.

Parameters
rear_to_com_distanceDistance from rear wheels to the vehicle's center of mass.
Returns
The position of the vehicle's center of mass.

◆ EstimateFuturePosition()

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.

Parameters
tThe length of time period.
Returns
The estimated future position in time t.

◆ gear()

double apollo::common::VehicleStateProvider::gear ( ) const

Get the vehicle's gear position.

Returns
The vehicle's gear position.

◆ heading()

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.

Returns
The angle between the vehicle's heading direction and the x-axis.

◆ kappa()

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.

Returns
The kappa of vehicle position.

◆ linear_acceleration()

double apollo::common::VehicleStateProvider::linear_acceleration ( ) const

Get the vehicle's linear acceleration.

Returns
The vehicle's linear acceleration.

◆ linear_velocity()

double apollo::common::VehicleStateProvider::linear_velocity ( ) const

Get the vehicle's linear velocity.

Returns
The vehicle's linear velocity.

◆ original_pose()

const localization::Pose& apollo::common::VehicleStateProvider::original_pose ( ) const

◆ pitch()

double apollo::common::VehicleStateProvider::pitch ( ) const

Get the vehicle pitch angle.

Returns
The euler pitch angle.

◆ pose()

const localization::Pose& apollo::common::VehicleStateProvider::pose ( ) const

◆ roll()

double apollo::common::VehicleStateProvider::roll ( ) const

Get the vehicle roll angle.

Returns
The euler roll angle.

◆ set_linear_velocity()

void apollo::common::VehicleStateProvider::set_linear_velocity ( const double  linear_velocity)

Set the vehicle's linear velocity.

Parameters
linear_velocityThe value to set the vehicle's linear velocity.

◆ steering_percentage()

double apollo::common::VehicleStateProvider::steering_percentage ( ) const

Get the vehicle's steering angle.

Returns
double

◆ timestamp()

double apollo::common::VehicleStateProvider::timestamp ( ) const

◆ Update() [1/2]

Status apollo::common::VehicleStateProvider::Update ( const localization::LocalizationEstimate &  localization,
const canbus::Chassis &  chassis 
)

Constructor by information of localization and chassis.

Parameters
localizationLocalization information of the vehicle.
chassisChassis information of the vehicle.

◆ Update() [2/2]

void apollo::common::VehicleStateProvider::Update ( const std::string &  localization_file,
const std::string &  chassis_file 
)

Update VehicleStateProvider instance by protobuf files.

Parameters
localization_filethe localization protobuf file.
chassis_fileThe chassis protobuf file

◆ vehicle_state()

const VehicleState& apollo::common::VehicleStateProvider::vehicle_state ( ) const

◆ x()

double apollo::common::VehicleStateProvider::x ( ) const

Get the x-coordinate of vehicle position.

Returns
The x-coordinate of vehicle position.

◆ y()

double apollo::common::VehicleStateProvider::y ( ) const

Get the y-coordinate of vehicle position.

Returns
The y-coordinate of vehicle position.

◆ yaw()

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.

Returns
The euler yaw angle.

◆ z()

double apollo::common::VehicleStateProvider::z ( ) const

Get the z coordinate of vehicle position.

Returns
The z coordinate of vehicle position.

The documentation for this class was generated from the following file: