Go to the documentation of this file.
19 #ifndef VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
20 #define VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
23 #include <rclcpp/rclcpp.hpp>
34 namespace vehicle_constants_manager
41 using SharedPtr = std::shared_ptr<VehicleConstants>;
169 std::string str_pretty()
const;
186 #endif // VEHICLE_CONSTANTS_MANAGER__VEHICLE_CONSTANTS_MANAGER_HPP_
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
const float64_t maximum_turning_angle_rad
[rad] Maximum turning angle for cars front axis
Definition: vehicle_constants_manager.hpp:128
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
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
This file includes common type definition.
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
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
const float64_t tire_cornering_stiffness_rear
[kg/deg] The nominal cornering stiffness for rear wheels
Definition: vehicle_constants_manager.hpp:119
const float64_t vehicle_length
[m] Horizontal distance between foremost and rearmost points of the vehicle
Definition: vehicle_constants_manager.hpp:138
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
const float64_t vehicle_width
[m] Horizontal distance between leftmost and rightmost points of the vehicle
Definition: vehicle_constants_manager.hpp:141
A struct that holds vehicle specific parameters that don't change over time.
Definition: vehicle_constants_manager.hpp:39
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
float64_t minimum_turning_radius
[rad] Minimum turning radius
Definition: vehicle_constants_manager.hpp:166
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
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
node
Definition: sys_info_node.py:23
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
const float64_t mass_vehicle
[kg] Total mass of the vehicle including sensors in kilograms
Definition: vehicle_constants_manager.hpp:122
const SharedPtr ConstSharedPtr
Definition: vehicle_constants_manager.hpp:42
const float64_t wheel_base
[m] Absolute distance between axis centers of front and rear wheels.
Definition: vehicle_constants_manager.hpp:83
const float64_t wheel_radius
[m] Radius of the wheel including the tires
Definition: vehicle_constants_manager.hpp:77
autoware::common::types::float64_t float64_t
Definition: vehicle_constants_manager.hpp:44
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
const float64_t wheel_width
[m] Horizontal distance between 2 circular sides of the wheel
Definition: vehicle_constants_manager.hpp:80
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
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
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
double float64_t
Definition: types.hpp:47
const float64_t offset_longitudinal_min
Offsets from base_link.
Definition: vehicle_constants_manager.hpp:148
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
std::shared_ptr< VehicleConstants > SharedPtr
Definition: vehicle_constants_manager.hpp:41
const float64_t wheel_tread
[m] Absolute distance between axis centers of left and right wheels.
Definition: vehicle_constants_manager.hpp:86
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