Autoware.Auto
vehicle_constants_manager.hpp
Go to the documentation of this file.
1 // Copyright 2021 The Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
18 
19 #ifndef VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
20 #define VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
21 
22 #include <common/types.hpp>
23 #include <rclcpp/rclcpp.hpp>
25 
26 #include <chrono>
27 #include <memory>
28 #include <string>
29 
30 namespace autoware
31 {
32 namespace common
33 {
34 namespace vehicle_constants_manager
35 {
39 struct VEHICLE_CONSTANTS_MANAGER_PUBLIC VehicleConstants
40 {
41  using SharedPtr = std::shared_ptr<VehicleConstants>;
42  using ConstSharedPtr = const SharedPtr;
43 
45 
65  explicit VehicleConstants(
66  float64_t wheel_radius, float64_t wheel_width, float64_t wheel_base,
67  float64_t wheel_tread, float64_t overhang_front,
68  float64_t overhang_rear, float64_t overhang_left,
69  float64_t overhang_right, float64_t vehicle_height,
70  float64_t cg_to_rear, float64_t tire_cornering_stiffness_front,
71  float64_t tire_cornering_stiffness_rear, float64_t mass_vehicle,
72  float64_t inertia_yaw_kg_m_2, float64_t maximum_turning_angle_rad);
73 
74  // Primary Constants
75 
78 
81 
84 
87 
91 
95 
99 
103 
107 
111 
117 
120 
123 
126 
129 
130 
131  // Derived Constants
132 
136 
139 
142 
146 
149 
152 
155 
158 
161 
164 
167 
169  std::string str_pretty() const;
170 };
171 
180 VEHICLE_CONSTANTS_MANAGER_PUBLIC VehicleConstants
182 } // namespace vehicle_constants_manager
183 } // namespace common
184 } // namespace autoware
185 
186 #endif // VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
autoware::common::vehicle_constants_manager::VehicleConstants::offset_height_min
const float64_t offset_height_min
[m] Signed distance from base_link to the bottom-most point of the vehicle. (Negative)
Definition: vehicle_constants_manager.hpp:160
autoware::common::vehicle_constants_manager::VehicleConstants::maximum_turning_angle_rad
const float64_t maximum_turning_angle_rad
[rad] Maximum turning angle for cars front axis
Definition: vehicle_constants_manager.hpp:128
autoware::common::vehicle_constants_manager::VehicleConstants::inertia_yaw_kg_m2
const float64_t inertia_yaw_kg_m2
[kg * m^2] Moment of inertia around vertical axis of the vehicle
Definition: vehicle_constants_manager.hpp:125
autoware::common::vehicle_constants_manager::declare_and_get_vehicle_constants
VEHICLE_CONSTANTS_MANAGER_PUBLIC VehicleConstants declare_and_get_vehicle_constants(rclcpp::Node &node)
Declares the vehicle parameters for the node and creates a VehicleConstants object.
Definition: vehicle_constants_manager.cpp:142
types.hpp
This file includes common type definition.
autoware::common::vehicle_constants_manager::VehicleConstants::offset_height_max
const float64_t offset_height_max
[m] Signed distance from base_link to the top-most point of the vehicle.
Definition: vehicle_constants_manager.hpp:163
autoware::common::vehicle_constants_manager::VehicleConstants::overhang_front
const float64_t overhang_front
[m] Absolute distance between the vertical plane passing through the centres of the front wheels and ...
Definition: vehicle_constants_manager.hpp:90
autoware::common::vehicle_constants_manager::VehicleConstants::tire_cornering_stiffness_rear
const float64_t tire_cornering_stiffness_rear
[kg/deg] The nominal cornering stiffness for rear wheels
Definition: vehicle_constants_manager.hpp:119
autoware::common::vehicle_constants_manager::VehicleConstants::vehicle_length
const float64_t vehicle_length
[m] Horizontal distance between foremost and rearmost points of the vehicle
Definition: vehicle_constants_manager.hpp:138
visibility_control.hpp
autoware::common::vehicle_constants_manager::VehicleConstants::cg_to_front
const float64_t cg_to_front
[m] Absolute value of longitudinal distance between Center of Gravity and center of front axle
Definition: vehicle_constants_manager.hpp:135
autoware::common::vehicle_constants_manager::VehicleConstants::vehicle_width
const float64_t vehicle_width
[m] Horizontal distance between leftmost and rightmost points of the vehicle
Definition: vehicle_constants_manager.hpp:141
autoware::common::vehicle_constants_manager::VehicleConstants
A struct that holds vehicle specific parameters that don't change over time.
Definition: vehicle_constants_manager.hpp:39
autoware::common::vehicle_constants_manager::VehicleConstants::vehicle_height
const float64_t vehicle_height
[m] Absolute vertical distance between ground and topmost point of the vehicle including mounted sens...
Definition: vehicle_constants_manager.hpp:106
autoware::common::vehicle_constants_manager::VehicleConstants::minimum_turning_radius
float64_t minimum_turning_radius
[rad] Minimum turning radius
Definition: vehicle_constants_manager.hpp:166
autoware::common::vehicle_constants_manager::VehicleConstants::tire_cornering_stiffness_front
const float64_t tire_cornering_stiffness_front
[kg/deg] The nominal cornering stiffness is equal to the side force in Newtons divided by the slip an...
Definition: vehicle_constants_manager.hpp:116
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
sys_info_node.node
node
Definition: sys_info_node.py:23
autoware::common::vehicle_constants_manager::VehicleConstants::overhang_rear
const float64_t overhang_rear
[m] Absolute distance between the vertical plane passing through the centres of the rear wheels and t...
Definition: vehicle_constants_manager.hpp:94
autoware::common::vehicle_constants_manager::VehicleConstants::mass_vehicle
const float64_t mass_vehicle
[kg] Total mass of the vehicle including sensors in kilograms
Definition: vehicle_constants_manager.hpp:122
autoware::common::vehicle_constants_manager::VehicleConstants::ConstSharedPtr
const SharedPtr ConstSharedPtr
Definition: vehicle_constants_manager.hpp:42
autoware::common::vehicle_constants_manager::VehicleConstants::wheel_base
const float64_t wheel_base
[m] Absolute distance between axis centers of front and rear wheels.
Definition: vehicle_constants_manager.hpp:83
autoware::common::vehicle_constants_manager::VehicleConstants::wheel_radius
const float64_t wheel_radius
[m] Radius of the wheel including the tires
Definition: vehicle_constants_manager.hpp:77
autoware::common::vehicle_constants_manager::VehicleConstants::float64_t
autoware::common::types::float64_t float64_t
Definition: vehicle_constants_manager.hpp:44
autoware::common::vehicle_constants_manager::VehicleConstants::offset_lateral_max
const float64_t offset_lateral_max
[m] Signed distance from base_link to the left-most point of the vehicle.
Definition: vehicle_constants_manager.hpp:157
autoware::common::vehicle_constants_manager::VehicleConstants::wheel_width
const float64_t wheel_width
[m] Horizontal distance between 2 circular sides of the wheel
Definition: vehicle_constants_manager.hpp:80
autoware::common::vehicle_constants_manager::VehicleConstants::offset_lateral_min
const float64_t offset_lateral_min
[m] Signed distance from base_link to the right-most point of the vehicle. (Negative)
Definition: vehicle_constants_manager.hpp:154
autoware::common::vehicle_constants_manager::VehicleConstants::cg_to_rear
const float64_t cg_to_rear
[m] Absolute value of longitudinal distance between Center of Gravity and center of rear axle
Definition: vehicle_constants_manager.hpp:110
autoware::common::vehicle_constants_manager::VehicleConstants::overhang_left
const float64_t overhang_left
[m] Absolute distance between axis centers of left wheels and the leftmost point of the vehicle
Definition: vehicle_constants_manager.hpp:98
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::common::vehicle_constants_manager::VehicleConstants::offset_longitudinal_min
const float64_t offset_longitudinal_min
Offsets from base_link.
Definition: vehicle_constants_manager.hpp:148
autoware::common::vehicle_constants_manager::VehicleConstants::overhang_right
const float64_t overhang_right
[m] Absolute distance between axis centers of right wheels and the rightmost point of the vehicle
Definition: vehicle_constants_manager.hpp:102
autoware::common::vehicle_constants_manager::VehicleConstants::SharedPtr
std::shared_ptr< VehicleConstants > SharedPtr
Definition: vehicle_constants_manager.hpp:41
autoware::common::vehicle_constants_manager::VehicleConstants::wheel_tread
const float64_t wheel_tread
[m] Absolute distance between axis centers of left and right wheels.
Definition: vehicle_constants_manager.hpp:86
autoware::common::vehicle_constants_manager::VehicleConstants::offset_longitudinal_max
const float64_t offset_longitudinal_max
[m] Signed distance from base_link to the fore-most point of the vehicle.
Definition: vehicle_constants_manager.hpp:151