提交 783a9321 编写于 作者: C Capri2014 提交者: Dong Li

Move qp solver to common/math (#62)

* Seperate qp_solver_flags from planning_flags

* Move qp solver from planning to common
上级 96e71bcc
......@@ -2,6 +2,19 @@ load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "qp_solver_gflags",
srcs = [
"qp_solver_gflags.cc",
],
hdrs = [
"qp_solver_gflags.h",
],
deps = [
"//external:gflags",
],
)
cc_library(
name = "qp_solver",
srcs = [
......@@ -25,7 +38,7 @@ cc_library(
],
deps = [
":qp_solver",
"//modules/planning/common:planning_gflags",
"//modules/common/math/qp_solver:qp_solver_gflags",
"@eigen//:eigen",
"//third_party/qp_oases",
],
......
......@@ -17,16 +17,17 @@
/**
* @file: active_set_qp_solver.cc
**/
#include "modules/planning/math/qp_solver/active_set_qp_solver.h"
#include "modules/common/math/qp_solver/active_set_qp_solver.h"
#include <algorithm>
#include <climits>
#include <vector>
#include "modules/planning/common/planning_gflags.h"
#include "modules/common/math/qp_solver/qp_solver_gflags.h"
namespace apollo {
namespace planning {
namespace common {
namespace math {
ActiveSetQPSolver::ActiveSetQPSolver(
const Eigen::MatrixXd& kernel_matrix, const Eigen::MatrixXd& offset,
......@@ -192,5 +193,6 @@ bool ActiveSetQPSolver::sanity_check() {
affine_inequality_matrix_.rows() == affine_inequality_matrix_.rows();
}
} // namespace planning
} // namespace math
} // namespace common
} // namespace apollo
......@@ -18,15 +18,16 @@
* @file: active_set_qp_solver.h
* @brief: wrapper class for active set method in qpOases
**/
#ifndef MODULES_PLANNING_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
#define MODULES_PLANNING_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
#ifndef MODULES_COMMON_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
#define MODULES_COMMON_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
#include "qpOASES/include/qpOASES.hpp"
#include "modules/planning/math/qp_solver/qp_solver.h"
#include "modules/common/math/qp_solver/qp_solver.h"
namespace apollo {
namespace planning {
namespace common {
namespace math {
class ActiveSetQPSolver : public QPSolver {
public:
......@@ -82,6 +83,7 @@ class ActiveSetQPSolver : public QPSolver {
int max_iteration_ = 1000;
};
} // namespace planning
} // namespace math
} // namespace common
} // namespace apollo
#endif // MODULES_PLANNING_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
#endif // MODULES_COMMON_MATH_QP_SOLVER_ACTIVE_SET_QP_SOLVER_H_
......@@ -17,10 +17,11 @@
/**
* @file: qp_solver.cc
**/
#include "modules/planning/math/qp_solver/qp_solver.h"
#include "modules/common/math/qp_solver/qp_solver.h"
namespace apollo {
namespace planning {
namespace common {
namespace math {
QPSolver::QPSolver(const Eigen::MatrixXd& kernel_matrix,
const Eigen::MatrixXd& offset,
......@@ -59,5 +60,6 @@ const Eigen::MatrixXd& QPSolver::affine_inequality_boundary() const {
return affine_inequality_boundary_;
}
} // namespace planning
} // namespace math
} // namespace common
} // namespace apollo
......@@ -23,14 +23,15 @@
* C * x >= d (equality constraint)
**/
#ifndef MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_H_
#define MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_H_
#ifndef MODULES_COMMON_MATH_QP_SOLVER_QP_SOLVER_H_
#define MODULES_COMMON_MATH_QP_SOLVER_QP_SOLVER_H_
#include "Eigen/Core"
#include "Eigen/LU"
namespace apollo {
namespace planning {
namespace common {
namespace math {
class QPSolver {
public:
......@@ -60,7 +61,8 @@ class QPSolver {
Eigen::MatrixXd affine_equality_boundary_;
};
} // namespace planning
} // namespace math
} // namespace common
} // namespace apollo
#endif // MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_H_
#endif // MODULES_COMMON_MATH_QP_SOLVER_QP_SOLVER_H_
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/common/math/qp_solver/qp_solver_gflags.h"
// math : active set solver
DEFINE_double(default_active_set_eps_num, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_double(default_active_set_eps_den, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_double(default_active_set_eps_iter_ref, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_bool(default_enable_active_set_debug_info, false,
"Enable print information");
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#ifndef MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_GFLAGS_H_
#define MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_GFLAGS_H_
#include "gflags/gflags.h"
// math : active set solver
DECLARE_double(default_active_set_eps_num);
DECLARE_double(default_active_set_eps_den);
DECLARE_double(default_active_set_eps_iter_ref);
DECLARE_bool(default_enable_active_set_debug_info);
#endif /* MODULES_PLANNING_MATH_QP_SOLVER_QP_SOLVER_GFLAGS_H_ */
......@@ -40,13 +40,3 @@ DEFINE_double(replanning_threshold, 2.0,
DEFINE_double(trajectory_resolution, 0.01,
"The time resolution of "
"output trajectory.");
// math : active set solver
DEFINE_double(default_active_set_eps_num, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_double(default_active_set_eps_den, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_double(default_active_set_eps_iter_ref, 1e-7,
"qpOases wrapper error control numerator");
DEFINE_bool(default_enable_active_set_debug_info, false,
"Enable print information");
......@@ -27,10 +27,4 @@ DECLARE_uint64(rtk_trajectory_forward);
DECLARE_double(replanning_threshold);
DECLARE_double(trajectory_resolution);
// math : active set solver
DECLARE_double(default_active_set_eps_num);
DECLARE_double(default_active_set_eps_den);
DECLARE_double(default_active_set_eps_iter_ref);
DECLARE_bool(default_enable_active_set_debug_info);
#endif /* MODULES_PLANNING_COMMON_PLANNING_GFLAGS_H_ */
......@@ -104,8 +104,8 @@ cc_library(
":spline_1d",
":spline_1d_constraint",
":spline_1d_kernel",
"//modules/planning/math/qp_solver",
"//modules/planning/math/qp_solver:active_set_qp_solver",
"//modules/common/math/qp_solver",
"//modules/common/math/qp_solver:active_set_qp_solver",
"@eigen//:eigen",
"@glog//:glog",
],
......@@ -186,8 +186,8 @@ cc_library(
":spline_2d_constraint",
":spline_2d_kernel",
"//modules/common/math:vec2d",
"//modules/planning/math/qp_solver",
"//modules/planning/math/qp_solver:active_set_qp_solver",
"//modules/common/math/qp_solver",
"//modules/common/math/qp_solver:active_set_qp_solver",
"@eigen//:eigen",
],
)
......
......@@ -23,7 +23,7 @@
#include "modules/planning/math/smoothing_spline/spline_1d_generator.h"
#include "modules/planning/math/qp_solver/active_set_qp_solver.h"
#include "modules/common/math/qp_solver/active_set_qp_solver.h"
namespace apollo {
namespace planning {
......@@ -64,7 +64,7 @@ bool Spline1dGenerator::solve() {
const Eigen::MatrixXd& equality_constraint_boundary =
spline_constraint_.equality_constraint().constraint_boundary();
qp_solver_.reset(new ActiveSetQPSolver(
qp_solver_.reset(new apollo::common::math::ActiveSetQPSolver(
kernel_matrix, offset, inequality_constraint_matrix,
inequality_constraint_boundary, equality_constraint_matrix,
equality_constraint_boundary));
......
......@@ -54,7 +54,7 @@
#include "Eigen/Core"
#include "glog/logging.h"
#include "modules/planning/math/qp_solver/qp_solver.h"
#include "modules/common/math/qp_solver/qp_solver.h"
#include "modules/planning/math/smoothing_spline/spline_1d.h"
#include "modules/planning/math/smoothing_spline/spline_1d_constraint.h"
#include "modules/planning/math/smoothing_spline/spline_1d_kernel.h"
......@@ -89,7 +89,7 @@ class Spline1dGenerator {
Spline1dConstraint spline_constraint_;
Spline1dKernel spline_kernel_;
std::unique_ptr<QPSolver> qp_solver_ = nullptr;
std::unique_ptr<apollo::common::math::QPSolver> qp_solver_ = nullptr;
Eigen::MatrixXd init_x_;
Eigen::MatrixXd init_y_;
Eigen::MatrixXd init_z_;
......
......@@ -19,7 +19,7 @@
**/
#include "modules/planning/math/smoothing_spline/spline_2d_solver.h"
#include "modules/planning/math/qp_solver/active_set_qp_solver.h"
#include "modules/common/math/qp_solver/active_set_qp_solver.h"
namespace apollo {
namespace planning {
......@@ -52,7 +52,7 @@ bool Spline2dSolver::solve() {
const Eigen::MatrixXd& equality_constraint_boundary =
constraint_.equality_constraint().constraint_boundary();
qp_solver_.reset(new ActiveSetQPSolver(
qp_solver_.reset(new apollo::common::math::ActiveSetQPSolver(
kernel_matrix, offset, inequality_constraint_matrix,
inequality_constraint_boundary, equality_constraint_matrix,
equality_constraint_boundary));
......
......@@ -24,7 +24,7 @@
#include <memory>
#include <vector>
#include "modules/planning/math/qp_solver/qp_solver.h"
#include "modules/common/math/qp_solver/qp_solver.h"
#include "modules/planning/math/smoothing_spline/spline_2d.h"
#include "modules/planning/math/smoothing_spline/spline_2d_constraint.h"
#include "modules/planning/math/smoothing_spline/spline_2d_kernel.h"
......@@ -51,7 +51,7 @@ class Spline2dSolver {
Spline2d spline_;
Spline2dKernel kernel_;
Spline2dConstraint constraint_;
std::unique_ptr<QPSolver> qp_solver_ = nullptr;
std::unique_ptr<apollo::common::math::QPSolver> qp_solver_ = nullptr;
};
} // namespace planning
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册