提交 e3f099ce 编写于 作者: Z Zhang Liangliang 提交者: Kecheng Xu

uniform the naming of 'QP'

上级 afa43c7b
...@@ -24,8 +24,8 @@ namespace common { ...@@ -24,8 +24,8 @@ namespace common {
namespace math { namespace math {
using Matrix = Eigen::MatrixXd; using Matrix = Eigen::MatrixXd;
using ::apollo::common::math::QPSolver; using ::apollo::common::math::QpSolver;
using ::apollo::common::math::ActiveSetQPSolver; using ::apollo::common::math::ActiveSetQpSolver;
// discrete linear predictive control solver, with control format // discrete linear predictive control solver, with control format
// x(i + 1) = A * x(i) + B * u (i) + C // x(i + 1) = A * x(i) + B * u (i) + C
...@@ -130,7 +130,7 @@ void SolveLinearMPC(const Matrix &matrix_a, ...@@ -130,7 +130,7 @@ void SolveLinearMPC(const Matrix &matrix_a,
Eigen::MatrixXd matrix_equality_boundary = Eigen::MatrixXd::Zero( Eigen::MatrixXd matrix_equality_boundary = Eigen::MatrixXd::Zero(
matrix_ll.rows() + matrix_uu.rows(), matrix_ll.cols()); matrix_ll.rows() + matrix_uu.rows(), matrix_ll.cols());
std::unique_ptr<QPSolver> qp_solver(new ActiveSetQPSolver(matrix_m1, std::unique_ptr<QpSolver> qp_solver(new ActiveSetQpSolver(matrix_m1,
matrix_m2, matrix_m2,
matrix_inequality_constrain, matrix_inequality_constrain,
matrix_inequality_boundary, matrix_inequality_boundary,
......
...@@ -29,13 +29,13 @@ namespace apollo { ...@@ -29,13 +29,13 @@ namespace apollo {
namespace common { namespace common {
namespace math { namespace math {
ActiveSetQPSolver::ActiveSetQPSolver( ActiveSetQpSolver::ActiveSetQpSolver(
const Eigen::MatrixXd& kernel_matrix, const Eigen::MatrixXd& offset, const Eigen::MatrixXd& kernel_matrix, const Eigen::MatrixXd& offset,
const Eigen::MatrixXd& affine_inequality_matrix, const Eigen::MatrixXd& affine_inequality_matrix,
const Eigen::MatrixXd& affine_inequality_boundary, const Eigen::MatrixXd& affine_inequality_boundary,
const Eigen::MatrixXd& affine_equality_matrix, const Eigen::MatrixXd& affine_equality_matrix,
const Eigen::MatrixXd& affine_equality_boundary) const Eigen::MatrixXd& affine_equality_boundary)
: QPSolver(kernel_matrix, offset, affine_inequality_matrix, : QpSolver(kernel_matrix, offset, affine_inequality_matrix,
affine_inequality_boundary, affine_equality_matrix, affine_inequality_boundary, affine_equality_matrix,
affine_equality_boundary) { affine_equality_boundary) {
num_param_ = kernel_matrix.rows(); num_param_ = kernel_matrix.rows();
...@@ -48,7 +48,7 @@ ActiveSetQPSolver::ActiveSetQPSolver( ...@@ -48,7 +48,7 @@ ActiveSetQPSolver::ActiveSetQPSolver(
debug_info_ = FLAGS_default_enable_active_set_debug_info; debug_info_ = FLAGS_default_enable_active_set_debug_info;
} }
bool ActiveSetQPSolver::solve() { bool ActiveSetQpSolver::solve() {
::qpOASES::QProblem qp_problem(num_param_, num_constraint_); ::qpOASES::QProblem qp_problem(num_param_, num_constraint_);
::qpOASES::Options my_options; ::qpOASES::Options my_options;
my_options.epsNum = qp_eps_num_; my_options.epsNum = qp_eps_num_;
...@@ -138,54 +138,54 @@ bool ActiveSetQPSolver::solve() { ...@@ -138,54 +138,54 @@ bool ActiveSetQPSolver::solve() {
return false; return false;
} }
void ActiveSetQPSolver::set_qp_eps_num(const double eps) { qp_eps_num_ = eps; } void ActiveSetQpSolver::set_qp_eps_num(const double eps) { qp_eps_num_ = eps; }
void ActiveSetQPSolver::set_qp_eps_den(const double eps) { qp_eps_den_ = eps; } void ActiveSetQpSolver::set_qp_eps_den(const double eps) { qp_eps_den_ = eps; }
void ActiveSetQPSolver::set_qp_eps_iter_ref(const double eps) { void ActiveSetQpSolver::set_qp_eps_iter_ref(const double eps) {
qp_eps_iter_ref_ = eps; qp_eps_iter_ref_ = eps;
} }
void ActiveSetQPSolver::set_debug_info(const bool enable) { void ActiveSetQpSolver::set_debug_info(const bool enable) {
debug_info_ = enable; debug_info_ = enable;
} }
void ActiveSetQPSolver::set_l_lower_bound(const double l_lower_bound) { void ActiveSetQpSolver::set_l_lower_bound(const double l_lower_bound) {
l_lower_bound_ = l_lower_bound; l_lower_bound_ = l_lower_bound;
} }
void ActiveSetQPSolver::set_l_upper_bound(const double l_upper_bound) { void ActiveSetQpSolver::set_l_upper_bound(const double l_upper_bound) {
l_upper_bound_ = l_upper_bound; l_upper_bound_ = l_upper_bound;
} }
void ActiveSetQPSolver::set_constraint_upper_bound( void ActiveSetQpSolver::set_constraint_upper_bound(
const double la_upper_bound) { const double la_upper_bound) {
constraint_upper_bound_ = la_upper_bound; constraint_upper_bound_ = la_upper_bound;
} }
void ActiveSetQPSolver::set_max_iteration(const int max_iter) { void ActiveSetQpSolver::set_max_iteration(const int max_iter) {
max_iteration_ = max_iter; max_iteration_ = max_iter;
} }
double ActiveSetQPSolver::qp_eps_num() const { return qp_eps_num_; } double ActiveSetQpSolver::qp_eps_num() const { return qp_eps_num_; }
double ActiveSetQPSolver::qp_eps_den() const { return qp_eps_den_; } double ActiveSetQpSolver::qp_eps_den() const { return qp_eps_den_; }
double ActiveSetQPSolver::qp_eps_iter_ref() const { return qp_eps_iter_ref_; } double ActiveSetQpSolver::qp_eps_iter_ref() const { return qp_eps_iter_ref_; }
bool ActiveSetQPSolver::debug_info() const { return debug_info_; } bool ActiveSetQpSolver::debug_info() const { return debug_info_; }
double ActiveSetQPSolver::l_lower_bound() const { return l_lower_bound_; } double ActiveSetQpSolver::l_lower_bound() const { return l_lower_bound_; }
double ActiveSetQPSolver::l_upper_bound() const { return l_upper_bound_; } double ActiveSetQpSolver::l_upper_bound() const { return l_upper_bound_; }
double ActiveSetQPSolver::constraint_upper_bound() const { double ActiveSetQpSolver::constraint_upper_bound() const {
return constraint_upper_bound_; return constraint_upper_bound_;
} }
int ActiveSetQPSolver::max_iteration() const { return max_iteration_; } int ActiveSetQpSolver::max_iteration() const { return max_iteration_; }
// pure virtual // pure virtual
bool ActiveSetQPSolver::sanity_check() { bool ActiveSetQpSolver::sanity_check() {
return kernel_matrix_.rows() == kernel_matrix_.cols() && return kernel_matrix_.rows() == kernel_matrix_.cols() &&
kernel_matrix_.rows() == affine_inequality_matrix_.cols() && kernel_matrix_.rows() == affine_inequality_matrix_.cols() &&
kernel_matrix_.rows() == affine_equality_matrix_.cols() && kernel_matrix_.rows() == affine_equality_matrix_.cols() &&
......
...@@ -29,9 +29,9 @@ namespace apollo { ...@@ -29,9 +29,9 @@ namespace apollo {
namespace common { namespace common {
namespace math { namespace math {
class ActiveSetQPSolver : public QPSolver { class ActiveSetQpSolver : public QpSolver {
public: public:
ActiveSetQPSolver(const Eigen::MatrixXd& kernel_matrix, ActiveSetQpSolver(const Eigen::MatrixXd& kernel_matrix,
const Eigen::MatrixXd& offset, const Eigen::MatrixXd& offset,
const Eigen::MatrixXd& affine_inequality_matrix, const Eigen::MatrixXd& affine_inequality_matrix,
const Eigen::MatrixXd& affine_inequality_boundary, const Eigen::MatrixXd& affine_inequality_boundary,
......
...@@ -23,7 +23,7 @@ namespace apollo { ...@@ -23,7 +23,7 @@ namespace apollo {
namespace common { namespace common {
namespace math { namespace math {
QPSolver::QPSolver(const Eigen::MatrixXd& kernel_matrix, QpSolver::QpSolver(const Eigen::MatrixXd& kernel_matrix,
const Eigen::MatrixXd& offset, const Eigen::MatrixXd& offset,
const Eigen::MatrixXd& affine_inequality_matrix, const Eigen::MatrixXd& affine_inequality_matrix,
const Eigen::MatrixXd& affine_inequality_boundary, const Eigen::MatrixXd& affine_inequality_boundary,
...@@ -36,27 +36,27 @@ QPSolver::QPSolver(const Eigen::MatrixXd& kernel_matrix, ...@@ -36,27 +36,27 @@ QPSolver::QPSolver(const Eigen::MatrixXd& kernel_matrix,
affine_equality_matrix_(affine_equality_matrix), affine_equality_matrix_(affine_equality_matrix),
affine_equality_boundary_(affine_equality_boundary) {} affine_equality_boundary_(affine_equality_boundary) {}
const Eigen::MatrixXd& QPSolver::params() const { return params_; } const Eigen::MatrixXd& QpSolver::params() const { return params_; }
const Eigen::MatrixXd& QPSolver::kernel_matrix() const { const Eigen::MatrixXd& QpSolver::kernel_matrix() const {
return kernel_matrix_; return kernel_matrix_;
} }
const Eigen::MatrixXd& QPSolver::offset() const { return offset_; } const Eigen::MatrixXd& QpSolver::offset() const { return offset_; }
const Eigen::MatrixXd& QPSolver::affine_equality_matrix() const { const Eigen::MatrixXd& QpSolver::affine_equality_matrix() const {
return affine_equality_matrix_; return affine_equality_matrix_;
} }
const Eigen::MatrixXd& QPSolver::affine_equality_boundary() const { const Eigen::MatrixXd& QpSolver::affine_equality_boundary() const {
return affine_equality_boundary_; return affine_equality_boundary_;
} }
const Eigen::MatrixXd& QPSolver::affine_inequality_matrix() const { const Eigen::MatrixXd& QpSolver::affine_inequality_matrix() const {
return affine_inequality_matrix_; return affine_inequality_matrix_;
} }
const Eigen::MatrixXd& QPSolver::affine_inequality_boundary() const { const Eigen::MatrixXd& QpSolver::affine_inequality_boundary() const {
return affine_inequality_boundary_; return affine_inequality_boundary_;
} }
......
...@@ -33,9 +33,9 @@ namespace apollo { ...@@ -33,9 +33,9 @@ namespace apollo {
namespace common { namespace common {
namespace math { namespace math {
class QPSolver { class QpSolver {
public: public:
QPSolver(const Eigen::MatrixXd& kernel_matrix, const Eigen::MatrixXd& offset, QpSolver(const Eigen::MatrixXd& kernel_matrix, const Eigen::MatrixXd& offset,
const Eigen::MatrixXd& affine_inequality_matrix, const Eigen::MatrixXd& affine_inequality_matrix,
const Eigen::MatrixXd& affine_inequality_boundary, const Eigen::MatrixXd& affine_inequality_boundary,
const Eigen::MatrixXd& affine_equality_matrix, const Eigen::MatrixXd& affine_equality_matrix,
......
...@@ -64,7 +64,7 @@ bool Spline1dGenerator::solve() { ...@@ -64,7 +64,7 @@ bool Spline1dGenerator::solve() {
const Eigen::MatrixXd& equality_constraint_boundary = const Eigen::MatrixXd& equality_constraint_boundary =
spline_constraint_.equality_constraint().constraint_boundary(); spline_constraint_.equality_constraint().constraint_boundary();
qp_solver_.reset(new apollo::common::math::ActiveSetQPSolver( qp_solver_.reset(new apollo::common::math::ActiveSetQpSolver(
kernel_matrix, offset, inequality_constraint_matrix, kernel_matrix, offset, inequality_constraint_matrix,
inequality_constraint_boundary, equality_constraint_matrix, inequality_constraint_boundary, equality_constraint_matrix,
equality_constraint_boundary)); equality_constraint_boundary));
......
...@@ -88,7 +88,7 @@ class Spline1dGenerator { ...@@ -88,7 +88,7 @@ class Spline1dGenerator {
Spline1dConstraint spline_constraint_; Spline1dConstraint spline_constraint_;
Spline1dKernel spline_kernel_; Spline1dKernel spline_kernel_;
std::unique_ptr<apollo::common::math::QPSolver> qp_solver_ = nullptr; std::unique_ptr<apollo::common::math::QpSolver> qp_solver_ = nullptr;
Eigen::MatrixXd init_x_; Eigen::MatrixXd init_x_;
Eigen::MatrixXd init_y_; Eigen::MatrixXd init_y_;
Eigen::MatrixXd init_z_; Eigen::MatrixXd init_z_;
......
...@@ -52,7 +52,7 @@ bool Spline2dSolver::solve() { ...@@ -52,7 +52,7 @@ bool Spline2dSolver::solve() {
const Eigen::MatrixXd& equality_constraint_boundary = const Eigen::MatrixXd& equality_constraint_boundary =
constraint_.equality_constraint().constraint_boundary(); constraint_.equality_constraint().constraint_boundary();
qp_solver_.reset(new apollo::common::math::ActiveSetQPSolver( qp_solver_.reset(new apollo::common::math::ActiveSetQpSolver(
kernel_matrix, offset, inequality_constraint_matrix, kernel_matrix, offset, inequality_constraint_matrix,
inequality_constraint_boundary, equality_constraint_matrix, inequality_constraint_boundary, equality_constraint_matrix,
equality_constraint_boundary)); equality_constraint_boundary));
......
...@@ -51,7 +51,7 @@ class Spline2dSolver { ...@@ -51,7 +51,7 @@ class Spline2dSolver {
Spline2d spline_; Spline2d spline_;
Spline2dKernel kernel_; Spline2dKernel kernel_;
Spline2dConstraint constraint_; Spline2dConstraint constraint_;
std::unique_ptr<apollo::common::math::QPSolver> qp_solver_ = nullptr; std::unique_ptr<apollo::common::math::QpSolver> qp_solver_ = nullptr;
}; };
} // namespace planning } // namespace planning
......
...@@ -36,7 +36,7 @@ ...@@ -36,7 +36,7 @@
namespace apollo { namespace apollo {
namespace planning { namespace planning {
bool QPSplinePathGenerator::SetConfig(const std::string& config_file) { bool QpSplinePathGenerator::SetConfig(const std::string& config_file) {
if (!common::util::GetProtoFromFile(config_file, &_qp_spline_path_config)) { if (!common::util::GetProtoFromFile(config_file, &_qp_spline_path_config)) {
AERROR << "Failed to load config file " << config_file; AERROR << "Failed to load config file " << config_file;
return false; return false;
...@@ -44,7 +44,7 @@ bool QPSplinePathGenerator::SetConfig(const std::string& config_file) { ...@@ -44,7 +44,7 @@ bool QPSplinePathGenerator::SetConfig(const std::string& config_file) {
return true; return true;
} }
bool QPSplinePathGenerator::generate(const ReferenceLine& reference_line, bool QpSplinePathGenerator::generate(const ReferenceLine& reference_line,
const DecisionData& decision_data, const DecisionData& decision_data,
const SpeedData& speed_data, const SpeedData& speed_data,
const common::TrajectoryPoint& init_point, const common::TrajectoryPoint& init_point,
...@@ -140,7 +140,7 @@ bool QPSplinePathGenerator::generate(const ReferenceLine& reference_line, ...@@ -140,7 +140,7 @@ bool QPSplinePathGenerator::generate(const ReferenceLine& reference_line,
return true; return true;
} }
bool QPSplinePathGenerator::calculate_sl_point( bool QpSplinePathGenerator::calculate_sl_point(
const ReferenceLine& reference_line, const ReferenceLine& reference_line,
const common::TrajectoryPoint& traj_point, const common::TrajectoryPoint& traj_point,
common::FrenetFramePoint* const frenet_frame_point) { common::FrenetFramePoint* const frenet_frame_point) {
...@@ -173,7 +173,7 @@ bool QPSplinePathGenerator::calculate_sl_point( ...@@ -173,7 +173,7 @@ bool QPSplinePathGenerator::calculate_sl_point(
return true; return true;
} }
bool QPSplinePathGenerator::init_coord_range(double* const start_s, bool QpSplinePathGenerator::init_coord_range(double* const start_s,
double* const end_s) { double* const end_s) {
// TODO(all): step 1 get current sl coordinate - with init coordinate point // TODO(all): step 1 get current sl coordinate - with init coordinate point
double start_point = std::max(_init_point.s() - 5.0, 0.0); double start_point = std::max(_init_point.s() - 5.0, 0.0);
...@@ -194,7 +194,7 @@ bool QPSplinePathGenerator::init_coord_range(double* const start_s, ...@@ -194,7 +194,7 @@ bool QPSplinePathGenerator::init_coord_range(double* const start_s,
return true; return true;
} }
bool QPSplinePathGenerator::init_smoothing_spline( bool QpSplinePathGenerator::init_smoothing_spline(
const ReferenceLine& reference_line, const double start_s, const ReferenceLine& reference_line, const double start_s,
const double end_s) { const double end_s) {
QpSplinePathSampler sampler(_qp_spline_path_config); QpSplinePathSampler sampler(_qp_spline_path_config);
...@@ -212,7 +212,7 @@ bool QPSplinePathGenerator::init_smoothing_spline( ...@@ -212,7 +212,7 @@ bool QPSplinePathGenerator::init_smoothing_spline(
return true; return true;
} }
bool QPSplinePathGenerator::setup_constraint() { bool QpSplinePathGenerator::setup_constraint() {
Spline1dConstraint* spline_constraint = Spline1dConstraint* spline_constraint =
_spline_generator->mutable_spline_constraint(); _spline_generator->mutable_spline_constraint();
// add init status constraint // add init status constraint
...@@ -284,7 +284,7 @@ bool QPSplinePathGenerator::setup_constraint() { ...@@ -284,7 +284,7 @@ bool QPSplinePathGenerator::setup_constraint() {
return true; return true;
} }
bool QPSplinePathGenerator::setup_kernel() { bool QpSplinePathGenerator::setup_kernel() {
Spline1dKernel* spline_kernel = _spline_generator->mutable_spline_kernel(); Spline1dKernel* spline_kernel = _spline_generator->mutable_spline_kernel();
if (_qp_spline_path_config.regularization_weight() > 0) { if (_qp_spline_path_config.regularization_weight() > 0) {
...@@ -311,7 +311,7 @@ bool QPSplinePathGenerator::setup_kernel() { ...@@ -311,7 +311,7 @@ bool QPSplinePathGenerator::setup_kernel() {
return true; return true;
} }
bool QPSplinePathGenerator::solve() { bool QpSplinePathGenerator::solve() {
if (!_spline_generator->solve()) { if (!_spline_generator->solve()) {
AERROR << "Could not solve the qp problem in spline path generator."; AERROR << "Could not solve the qp problem in spline path generator.";
return false; return false;
......
...@@ -36,9 +36,9 @@ ...@@ -36,9 +36,9 @@
namespace apollo { namespace apollo {
namespace planning { namespace planning {
class QPSplinePathGenerator { class QpSplinePathGenerator {
public: public:
QPSplinePathGenerator() = default; QpSplinePathGenerator() = default;
bool SetConfig(const std::string& config_file); bool SetConfig(const std::string& config_file);
bool generate(const ReferenceLine& reference_line, bool generate(const ReferenceLine& reference_line,
const DecisionData& decision_data, const SpeedData& speed_data, const DecisionData& decision_data, const SpeedData& speed_data,
...@@ -68,7 +68,7 @@ class QPSplinePathGenerator { ...@@ -68,7 +68,7 @@ class QPSplinePathGenerator {
double* const y_diff) const; double* const y_diff) const;
private: private:
QPSplinePathConfig _qp_spline_path_config; QpSplinePathConfig _qp_spline_path_config;
common::FrenetFramePoint _init_point; common::FrenetFramePoint _init_point;
QpFrenetFrame _qp_frenet_frame; QpFrenetFrame _qp_frenet_frame;
std::unique_ptr<Spline1dGenerator> _spline_generator; std::unique_ptr<Spline1dGenerator> _spline_generator;
......
...@@ -27,10 +27,10 @@ namespace planning { ...@@ -27,10 +27,10 @@ namespace planning {
using apollo::common::ErrorCode; using apollo::common::ErrorCode;
using apollo::common::Status; using apollo::common::Status;
QPSplinePathOptimizer::QPSplinePathOptimizer(const std::string& name) QpSplinePathOptimizer::QpSplinePathOptimizer(const std::string& name)
: PathOptimizer(name) {} : PathOptimizer(name) {}
bool QPSplinePathOptimizer::Init() { bool QpSplinePathOptimizer::Init() {
if (!_path_generator.SetConfig(FLAGS_qp_spline_path_config_file)) { if (!_path_generator.SetConfig(FLAGS_qp_spline_path_config_file)) {
AERROR << "Fail to set config file for path generator."; AERROR << "Fail to set config file for path generator.";
return false; return false;
...@@ -39,7 +39,7 @@ bool QPSplinePathOptimizer::Init() { ...@@ -39,7 +39,7 @@ bool QPSplinePathOptimizer::Init() {
return true; return true;
} }
Status QPSplinePathOptimizer::Process(const SpeedData& speed_data, Status QpSplinePathOptimizer::Process(const SpeedData& speed_data,
const ReferenceLine& reference_line, const ReferenceLine& reference_line,
const common::TrajectoryPoint& init_point, const common::TrajectoryPoint& init_point,
DecisionData* const decision_data, DecisionData* const decision_data,
......
...@@ -30,9 +30,9 @@ ...@@ -30,9 +30,9 @@
namespace apollo { namespace apollo {
namespace planning { namespace planning {
class QPSplinePathOptimizer : public PathOptimizer { class QpSplinePathOptimizer : public PathOptimizer {
public: public:
explicit QPSplinePathOptimizer(const std::string& name); explicit QpSplinePathOptimizer(const std::string& name);
bool Init() override; bool Init() override;
private: private:
...@@ -43,7 +43,7 @@ class QPSplinePathOptimizer : public PathOptimizer { ...@@ -43,7 +43,7 @@ class QPSplinePathOptimizer : public PathOptimizer {
PathData* const path_data) override; PathData* const path_data) override;
private: private:
QPSplinePathGenerator _path_generator; QpSplinePathGenerator _path_generator;
}; };
} // namespace planning } // namespace planning
......
...@@ -28,7 +28,7 @@ ...@@ -28,7 +28,7 @@
namespace apollo { namespace apollo {
namespace planning { namespace planning {
QpSplinePathSampler::QpSplinePathSampler(const QPSplinePathConfig& config) QpSplinePathSampler::QpSplinePathSampler(const QpSplinePathConfig& config)
: config_(config) {} : config_(config) {}
bool QpSplinePathSampler::Sample(const common::FrenetFramePoint& init_point, bool QpSplinePathSampler::Sample(const common::FrenetFramePoint& init_point,
......
...@@ -31,14 +31,14 @@ namespace planning { ...@@ -31,14 +31,14 @@ namespace planning {
class QpSplinePathSampler { class QpSplinePathSampler {
public: public:
explicit QpSplinePathSampler(const QPSplinePathConfig& config); explicit QpSplinePathSampler(const QpSplinePathConfig& config);
bool Sample(const common::FrenetFramePoint& init_point, bool Sample(const common::FrenetFramePoint& init_point,
const ReferenceLine& reference_line, const double s_lower_bound, const ReferenceLine& reference_line, const double s_lower_bound,
const double s_upper_bound, const double s_upper_bound,
std::vector<double>* const sampling_point); std::vector<double>* const sampling_point);
private: private:
const QPSplinePathConfig config_; const QpSplinePathConfig config_;
}; };
} // namespace planning } // namespace planning
......
...@@ -55,7 +55,7 @@ void EMPlanner::RegisterOptimizers() { ...@@ -55,7 +55,7 @@ void EMPlanner::RegisterOptimizers() {
return new DpStSpeedOptimizer("DpStSpeedOptimizer"); return new DpStSpeedOptimizer("DpStSpeedOptimizer");
}); });
optimizer_factory_.Register(QP_SPLINE_PATH_OPTIMIZER, []() -> Optimizer* { optimizer_factory_.Register(QP_SPLINE_PATH_OPTIMIZER, []() -> Optimizer* {
return new QPSplinePathOptimizer("QPSplinePathOptimizer"); return new QpSplinePathOptimizer("QpSplinePathOptimizer");
}); });
optimizer_factory_.Register(QP_SPLINE_ST_SPEED_OPTIMIZER, []() -> Optimizer* { optimizer_factory_.Register(QP_SPLINE_ST_SPEED_OPTIMIZER, []() -> Optimizer* {
return new QpSplineStSpeedOptimizer("QpSplineStSpeedOptimizer"); return new QpSplineStSpeedOptimizer("QpSplineStSpeedOptimizer");
......
...@@ -2,7 +2,7 @@ syntax = "proto2"; ...@@ -2,7 +2,7 @@ syntax = "proto2";
package apollo.planning; package apollo.planning;
message QPSplinePathConfig { message QpSplinePathConfig {
optional uint32 spline_order = 1 [default = 6]; optional uint32 spline_order = 1 [default = 6];
optional uint32 number_of_spline = 2 [default = 5]; optional uint32 number_of_spline = 2 [default = 5];
optional uint32 number_of_fx_constraint_knots = 3 [default = 6]; optional uint32 number_of_fx_constraint_knots = 3 [default = 6];
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册