Apollo  6.0
Open source self driving car software
vehicle_state_provider.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
21 #pragma once
22 
23 #include <memory>
24 #include <string>
25 
26 #include "modules/canbus/proto/chassis.pb.h"
30 #include "modules/common/vehicle_state/proto/vehicle_state.pb.h"
31 #include "modules/localization/proto/localization.pb.h"
32 
37 namespace apollo {
38 namespace common {
39 
47  public:
53  Status Update(const localization::LocalizationEstimate& localization,
54  const canbus::Chassis& chassis);
55 
61  void Update(const std::string& localization_file,
62  const std::string& chassis_file);
63 
64  double timestamp() const;
65 
66  const localization::Pose& pose() const;
67  const localization::Pose& original_pose() const;
68 
72  virtual ~VehicleStateProvider() = default;
73 
78  double x() const;
79 
84  double y() const;
85 
90  double z() const;
91 
98  double kappa() const;
99 
104  double roll() const;
105 
110  double pitch() const;
111 
118  double yaw() const;
119 
126  double heading() const;
127 
132  double linear_velocity() const;
133 
138  double angular_velocity() const;
139 
144  double linear_acceleration() const;
145 
150  double gear() const;
151 
156  double steering_percentage() const;
157 
162  void set_linear_velocity(const double linear_velocity);
163 
171  math::Vec2d EstimateFuturePosition(const double t) const;
172 
180  math::Vec2d ComputeCOMPosition(const double rear_to_com_distance) const;
181 
182  const VehicleState& vehicle_state() const;
183 
184  private:
185  bool ConstructExceptLinearVelocity(
186  const localization::LocalizationEstimate& localization);
187 
188  common::VehicleState vehicle_state_;
189  localization::LocalizationEstimate original_localization_;
190 };
191 
192 } // namespace common
193 } // namespace apollo
double heading() const
Get the heading of vehicle position, which is the angle between the vehicle&#39;s heading direction and t...
double roll() const
Get the vehicle roll angle.
double linear_acceleration() const
Get the vehicle&#39;s linear acceleration.
double angular_velocity() const
Get the vehicle&#39;s angular velocity.
Defines the Vec2d class.
The class of vehicle state. It includes basic information and computation about the state of the vehi...
Definition: vehicle_state_provider.h:46
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
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 th...
double y() const
Get the y-coordinate of vehicle position.
virtual ~VehicleStateProvider()=default
Default destructor.
Implements a class of 2-dimensional vectors.
Definition: vec2d.h:42
double x() const
Get the x-coordinate of vehicle position.
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.
void set_linear_velocity(const double linear_velocity)
Set the vehicle&#39;s linear velocity.
const localization::Pose & pose() const
double pitch() const
Get the vehicle pitch angle.
double z() const
Get the z coordinate of vehicle position.
double kappa() const
Get the kappa of vehicle position. the positive or negative sign is decided by the vehicle heading ve...
A general class to denote the return status of an API call. It can either be an OK status for success...
Definition: status.h:43
double gear() const
Get the vehicle&#39;s gear position.
The class of Box2d. Here, the x/y axes are respectively Forward/Left, as opposed to what happens in e...
const localization::Pose & original_pose() const
double steering_percentage() const
Get the vehicle&#39;s steering angle.
double yaw() const
Get the vehicle yaw angle. As of now, use the heading instead of yaw angle. Heading angle with East a...
const VehicleState & vehicle_state() const
Status Update(const localization::LocalizationEstimate &localization, const canbus::Chassis &chassis)
Constructor by information of localization and chassis.
double linear_velocity() const
Get the vehicle&#39;s linear velocity.