ddp_solver_py.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018-2020, University of Edinburgh, University of Oxford
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 //
8 // * Redistributions of source code must retain the above copyright notice,
9 // this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without specific
15 // prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 //
29 
34 #include <pybind11/eigen.h>
35 #include <pybind11/pybind11.h>
36 #include <pybind11/stl.h>
37 
38 using namespace exotica;
39 namespace py = pybind11;
40 
41 PYBIND11_MODULE(exotica_ddp_solver_py, module)
42 {
43  module.doc() = "Exotica DDP Solver";
44 
45  py::module::import("pyexotica");
46 
47  py::class_<AbstractDDPSolver, std::shared_ptr<AbstractDDPSolver>, FeedbackMotionSolver>(module, "AbstractDDPSolver")
48  .def_property_readonly("Vxx", &AbstractDDPSolver::get_Vxx)
49  .def_property_readonly("Vx", &AbstractDDPSolver::get_Vx)
50  .def_property_readonly("Qxx", &AbstractDDPSolver::get_Qxx)
51  .def_property_readonly("Qux", &AbstractDDPSolver::get_Qux)
52  .def_property_readonly("Quu", &AbstractDDPSolver::get_Quu)
53  .def_property_readonly("Qx", &AbstractDDPSolver::get_Qx)
54  .def_property_readonly("Qu", &AbstractDDPSolver::get_Qu)
55  .def_property_readonly("K", &AbstractDDPSolver::get_K)
56  .def_property_readonly("k", &AbstractDDPSolver::get_k)
57  .def_property_readonly("X_try", &AbstractDDPSolver::get_X_try)
58  .def_property_readonly("U_try", &AbstractDDPSolver::get_U_try)
59  .def_property_readonly("X_ref", &AbstractDDPSolver::get_X_ref)
60  .def_property_readonly("U_ref", &AbstractDDPSolver::get_U_ref)
61  .def_property_readonly("Quu_inv", &AbstractDDPSolver::get_Quu_inv)
62  .def_property_readonly("fx", &AbstractDDPSolver::get_fx)
63  .def_property_readonly("fu", &AbstractDDPSolver::get_fu)
64  .def_property_readonly("control_cost_evolution", &AbstractDDPSolver::get_control_cost_evolution)
65  .def_property_readonly("steplength_evolution", &AbstractDDPSolver::get_steplength_evolution)
66  .def_property_readonly("regularization_evolution", &AbstractDDPSolver::get_regularization_evolution);
67 
68  py::class_<AnalyticDDPSolver, std::shared_ptr<AnalyticDDPSolver>, AbstractDDPSolver> analytic_ddp_solver(module, "AnalyticDDPSolver");
69 
70  py::class_<ControlLimitedDDPSolver, std::shared_ptr<ControlLimitedDDPSolver>, AbstractDDPSolver> control_limited_ddp_solver(module, "ControlLimitedDDPSolver");
71 
72  py::class_<FeasibilityDrivenDDPSolver, std::shared_ptr<FeasibilityDrivenDDPSolver>, AbstractDDPSolver> feasibility_driven_ddp_solver(module, "FeasibilityDrivenDDPSolver");
73  feasibility_driven_ddp_solver.def_property_readonly("fs", &FeasibilityDrivenDDPSolver::get_fs);
74  feasibility_driven_ddp_solver.def_property_readonly("xs", &FeasibilityDrivenDDPSolver::get_xs);
75  feasibility_driven_ddp_solver.def_property_readonly("us", &FeasibilityDrivenDDPSolver::get_us);
76 
77  py::class_<ControlLimitedFeasibilityDrivenDDPSolver, std::shared_ptr<ControlLimitedFeasibilityDrivenDDPSolver>, AbstractDDPSolver> control_limited_feasibility_driven_ddp_solver(module, "ControlLimitedFeasibilityDrivenDDPSolver");
78 }
const std::vector< Eigen::VectorXd > & get_fs() const
const std::vector< Eigen::VectorXd > & get_U_try() const
const std::vector< Eigen::VectorXd > & get_Qu() const
const std::vector< Eigen::VectorXd > & get_U_ref() const
const std::vector< Eigen::VectorXd > & get_X_ref() const
const std::vector< Eigen::MatrixXd > & get_Quu() const
const std::vector< Eigen::MatrixXd > & get_fx() const
const std::vector< Eigen::VectorXd > & get_us() const
const std::vector< Eigen::MatrixXd > & get_fu() const
const std::vector< Eigen::MatrixXd > & get_K() const
const std::vector< Eigen::VectorXd > & get_Vx() const
const std::vector< Eigen::MatrixXd > & get_Qux() const
std::vector< double > get_steplength_evolution() const
const std::vector< Eigen::MatrixXd > & get_Vxx() const
std::vector< double > get_regularization_evolution() const
const std::vector< Eigen::MatrixXd > & get_Quu_inv() const
const std::vector< Eigen::VectorXd > & get_Qx() const
PYBIND11_MODULE(exotica_ddp_solver_py, module)
const std::vector< Eigen::VectorXd > & get_k() const
const std::vector< Eigen::VectorXd > & get_xs() const
const std::vector< Eigen::VectorXd > & get_X_try() const
const std::vector< Eigen::MatrixXd > & get_Qxx() const
std::vector< double > get_control_cost_evolution() const


exotica_ddp_solver
Author(s): Traiko Dinev
autogenerated on Sat Apr 10 2021 02:36:21