diff --git a/CHANGELOG.md b/CHANGELOG.md index 05ad8360a..198f24228 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -15,6 +15,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ### Fixed +- Fixed copy of TrajOptProblem ([#265](https://github.com/Simple-Robotics/aligator/pull/265)) - `LinesearchVariant::init()` should not be called unless the step accpetance strategy is a linesearch - Fixed compilation issues with C++20 (resolving [#246](https://github.com/Simple-Robotics/aligator/issues/246) and [#254](https://github.com/Simple-Robotics/aligator/discussions/254)) diff --git a/README.md b/README.md index cbf17d3d4..203a10568 100644 --- a/README.md +++ b/README.md @@ -133,6 +133,7 @@ Please also consider citing the reference paper for the ProxDDP algorithm: * [Fabian Schramm](https://github.com/fabinsch) (Inria): core developer * [Ludovic De Matteïs](https://github.com/LudovicDeMatteis) (LAAS-CNRS/Inria): feature developer * [Ewen Dantec](https://edantec.github.io/) (Inria): feature developer +* [Antoine Bussy](https://github.com/antoine-bussy) (Aldebaran) ## Acknowledgments diff --git a/include/aligator/core/traj-opt-problem.hpp b/include/aligator/core/traj-opt-problem.hpp index 94774a2c6..3fabfd5c5 100644 --- a/include/aligator/core/traj-opt-problem.hpp +++ b/include/aligator/core/traj-opt-problem.hpp @@ -127,7 +127,10 @@ template struct TrajOptProblemTpl { xyz::polymorphic space, xyz::polymorphic term_cost); - bool initCondIsStateError() const { return init_state_error_ != nullptr; } + bool initCondIsStateError() const { + assert(init_cond_is_state_error_ == checkInitCondIsStateError()); + return init_cond_is_state_error_; + } /// @brief Add a stage to the control problem. void addStage(const xyz::polymorphic &stage); @@ -138,7 +141,7 @@ template struct TrajOptProblemTpl { ALIGATOR_RUNTIME_ERROR( "Initial condition is not a StateErrorResidual.\n"); } - return init_state_error_->target_; + return static_cast(&*init_constraint_)->target_; } /// @brief Set initial state constraint. @@ -147,7 +150,7 @@ template struct TrajOptProblemTpl { ALIGATOR_RUNTIME_ERROR( "Initial condition is not a StateErrorResidual.\n"); } - init_state_error_->target_ = x0; + static_cast(&*init_constraint_)->target_ = x0; } /// @brief Add a terminal constraint for the model. @@ -187,8 +190,10 @@ template struct TrajOptProblemTpl { bool checkIntegrity() const; protected: - /// Pointer to underlying state error residual - StateErrorResidual *init_state_error_; + // Check if the initial state is a StateErrorResidual. + // Since this is a costly operation (dynamic_cast), we cache the result. + bool checkInitCondIsStateError() const; + bool init_cond_is_state_error_ = false; }; namespace internal { diff --git a/include/aligator/core/traj-opt-problem.hxx b/include/aligator/core/traj-opt-problem.hxx index dd8843f12..9a14fcc9a 100644 --- a/include/aligator/core/traj-opt-problem.hxx +++ b/include/aligator/core/traj-opt-problem.hxx @@ -17,9 +17,9 @@ TrajOptProblemTpl::TrajOptProblemTpl( const std::vector> &stages, xyz::polymorphic term_cost) : init_constraint_(std::move(init_constraint)), stages_(stages), - term_cost_(std::move(term_cost)), unone_(term_cost_->nu) { + term_cost_(std::move(term_cost)), unone_(term_cost_->nu), + init_cond_is_state_error_(checkInitCondIsStateError()) { unone_.setZero(); - init_state_error_ = dynamic_cast(&*init_constraint_); } template @@ -29,9 +29,7 @@ TrajOptProblemTpl::TrajOptProblemTpl( xyz::polymorphic term_cost) : TrajOptProblemTpl( StateErrorResidual(stages[0]->xspace_, stages[0]->nu(), x0), stages, - std::move(term_cost)) { - init_state_error_ = static_cast(&*init_constraint_); -} + std::move(term_cost)) {} template TrajOptProblemTpl::TrajOptProblemTpl( @@ -131,6 +129,9 @@ template bool TrajOptProblemTpl::checkIntegrity() const { bool ok = true; + if (init_cond_is_state_error_ != checkInitCondIsStateError()) + return false; + if (numSteps() == 0) return true; @@ -173,4 +174,11 @@ void TrajOptProblemTpl::replaceStageCircular( stages_.pop_back(); } +template +bool TrajOptProblemTpl::checkInitCondIsStateError() const { + if (init_constraint_.valueless_after_move()) + return false; + return dynamic_cast(&*init_constraint_); +} + } // namespace aligator diff --git a/tests/problem.cpp b/tests/problem.cpp index eca0d87e7..b7727b73c 100644 --- a/tests/problem.cpp +++ b/tests/problem.cpp @@ -151,4 +151,24 @@ BOOST_AUTO_TEST_CASE(test_workspace) { ResultsTpl results(f.problem); } +BOOST_AUTO_TEST_CASE(test_copy) { + MyFixture f; + + auto copy = f.problem; + BOOST_CHECK_EQUAL(copy.getInitState(), f.problem.getInitState()); + + Eigen::VectorXd state = f.problem.getInitState(); + + state[0] = 0.; + f.problem.setInitState(state); + BOOST_CHECK_EQUAL(f.problem.getInitState()[0], 0.); + + state[0] = 1.; + BOOST_CHECK_EQUAL(f.problem.getInitState()[0], 0.); + + copy.setInitState(state); + BOOST_CHECK_EQUAL(copy.getInitState()[0], 1.); + BOOST_CHECK_EQUAL(f.problem.getInitState()[0], 0.); +} + BOOST_AUTO_TEST_SUITE_END()