Autoware.Auto
autoware::motion::control::trajectory_follower::MPC Class Reference

calculate control command to follow reference waypoints More...

#include <mpc.hpp>

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

Public Member Functions

 MPC ()=default
 constructor More...
 
bool8_t calculateMPC (const autoware_auto_vehicle_msgs::msg::VehicleKinematicState &current_steer, const float64_t current_velocity, const geometry_msgs::msg::Pose &current_pose, autoware_auto_control_msgs::msg::AckermannLateralCommand &ctrl_cmd, autoware_auto_planning_msgs::msg::Trajectory &predicted_traj, autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic &diagnostic)
 calculate control command by MPC algorithm More...
 
void setReferenceTrajectory (const autoware_auto_planning_msgs::msg::Trajectory &trajectory_msg, const float64_t traj_resample_dist, const bool8_t enable_path_smoothing, const int64_t path_filter_moving_ave_num, const bool8_t enable_yaw_recalculation, const int64_t curvature_smoothing_num, const geometry_msgs::msg::PoseStamped::SharedPtr current_pose_ptr)
 set the reference trajectory to follow More...
 
void setVehicleModel (std::shared_ptr< trajectory_follower::VehicleModelInterface > vehicle_model_ptr, const std::string &vehicle_model_type)
 set the vehicle model of this MPC More...
 
void setQPSolver (std::shared_ptr< trajectory_follower::QPSolverInterface > qpsolver_ptr)
 set the QP solver of this MPC More...
 
void initializeLowPassFilters (const float64_t steering_lpf_cutoff_hz, const float64_t error_deriv_lpf_cutoff_hz)
 initialize low pass filters More...
 
bool8_t hasVehicleModel () const
 return true if the vehicle model of this MPC is set More...
 
bool8_t hasQPSolver () const
 return true if the QP solver of this MPC is set More...
 
void setLogger (rclcpp::Logger logger)
 set the RCLCPP logger to use for logging More...
 
void setClock (rclcpp::Clock::SharedPtr clock)
 set the RCLCPP clock to use for time keeping More...
 

Public Attributes

trajectory_follower::MPCTrajectory m_ref_traj
 < More...
 
MPCParam m_param
 mpc_output buffer for delay time compensation More...
 
std::deque< float64_t > m_input_buffer
 mpc raw output in previous period More...
 
float64_t m_raw_steer_cmd_prev = 0.0
 
float64_t m_admissible_position_error
 < More...
 
float64_t m_admissible_yaw_error_rad
 steering command limit [rad] More...
 
float64_t m_steer_lim
 steering rate limit [rad/s] More...
 
float64_t m_steer_rate_lim
 control frequency [s] More...
 
float64_t m_ctrl_period
 
bool8_t m_use_steer_prediction
 < More...
 

Detailed Description

calculate control command to follow reference waypoints

MPC-based waypoints follower class

Constructor & Destructor Documentation

◆ MPC()

autoware::motion::control::trajectory_follower::MPC::MPC ( )
default

constructor

Member Function Documentation

◆ calculateMPC()

bool8_t autoware::motion::control::trajectory_follower::MPC::calculateMPC ( const autoware_auto_vehicle_msgs::msg::VehicleKinematicState &  current_steer,
const float64_t  current_velocity,
const geometry_msgs::msg::Pose &  current_pose,
autoware_auto_control_msgs::msg::AckermannLateralCommand &  ctrl_cmd,
autoware_auto_planning_msgs::msg::Trajectory &  predicted_traj,
autoware_auto_system_msgs::msg::Float32MultiArrayDiagnostic &  diagnostic 
)

calculate control command by MPC algorithm

Parameters
[in]current_steercurrent steering of the vehicle
[in]current_velocitycurrent velocity of the vehicle [m/s]
[in]current_posecurrent pose of the vehicle
[out]ctrl_cmdcontrol command calculated with mpc algorithm
[out]predicted_trajpredicted MPC trajectory
[out]diagnosticdiagnostic msg to be filled-out

◆ hasQPSolver()

bool8_t autoware::motion::control::trajectory_follower::MPC::hasQPSolver ( ) const
inline

return true if the QP solver of this MPC is set

◆ hasVehicleModel()

bool8_t autoware::motion::control::trajectory_follower::MPC::hasVehicleModel ( ) const
inline

return true if the vehicle model of this MPC is set

◆ initializeLowPassFilters()

void autoware::motion::control::trajectory_follower::MPC::initializeLowPassFilters ( const float64_t  steering_lpf_cutoff_hz,
const float64_t  error_deriv_lpf_cutoff_hz 
)
inline

initialize low pass filters

◆ setClock()

void autoware::motion::control::trajectory_follower::MPC::setClock ( rclcpp::Clock::SharedPtr  clock)
inline

set the RCLCPP clock to use for time keeping

◆ setLogger()

void autoware::motion::control::trajectory_follower::MPC::setLogger ( rclcpp::Logger  logger)
inline

set the RCLCPP logger to use for logging

◆ setQPSolver()

void autoware::motion::control::trajectory_follower::MPC::setQPSolver ( std::shared_ptr< trajectory_follower::QPSolverInterface qpsolver_ptr)
inline

set the QP solver of this MPC

◆ setReferenceTrajectory()

void autoware::motion::control::trajectory_follower::MPC::setReferenceTrajectory ( const autoware_auto_planning_msgs::msg::Trajectory &  trajectory_msg,
const float64_t  traj_resample_dist,
const bool8_t  enable_path_smoothing,
const int64_t  path_filter_moving_ave_num,
const bool8_t  enable_yaw_recalculation,
const int64_t  curvature_smoothing_num,
const geometry_msgs::msg::PoseStamped::SharedPtr  current_pose_ptr 
)

set the reference trajectory to follow

◆ setVehicleModel()

void autoware::motion::control::trajectory_follower::MPC::setVehicleModel ( std::shared_ptr< trajectory_follower::VehicleModelInterface vehicle_model_ptr,
const std::string &  vehicle_model_type 
)
inline

set the vehicle model of this MPC

Member Data Documentation

◆ m_admissible_position_error

float64_t autoware::motion::control::trajectory_follower::MPC::m_admissible_position_error

<

use stop cmd when lateral error exceeds this [m]

use stop cmd when yaw error exceeds this [rad]

◆ m_admissible_yaw_error_rad

float64_t autoware::motion::control::trajectory_follower::MPC::m_admissible_yaw_error_rad

steering command limit [rad]

◆ m_ctrl_period

float64_t autoware::motion::control::trajectory_follower::MPC::m_ctrl_period

◆ m_input_buffer

std::deque<float64_t> autoware::motion::control::trajectory_follower::MPC::m_input_buffer

mpc raw output in previous period

◆ m_param

MPCParam autoware::motion::control::trajectory_follower::MPC::m_param

mpc_output buffer for delay time compensation

◆ m_raw_steer_cmd_prev

float64_t autoware::motion::control::trajectory_follower::MPC::m_raw_steer_cmd_prev = 0.0

◆ m_ref_traj

trajectory_follower::MPCTrajectory autoware::motion::control::trajectory_follower::MPC::m_ref_traj

<

reference trajectory to be followed

MPC design parameter

◆ m_steer_lim

float64_t autoware::motion::control::trajectory_follower::MPC::m_steer_lim

steering rate limit [rad/s]

◆ m_steer_rate_lim

float64_t autoware::motion::control::trajectory_follower::MPC::m_steer_rate_lim

control frequency [s]

◆ m_use_steer_prediction

bool8_t autoware::motion::control::trajectory_follower::MPC::m_use_steer_prediction

<

flag to use predicted steer, not measured steer.


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