27 #include "modules/common/configs/proto/vehicle_config.pb.h" 43 void Init(
const double max_acc,
const double max_dec,
const double max_v,
65 const double lower_v,
const double upper_s,
66 const double upper_v);
84 std::vector<std::tuple<double, double, double>> curvature_speed_limits_s_v_;
86 std::vector<std::tuple<double, double, double>> traffic_speed_limits_s_v_;
88 std::vector<std::tuple<double, double, double>> obstacles_speed_limits_s_v_;
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
STDrivingLimits()
Definition: st_driving_limits.h:41
Planning module main class. It processes GPS and IMU as input, to generate planning info...
Definition: st_driving_limits.h:39
void Init(const double max_acc, const double max_dec, const double max_v, double curr_v)
std::pair< double, double > GetVehicleDynamicsLimits(const double t) const
Given time t, calculate the driving limits in s due to vehicle's dynamics.
void UpdateBlockingInfo(const double t, const double lower_s, const double lower_v, const double upper_s, const double upper_v)
Update the anchoring of the vehicle dynamics limits. For example, when ADC is blocked by some obstacl...
virtual ~STDrivingLimits()=default