@@ -57,11 +57,13 @@ class NewtonOptimizer : public Optimizer
5757
5858 std::tuple<std::vector<typename RobotModel::StateT>,
5959 std::vector<typename RobotModel::InputT>> forwardPass (
60+ const typename RobotModel::StateT & x0,
6061 const std::vector<typename RobotModel::StateT> & x_feasible,
6162 const std::vector<typename RobotModel::InputT> & u_feasible,
6263 const std::vector<MatrixXd> & K_gains, const double dt, const double alpha);
6364
6465 std::vector<typename RobotModel::InputT> optimize (
66+ const typename RobotModel::StateT & x0,
6567 const std::vector<typename RobotModel::StateT> & x_feasible, const Matrix3d & Q,
6668 const Matrix2d & R, const double dt);
6769
@@ -136,6 +138,7 @@ std::vector<MatrixXd> NewtonOptimizer<RobotModel>::backwardPass(
136138template <typename RobotModel>
137139std::tuple<std::vector<typename RobotModel::StateT>,
138140 std::vector<typename RobotModel::InputT>> NewtonOptimizer<RobotModel>::forwardPass(
141+ const typename RobotModel::StateT & x0,
139142 const std::vector<typename RobotModel::StateT> & x_feasible,
140143 const std::vector<typename RobotModel::InputT> & u_feasible,
141144 const std::vector<MatrixXd> & K_gains, const double dt, const double alpha)
@@ -147,7 +150,7 @@ std::tuple<std::vector<typename RobotModel::StateT>,
147150 std::vector<typename RobotModel::InputT> u_applied (input_size);
148151
149152 // assert trajectory_size > 0
150- x_tracked[0 ] = x_feasible[ 0 ] ;
153+ x_tracked[0 ] = x0 ;
151154 for (typename std::vector<typename RobotModel::StateT>::difference_type i = 0 ,
152155 max_difference = std::distance (x_feasible.begin (), std::prev (x_feasible.end (), 1 ));
153156 i < max_difference; ++i)
@@ -180,6 +183,7 @@ std::tuple<MatrixXd, MatrixXd> NewtonOptimizer<RobotModel>::solveDiscreteLQRProb
180183
181184template <typename RobotModel>
182185std::vector<typename RobotModel::InputT> NewtonOptimizer<RobotModel>::optimize(
186+ const typename RobotModel::StateT & x0,
183187 const std::vector<typename RobotModel::StateT> & x_trajectory, const Matrix3d & Q,
184188 const Matrix2d & R, const double dt)
185189{
@@ -198,7 +202,7 @@ std::vector<typename RobotModel::InputT> NewtonOptimizer<RobotModel>::optimize(
198202 double previous_best_trajectory_cost = best_trajectory_cost;
199203 for (size_t i = 0 ; i < iteration_number_; ++i) {
200204 auto K_gain_list = this ->backwardPass (x_trajectory, u_optimized, Q, R, dt);
201- auto [x_tracked, u_tracked] = this ->forwardPass (
205+ auto [x_tracked, u_tracked] = this ->forwardPass (x0,
202206 x_trajectory, u_optimized, K_gain_list, dt,
203207 alpha);
204208 u_optimized = u_tracked;
0 commit comments