Autoware.Auto
autoware::motion::control::trajectory_follower::MPCParam Struct Reference

#include <mpc.hpp>

Collaboration diagram for autoware::motion::control::trajectory_follower::MPCParam:

Public Attributes

int64_t prediction_horizon
 < More...
 
float64_t prediction_dt
 threshold that feed-forward angle becomes zero More...
 
float64_t zero_ff_steer_deg
 delay time for steering input to be compensated More...
 
float64_t input_delay
 for trajectory velocity calculation More...
 
float64_t acceleration_limit
 for trajectory velocity calculation More...
 
float64_t velocity_time_constant
 time constant for steer model More...
 
float64_t steer_tau
 
float64_t weight_lat_error
 < More...
 
float64_t weight_heading_error
 heading error * velocity weight More...
 
float64_t weight_heading_error_squared_vel
 terminal lateral error weight More...
 
float64_t weight_terminal_lat_error
 terminal heading error weight More...
 
float64_t weight_terminal_heading_error
 lateral error weight in matrix Q in low curvature point More...
 
float64_t low_curvature_weight_lat_error
 heading error weight in matrix Q in low curvature point More...
 
float64_t low_curvature_weight_heading_error
 heading error * velocity weight in matrix Q in low curvature point More...
 
float64_t low_curvature_weight_heading_error_squared_vel
 
float64_t weight_steering_input
 < More...
 
float64_t weight_steering_input_squared_vel
 lateral jerk weight More...
 
float64_t weight_lat_jerk
 steering rate weight More...
 
float64_t weight_steer_rate
 steering angle acceleration weight More...
 
float64_t weight_steer_acc
 steering error weight in matrix R in low curvature point More...
 
float64_t low_curvature_weight_steering_input
 steering error * velocity weight in matrix R in low curvature point More...
 
float64_t low_curvature_weight_steering_input_squared_vel
 lateral jerk weight in matrix R in low curvature point More...
 
float64_t low_curvature_weight_lat_jerk
 steering rate weight in matrix R in low curvature point More...
 
float64_t low_curvature_weight_steer_rate
 steering angle acceleration weight in matrix R in low curvature More...
 
float64_t low_curvature_weight_steer_acc
 threshold of curvature to use "low curvature" parameter More...
 
float64_t low_curvature_thresh_curvature
 

Member Data Documentation

◆ acceleration_limit

float64_t autoware::motion::control::trajectory_follower::MPCParam::acceleration_limit

for trajectory velocity calculation

◆ input_delay

float64_t autoware::motion::control::trajectory_follower::MPCParam::input_delay

for trajectory velocity calculation

◆ low_curvature_thresh_curvature

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_thresh_curvature

◆ low_curvature_weight_heading_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_heading_error

heading error * velocity weight in matrix Q in low curvature point

◆ low_curvature_weight_heading_error_squared_vel

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_heading_error_squared_vel

◆ low_curvature_weight_lat_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_lat_error

heading error weight in matrix Q in low curvature point

◆ low_curvature_weight_lat_jerk

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_lat_jerk

steering rate weight in matrix R in low curvature point

◆ low_curvature_weight_steer_acc

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_steer_acc

threshold of curvature to use "low curvature" parameter

◆ low_curvature_weight_steer_rate

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_steer_rate

steering angle acceleration weight in matrix R in low curvature

◆ low_curvature_weight_steering_input

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_steering_input

steering error * velocity weight in matrix R in low curvature point

◆ low_curvature_weight_steering_input_squared_vel

float64_t autoware::motion::control::trajectory_follower::MPCParam::low_curvature_weight_steering_input_squared_vel

lateral jerk weight in matrix R in low curvature point

◆ prediction_dt

float64_t autoware::motion::control::trajectory_follower::MPCParam::prediction_dt

threshold that feed-forward angle becomes zero

◆ prediction_horizon

int64_t autoware::motion::control::trajectory_follower::MPCParam::prediction_horizon

<

prediction horizon step

prediction horizon sampling time

◆ steer_tau

float64_t autoware::motion::control::trajectory_follower::MPCParam::steer_tau

◆ velocity_time_constant

float64_t autoware::motion::control::trajectory_follower::MPCParam::velocity_time_constant

time constant for steer model

◆ weight_heading_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_heading_error

heading error * velocity weight

◆ weight_heading_error_squared_vel

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_heading_error_squared_vel

terminal lateral error weight

◆ weight_lat_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_lat_error

<

lateral error weight

heading error weight

◆ weight_lat_jerk

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_lat_jerk

steering rate weight

◆ weight_steer_acc

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_steer_acc

steering error weight in matrix R in low curvature point

◆ weight_steer_rate

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_steer_rate

steering angle acceleration weight

◆ weight_steering_input

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_steering_input

<

steering error weight

steering error * velocity weight

◆ weight_steering_input_squared_vel

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_steering_input_squared_vel

lateral jerk weight

◆ weight_terminal_heading_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_terminal_heading_error

lateral error weight in matrix Q in low curvature point

◆ weight_terminal_lat_error

float64_t autoware::motion::control::trajectory_follower::MPCParam::weight_terminal_lat_error

terminal heading error weight

◆ zero_ff_steer_deg

float64_t autoware::motion::control::trajectory_follower::MPCParam::zero_ff_steer_deg

delay time for steering input to be compensated


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