diff --git a/.clang-format b/.clang-format
index 102216266..5e70adf83 100644
--- a/.clang-format
+++ b/.clang-format
@@ -35,8 +35,7 @@ BreakBeforeBinaryOperators: None
BreakBeforeBraces: Custom
BreakBeforeTernaryOperators: false
BreakConstructorInitializersBeforeComma: false
-BreakAfterJavaFieldAnnotations: false
-BreakStringLiterals: true
+#BreakStringLiterals: true
ColumnLimit: 120
CommentPragmas: '^ IWYU pragma:'
ConstructorInitializerAllOnOneLineOrOnePerLine: true
@@ -54,12 +53,9 @@ IncludeCategories:
Priority: 2
- Regex: '.*'
Priority: 3
-IncludeIsMainRegex: '([-_](test|unittest))?$'
IndentCaseLabels: true
IndentWidth: 4
IndentWrappedFunctionNames: false
-JavaScriptQuotes: Leave
-JavaScriptWrapImports: true
KeepEmptyLinesAtTheStartOfBlocks: false
MacroBlockBegin: ''
MacroBlockEnd: ''
diff --git a/README.md b/README.md
index abc9ab8a0..d836de4b3 100644
--- a/README.md
+++ b/README.md
@@ -56,10 +56,16 @@ The CT was designed with the following features in mind:
The Control Toolbox has been used for Hardware and Simulation control tasks on flying, walking and ground robots.
-[![ct example](https://img.youtube.com/vi/Y7-1CBqs4x4/0.jpg)](https://www.youtube.com/embed/Y7-1CBqs4x4)
-[![ct_example](https://img.youtube.com/vi/vuCSKtP67E4/0.jpg)](https://www.youtube.com/embed/vuCSKtP67E4)
-[![ct_example](https://img.youtube.com/vi/rWmw-ERGyz4/0.jpg)](https://www.youtube.com/embed/rWmw-ERGyz4)
-[![ct_example](https://img.youtube.com/vi/rVu1L_tPCoM/0.jpg)](https://www.youtube.com/embed/rVu1L_tPCoM)
+
+
+
+
+
+
## What is the CT?
diff --git a/ct_core/cmake/FindCppAD.cmake b/ct_core/cmake/FindCppAD.cmake
index 7eed22dd0..808014a63 100644
--- a/ct_core/cmake/FindCppAD.cmake
+++ b/ct_core/cmake/FindCppAD.cmake
@@ -1,11 +1,15 @@
+UNSET(CPPAD_INCLUDE_DIRS CACHE)
+UNSET(CPPAD_LIBRARIES CACHE)
+
+
IF (CPPAD_INCLUDES AND CPPAD_LIBRARIES)
SET(CPPAD_FIND_QUIETLY TRUE)
ENDIF ()
IF(DEFINED CPPAD_HOME)
-
+
FIND_PATH(CPPAD_INCLUDE_DIR NAMES cppad/cppad.hpp
PATHS "${CPPAD_HOME}"
NO_DEFAULT_PATH)
diff --git a/ct_core/include/ct/core/common/activations/ActivationBase.hpp b/ct_core/include/ct/core/common/activations/ActivationBase.hpp
index 333d91a3d..4e02142db 100644
--- a/ct_core/include/ct/core/common/activations/ActivationBase.hpp
+++ b/ct_core/include/ct/core/common/activations/ActivationBase.hpp
@@ -19,9 +19,9 @@ class ActivationBase
{
public:
//! constructor
- ActivationBase() {}
+ ActivationBase() = default;
//! destructor
- virtual ~ActivationBase() {}
+ virtual ~ActivationBase() = default;
//! load activations from file
virtual void loadConfigFile(const std::string& filename, const std::string& termName, bool verbose = false)
{
diff --git a/ct_core/include/ct/core/core-prespec.h b/ct_core/include/ct/core/core-prespec.h
index 83d647504..f90df1f98 100644
--- a/ct_core/include/ct/core/core-prespec.h
+++ b/ct_core/include/ct/core/core-prespec.h
@@ -11,12 +11,16 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
#include
#include
+#ifdef CPPADCG
#include
+#endif
+#ifdef CPPAD
#include
#include
#include
#include "internal/autodiff/CppadParallel.h"
+#endif
// Include file for convenience
#include
diff --git a/ct_core/include/ct/core/core.h b/ct_core/include/ct/core/core.h
index 3b72864c7..cec6103ec 100644
--- a/ct_core/include/ct/core/core.h
+++ b/ct_core/include/ct/core/core.h
@@ -12,12 +12,16 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
#include
#include
+#ifdef CPPADCG
#include
+#endif
+#ifdef CPPAD
#include
#include
#include
#include "internal/autodiff/CppadParallel.h"
+#endif
// Include file for convenience
#include
diff --git a/ct_core/include/ct/core/integration/Integrator.h b/ct_core/include/ct/core/integration/Integrator.h
index b1d02ab62..4f37d8995 100644
--- a/ct_core/include/ct/core/integration/Integrator.h
+++ b/ct_core/include/ct/core/integration/Integrator.h
@@ -285,22 +285,23 @@ class Integrator
{
}
+#ifdef CPPADCG
template
typename std::enable_if::value, void>::type initializeODEIntSteppers(
const IntegrationType& intType)
{
}
-
+#endif
/**
- * @brief Initializes the ODEint fixed size steppers. Does not work for
+ * @brief Initializes the ODEint fixed size steppers for double type. Does not work for
* ad types
*
* @param[in] intType The int type
*
*/
template
- typename std::enable_if::value, void>::type initializeODEIntSteppers(
+ typename std::enable_if::value, void>::type initializeODEIntSteppers(
const IntegrationType& intType)
{
switch (intType)
@@ -349,6 +350,7 @@ class Integrator
}
}
+
//! resets the observer
void reset();
diff --git a/ct_core/include/ct/core/internal/traits/TraitSelectorSpecs.h b/ct_core/include/ct/core/internal/traits/TraitSelectorSpecs.h
index d5f5a7279..922520bee 100644
--- a/ct_core/include/ct/core/internal/traits/TraitSelectorSpecs.h
+++ b/ct_core/include/ct/core/internal/traits/TraitSelectorSpecs.h
@@ -5,26 +5,33 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
#pragma once
+#ifdef CPPADCG
#include "CppADCodegenTrait.h"
+#endif
+#ifdef CPPAD
#include "CppADDoubleTrait.h"
+#endif
#include
namespace ct {
namespace core {
namespace tpl {
+#ifdef CPPAD
template <>
struct TraitSelector>
{
typedef internal::CppADDoubleTrait Trait;
};
+#endif
+#ifdef CPPADCG
template <>
struct TraitSelector>>
{
typedef internal::CppADCodegenTrait Trait;
};
-
+#endif
} // namespace tpl
} // namespace core
diff --git a/ct_core/include/ct/core/types/AutoDiff.h b/ct_core/include/ct/core/types/AutoDiff.h
index e8b3ac91a..beb22f013 100644
--- a/ct_core/include/ct/core/types/AutoDiff.h
+++ b/ct_core/include/ct/core/types/AutoDiff.h
@@ -5,15 +5,24 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
#pragma once
+#ifdef CPPADCG
#include
+#endif
+
+#ifdef CPPAD
#include
+#endif
namespace ct {
namespace core {
+#ifdef CPPAD
typedef CppAD::AD ADScalar;
-typedef CppAD::cg::CG ADCGValueType;
+#endif
+#ifdef CPPADCG
+typedef CppAD::cg::CG ADCGValueType;
typedef CppAD::AD ADCGScalar; //!< scalar type
+#endif
}
}
diff --git a/ct_models/CMakeLists.txt b/ct_models/CMakeLists.txt
index 3f0cd1412..b2ee6d02e 100755
--- a/ct_models/CMakeLists.txt
+++ b/ct_models/CMakeLists.txt
@@ -30,7 +30,7 @@ set(ct_models_target_include_dirs
## define placeholder for ct model libraries
-set(CT_MODELS_TARGETS "")
+set(CT_MODELS_LIBRARIES "")
set(IP_CODEGEN_OUTPUT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/InvertedPendulum/codegen")
set(HYA_CODEGEN_OUTPUT_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include/ct/models/HyA/codegen")
@@ -42,20 +42,18 @@ if(CPPADCG)
add_executable(HyQLinearizationCodegen src/HyQ/codegen/HyQLinearizationCodegen.cpp)
target_include_directories(HyQLinearizationCodegen PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyQLinearizationCodegen ct_rbd)
+ list(APPEND CT_MODELS_BINARIES HyQLinearizationCodegen)
endif()
if (BUILD_HYQ_FULL)
- if (NOT USE_CLANG)
- MESSAGE(WARNING "HyQ Linearization should be build with CLANG")
- endif()
add_library(HyQWithContactModelLinearizedForward include/ct/models/HyQ/codegen/HyQWithContactModelLinearizedForward.cpp)
target_link_libraries(HyQWithContactModelLinearizedForward ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQWithContactModelLinearizedForward)
+ list(APPEND CT_MODELS_LIBRARIES HyQWithContactModelLinearizedForward)
## Forward Dynamics Forward Zero
add_library(HyQForwardZero include/ct/models/HyQ/codegen/HyQForwardZero.cpp)
target_link_libraries(HyQForwardZero ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQForwardZero)
+ list(APPEND CT_MODELS_LIBRARIES HyQForwardZero)
endif(BUILD_HYQ_FULL)
if(BUILD_HYQ_LINEARIZATION_TIMINGS)
@@ -66,33 +64,33 @@ if(BUILD_HYQ_LINEARIZATION_TIMINGS)
## Forward Dynamics
add_library(HyQWithContactModelLinearizedReverse include/ct/models/HyQ/codegen/HyQWithContactModelLinearizedReverse.cpp)
target_link_libraries(HyQWithContactModelLinearizedReverse ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQWithContactModelLinearizedReverse)
+ list(APPEND CT_MODELS_LIBRARIES HyQWithContactModelLinearizedReverse)
add_library(HyQBareModelLinearizedForward include/ct/models/HyQ/codegen/HyQBareModelLinearizedForward.cpp)
target_link_libraries(HyQBareModelLinearizedForward ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQBareModelLinearizedForward)
+ list(APPEND CT_MODELS_LIBRARIES HyQBareModelLinearizedForward)
add_library(HyQBareModelLinearizedReverse include/ct/models/HyQ/codegen/HyQBareModelLinearizedReverse.cpp)
target_link_libraries(HyQBareModelLinearizedReverse ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQBareModelLinearizedReverse)
+ list(APPEND CT_MODELS_LIBRARIES HyQBareModelLinearizedReverse)
## Inverse Dynamics
add_library(HyQJacInverseDynamicsForward include/ct/models/HyQ/codegen/HyQInverseDynJacForward.cpp)
target_link_libraries(HyQJacInverseDynamicsForward ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQJacInverseDynamicsForward)
+ list(APPEND CT_MODELS_LIBRARIES HyQJacInverseDynamicsForward)
add_library(HyQJacInverseDynamicsReverse include/ct/models/HyQ/codegen/HyQInverseDynJacReverse.cpp)
target_link_libraries(HyQJacInverseDynamicsReverse ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQJacInverseDynamicsReverse)
+ list(APPEND CT_MODELS_LIBRARIES HyQJacInverseDynamicsReverse)
## ForwardKinematics
add_library(HyQJacForwardKinForward include/ct/models/HyQ/codegen/HyQForwardKinJacForward.cpp)
target_link_libraries(HyQJacForwardKinForward ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQJacForwardKinForward)
+ list(APPEND CT_MODELS_LIBRARIES HyQJacForwardKinForward)
add_library(HyQJacForwardKinReverse include/ct/models/HyQ/codegen/HyQForwardKinJacReverse.cpp)
target_link_libraries(HyQJacForwardKinReverse ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyQJacForwardKinReverse)
+ list(APPEND CT_MODELS_LIBRARIES HyQJacForwardKinReverse)
add_executable(HyQcompareForwardReverseFD src/HyQ/codegen/compareForwardReverseFD.cpp)
target_link_libraries(HyQcompareForwardReverseFD
@@ -101,25 +99,25 @@ if(BUILD_HYQ_LINEARIZATION_TIMINGS)
HyQBareModelLinearizedForward
HyQBareModelLinearizedReverse
ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseFD)
+ list(APPEND CT_MODELS_BINARIES HyQcompareForwardReverseFD)
add_executable(HyQcompareForwardReverseID src/HyQ/codegen/compareForwardReverseID.cpp)
target_link_libraries(HyQcompareForwardReverseID
HyQJacInverseDynamicsForward
HyQJacInverseDynamicsReverse
ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseID)
+ list(APPEND CT_MODELS_BINARIES HyQcompareForwardReverseID)
add_executable(HyQcompareForwardReverseKin src/HyQ/codegen/compareForwardReverseKin.cpp)
target_link_libraries(HyQcompareForwardReverseKin
HyQJacForwardKinForward
HyQJacForwardKinReverse
ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQcompareForwardReverseKin)
+ list(APPEND CT_MODELS_BINARIES HyQcompareForwardReverseKin)
add_executable(HyQcompareForwardZero src/HyQ/codegen/compareForwardZero.cpp)
target_link_libraries(HyQcompareForwardZero HyQForwardZero ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyQcompareForwardZero)
+ list(APPEND CT_MODELS_BINARIES HyQcompareForwardZero)
endif(BUILD_HYQ_LINEARIZATION_TIMINGS)
########## Inverted Pendulum #########
@@ -127,13 +125,13 @@ if(CPPADCG)
add_executable(InvertedPendulumWithActuatorCodeGen src/InvertedPendulum/codegen/InvertedPendulumWithActuatorCodeGen.cpp)
target_include_directories(InvertedPendulumWithActuatorCodeGen PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(InvertedPendulumWithActuatorCodeGen ct_rbd)
- list(APPEND CT_MODELS_TARGETS InvertedPendulumWithActuatorCodeGen)
+ list(APPEND CT_MODELS_BINARIES InvertedPendulumWithActuatorCodeGen)
endif()
add_library(InvertedPendulumActDynLinearizedForward include/ct/models/InvertedPendulum/codegen/InvertedPendulumActDynLinearizedForward.cpp)
target_include_directories(InvertedPendulumActDynLinearizedForward PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(InvertedPendulumActDynLinearizedForward ct_rbd)
-list(APPEND CT_MODELS_TARGETS InvertedPendulumActDynLinearizedForward)
+list(APPEND CT_MODELS_LIBRARIES InvertedPendulumActDynLinearizedForward)
################ HyA #################
@@ -141,29 +139,29 @@ if(CPPADCG)
add_executable(HyALinearizationCodegen src/HyA/codegen/HyALinearizationCodeGen.cpp)
target_include_directories(HyALinearizationCodegen PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyALinearizationCodegen ct_rbd)
- list(APPEND CT_MODELS_TARGETS HyALinearizationCodegen)
+ list(APPEND CT_MODELS_BINARIES HyALinearizationCodegen)
endif()
add_library(HyALinearizedForward include/ct/models/HyA/codegen/HyALinearizedForward.cpp)
target_include_directories(HyALinearizedForward PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyALinearizedForward ct_rbd )
-list(APPEND CT_MODELS_TARGETS HyALinearizedForward)
+list(APPEND CT_MODELS_LIBRARIES HyALinearizedForward)
add_library(HyAJacInverseDynamicsReverse include/ct/models/HyA/codegen/HyAInverseDynJacReverse.cpp)
target_include_directories(HyAJacInverseDynamicsReverse PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyAJacInverseDynamicsReverse ct_rbd)
-list(APPEND CT_MODELS_TARGETS HyAJacInverseDynamicsReverse)
+list(APPEND CT_MODELS_LIBRARIES HyAJacInverseDynamicsReverse)
if(BUILD_HYA_LINEARIZATION_TIMINGS)
add_library(HyALinearizedReverse include/ct/models/HyA/codegen/HyALinearizedReverse.cpp)
target_include_directories(HyALinearizedReverse PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyALinearizedReverse ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyALinearizedReverse)
+ list(APPEND CT_MODELS_LIBRARIES HyALinearizedReverse)
add_library(HyAJacInverseDynamicsForward include/ct/models/HyA/codegen/HyAInverseDynJacForward.cpp)
target_include_directories(HyAJacInverseDynamicsForward PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(HyAJacInverseDynamicsForward ct_rbd )
- list(APPEND CT_MODELS_TARGETS HyAJacInverseDynamicsForward)
+ list(APPEND CT_MODELS_LIBRARIES HyAJacInverseDynamicsForward)
add_executable(HyAcompareForwardReverse src/HyA/codegen/compareForwardReverse.cpp)
target_include_directories(HyAcompareForwardReverse PUBLIC ${ct_models_target_include_dirs})
@@ -174,7 +172,7 @@ if(BUILD_HYA_LINEARIZATION_TIMINGS)
HyAJacInverseDynamicsReverse
ct_rbd
)
- list(APPEND CT_MODELS_TARGETS HyAcompareForwardReverse)
+ list(APPEND CT_MODELS_BINARIES HyAcompareForwardReverse)
endif(BUILD_HYA_LINEARIZATION_TIMINGS)
@@ -187,7 +185,7 @@ add_library(quadrotorDynamics
)
target_include_directories(quadrotorDynamics PUBLIC ${ct_models_target_include_dirs})
target_link_libraries(quadrotorDynamics ct_core)
-list(APPEND CT_MODELS_TARGETS quadrotorDynamics)
+list(APPEND CT_MODELS_LIBRARIES quadrotorDynamics)
## Inverse Kinematics
@@ -196,13 +194,13 @@ add_library(hya_ik src/HyA/transform6d.cpp)
target_include_directories(hya_ik PUBLIC ${ct_models_target_include_dirs})
set_target_properties(hya_ik PROPERTIES COMPILE_FLAGS "-std=c++98 -fPIC -DIKFAST_NAMESPACE=hya_ik -DIKFAST_NO_MAIN -Wno-unused-variable")
target_link_libraries(hya_ik ct_rbd)
-list(APPEND CT_MODELS_TARGETS hya_ik)
+list(APPEND CT_MODELS_LIBRARIES hya_ik)
add_library(irb4600_ik src/Irb4600/transform6d.cpp)
target_include_directories(irb4600_ik PUBLIC ${ct_models_target_include_dirs})
set_target_properties(irb4600_ik PROPERTIES COMPILE_FLAGS "-std=c++98 -fPIC -DIKFAST_NAMESPACE=irb4600_ik -DIKFAST_NO_MAIN -Wno-unused-variable")
target_link_libraries(irb4600_ik ct_rbd)
-list(APPEND CT_MODELS_TARGETS irb4600_ik)
+list(APPEND CT_MODELS_LIBRARIES irb4600_ik)
## convenience library for passing on includes
@@ -210,9 +208,9 @@ add_library(ct_models INTERFACE)
target_include_directories(ct_models INTERFACE ${ct_models_target_include_dirs})
target_link_libraries(ct_models INTERFACE
ct_rbd
- ${CT_MODELS_TARGETS}
+ ${CT_MODELS_LIBRARIES}
)
-list(APPEND CT_MODELS_TARGETS ct_models)
+list(APPEND CT_MODELS_LIBRARIES ct_models)
############
@@ -249,7 +247,7 @@ install(FILES "cmake/ct_modelsConfig.cmake" DESTINATION "share/ct_models/cmake")
## install library and targets
install(
- TARGETS ${CT_MODELS_TARGETS}
+ TARGETS ${CT_MODELS_LIBRARIES} ${CT_MODELS_BINARIES}
EXPORT ct_models_export
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
diff --git a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAnalytical.h b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAnalytical.h
index eb73afdf4..c01821b44 100644
--- a/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAnalytical.h
+++ b/ct_optcon/include/ct/optcon/constraint/ConstraintContainerAnalytical.h
@@ -5,7 +5,7 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
#pragma once
-#include
+#include
#include "LinearConstraintContainer.h"
#include "term/ConstraintBase.h"
diff --git a/ct_optcon/include/ct/optcon/constraint/term/BoxConstraintBase.h b/ct_optcon/include/ct/optcon/constraint/term/BoxConstraintBase.h
index af916b009..ffbbbfd20 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/BoxConstraintBase.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/BoxConstraintBase.h
@@ -67,10 +67,12 @@ class BoxConstraintBase : public ConstraintBase
virtual VectorXs evaluate(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override = 0;
+#ifdef CPPADCG
virtual Eigen::Matrix evaluateCppadCg(
const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override = 0;
+#endif
virtual MatrixXs jacobianState(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override = 0;
diff --git a/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase-impl.h b/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase-impl.h
index 612d7eab1..9d85769da 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase-impl.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase-impl.h
@@ -24,6 +24,7 @@ ConstraintBase::~ConstraintBase()
{
}
+#ifdef CPPADCG
template
Eigen::Matrix ConstraintBase::evaluateCppadCg(
const core::StateVector& x,
@@ -32,6 +33,7 @@ Eigen::Matrix ConstraintBase
typename ConstraintBase::MatrixXs
diff --git a/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase.h b/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase.h
index a6550e835..cfd892f30 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/ConstraintBase.h
@@ -79,11 +79,12 @@ class ConstraintBase
*
* @return The constraint violation
*/
+#ifdef CPPADCG
virtual Eigen::Matrix evaluateCppadCg(
const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t);
-
+#endif
/**
* @brief Returns the number of constraints
diff --git a/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint-impl.h b/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint-impl.h
index c23d850ad..d3464f9eb 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint-impl.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint-impl.h
@@ -51,6 +51,7 @@ Eigen::Matrix ControlInputConstraintsparsity_J_ * u;
}
+#ifdef CPPADCG
template
Eigen::Matrix
ControlInputConstraint::evaluateCppadCg(
@@ -60,6 +61,7 @@ ControlInputConstraint::evaluateCppadCg(
{
return this->sparsity_J_.template cast() * u;
}
+#endif
template
typename ControlInputConstraint::MatrixXs
diff --git a/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint.h b/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint.h
index d2417dbfe..a1e2ef3c2 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/ControlInputConstraint.h
@@ -59,10 +59,12 @@ class ControlInputConstraint : public BoxConstraintBase evaluateCppadCg(
const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
virtual MatrixXs jacobianState(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override;
diff --git a/ct_optcon/include/ct/optcon/constraint/term/StateConstraint-impl.h b/ct_optcon/include/ct/optcon/constraint/term/StateConstraint-impl.h
index 6842d6f23..651d18cd4 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/StateConstraint-impl.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/StateConstraint-impl.h
@@ -48,6 +48,7 @@ StateConstraint::evaluate(const state_vector_t&
return this->sparsity_J_ * x;
}
+#ifdef CPPADCG
template
Eigen::Matrix StateConstraint::evaluateCppadCg(
const core::StateVector& x,
@@ -56,6 +57,7 @@ Eigen::Matrix StateConstraintsparsity_J_.template cast() * x;
}
+#endif
template
typename StateConstraint::MatrixXs
diff --git a/ct_optcon/include/ct/optcon/constraint/term/StateConstraint.h b/ct_optcon/include/ct/optcon/constraint/term/StateConstraint.h
index e4cb92c0e..0f0a8ed6e 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/StateConstraint.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/StateConstraint.h
@@ -60,10 +60,12 @@ class StateConstraint : public BoxConstraintBase evaluateCppadCg(
const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
virtual MatrixXs jacobianState(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override;
diff --git a/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint-impl.h b/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint-impl.h
index 9dd73d8e3..56b3dabee 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint-impl.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint-impl.h
@@ -51,6 +51,7 @@ TerminalConstraint::evaluate(const state_vector_
return x - xF_;
}
+#ifdef CPPADCG
template
Eigen::Matrix
TerminalConstraint::evaluateCppadCg(
@@ -60,6 +61,7 @@ TerminalConstraint::evaluateCppadCg(
{
return x - xF_.template cast();
}
+#endif
template
typename TerminalConstraint::MatrixXs
diff --git a/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint.h b/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint.h
index 80a3bafe6..c4f598f4e 100644
--- a/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint.h
+++ b/ct_optcon/include/ct/optcon/constraint/term/TerminalConstraint.h
@@ -49,10 +49,12 @@ class TerminalConstraint : public ConstraintBase
virtual VectorXs evaluate(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override;
+#ifdef CPPADCG
virtual Eigen::Matrix evaluateCppadCg(
const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
virtual MatrixXs jacobianState(const state_vector_t& x, const control_vector_t& u, const SCALAR t) override;
diff --git a/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic-impl.hpp
index 3a43977ea..3b79d0241 100644
--- a/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic-impl.hpp
@@ -41,6 +41,7 @@ CostFunctionQuadratic::~CostFunctionQuadratic()
{
}
+#ifdef CPPADCG
template
void CostFunctionQuadratic::addIntermediateADTerm(
std::shared_ptr> term,
@@ -49,7 +50,6 @@ void CostFunctionQuadratic::addIntermediateADTer
throw std::runtime_error("not implemented");
}
-
template
void CostFunctionQuadratic::addFinalADTerm(
std::shared_ptr> term,
@@ -57,6 +57,7 @@ void CostFunctionQuadratic::addFinalADTerm(
{
throw std::runtime_error("not implemented");
}
+#endif
template
void CostFunctionQuadratic::loadFromConfigFile(const std::string& filename,
diff --git a/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic.hpp b/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic.hpp
index 476401816..99528155c 100644
--- a/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/CostFunctionQuadratic.hpp
@@ -71,10 +71,6 @@ class CostFunctionQuadratic : public CostFunction> term,
bool verbose = false);
- virtual void addIntermediateADTerm(
- std::shared_ptr> term,
- bool verbose = false);
-
/**
* \brief Adds a final term
* @param term final term
@@ -83,8 +79,15 @@ class CostFunctionQuadratic : public CostFunction> term, bool verbose = false);
+
+#ifdef CPPADCG
+ virtual void addIntermediateADTerm(
+ std::shared_ptr> term,
+ bool verbose = false);
+
virtual void addFinalADTerm(std::shared_ptr> term,
bool verbose = false);
+#endif
/**
* \brief Loads cost function from config file
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermBase-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermBase-impl.hpp
index e9e2e9cfb..aa9f83bae 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermBase-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermBase-impl.hpp
@@ -37,7 +37,7 @@ SCALAR_EVAL TermBase::eval(
return computeActivation(t) * evaluate(x, u, t);
}
-
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermBase::evaluateCppadCg(
const core::StateVector& x,
@@ -46,6 +46,7 @@ ct::core::ADCGScalar TermBase::eval
{
throw std::runtime_error("The cost function term term " + name_ + " does not implement evaluate CppadCg.");
}
+#endif
template
bool TermBase::isActiveAtTime(SCALAR_EVAL t)
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermBase.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermBase.hpp
index e28132552..bc10273bd 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermBase.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermBase.hpp
@@ -79,6 +79,7 @@ class TermBase
const Eigen::Matrix& u,
const SCALAR& t) = 0;
+#ifdef CPPADCG
/**
* @brief The evaluate method used for jit compilation in CostfunctionAD
*
@@ -91,6 +92,7 @@ class TermBase
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t);
+#endif
/**
* @brief Gets called by the analytical costfunction. Adds time
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermLinear-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermLinear-impl.hpp
index e6681e16b..dfd971d5b 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermLinear-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermLinear-impl.hpp
@@ -48,6 +48,7 @@ SCALAR TermLinear::evaluate(const E
return evalLocal(x, u, t);
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermLinear::evaluateCppadCg(
const core::StateVector& x,
@@ -56,6 +57,7 @@ ct::core::ADCGScalar TermLinear::ev
{
return evalLocal(x, u, t);
}
+#endif
template
core::StateVector TermLinear::stateDerivative(
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermLinear.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermLinear.hpp
index 2889d7222..4403d7dec 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermLinear.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermLinear.hpp
@@ -45,9 +45,11 @@ class TermLinear : public TermBase
const Eigen::Matrix& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
core::StateVector stateDerivative(const core::StateVector& x,
const core::ControlVector& u,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermMixed-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermMixed-impl.hpp
index 0b090f863..8d1df09ff 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermMixed-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermMixed-impl.hpp
@@ -73,6 +73,7 @@ SCALAR TermMixed::evaluate(const Ei
return evalLocal(x, u, t);
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermMixed::evaluateCppadCg(
const core::StateVector& x,
@@ -81,6 +82,7 @@ ct::core::ADCGScalar TermMixed::eva
{
return evalLocal(x, u, t);
}
+#endif
template
ct::core::StateVector TermMixed::stateDerivative(
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermMixed.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermMixed.hpp
index 6fdd8fbec..d9b3bd597 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermMixed.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermMixed.hpp
@@ -53,9 +53,11 @@ class TermMixed : public TermBase
const Eigen::Matrix& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
core::StateVector stateDerivative(const core::StateVector& x,
const core::ControlVector& u,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult-impl.hpp
index cc47be986..21f347fb4 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult-impl.hpp
@@ -85,6 +85,7 @@ SCALAR TermQuadMult::evaluate(const
return evalLocal(x, u, t);
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermQuadMult::evaluateCppadCg(
const core::StateVector& x,
@@ -93,6 +94,7 @@ ct::core::ADCGScalar TermQuadMult::
{
return evalLocal(x, u, t);
}
+#endif
template
core::StateVector TermQuadMult::stateDerivative(
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp
index 9bb731763..b884402ed 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadMult.hpp
@@ -57,9 +57,11 @@ class TermQuadMult : public TermBase& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
core::StateVector stateDerivative(const core::StateVector& x,
const core::ControlVector& u,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic-impl.hpp
index 443618eac..827d08847 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic-impl.hpp
@@ -126,6 +126,7 @@ SCALAR TermQuadratic::evaluate(
return evalLocal(x, u, t);
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermQuadratic::evaluateCppadCg(
const core::StateVector& x,
@@ -134,7 +135,7 @@ ct::core::ADCGScalar TermQuadratic:
{
return evalLocal(x, u, t);
}
-
+#endif
template
ct::core::StateVector
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic.hpp
index 6b79feeee..526b3287d 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermQuadratic.hpp
@@ -66,9 +66,11 @@ class TermQuadratic : public TermBase& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
core::StateVector stateDerivative(const core::StateVector& x,
const core::ControlVector& u,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs-impl.hpp
index d429e5dd8..a78b9e6ec 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs-impl.hpp
@@ -52,6 +52,7 @@ SCALAR TermSmoothAbs::evaluate(
return evalLocal(x, u, t);
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermSmoothAbs::evaluateCppadCg(
const core::StateVector& x,
@@ -60,6 +61,7 @@ ct::core::ADCGScalar TermSmoothAbs:
{
return evalLocal(x, u, t);
}
+#endif
template
core::StateVector TermSmoothAbs::stateDerivative(
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs.hpp
index a804064b6..c93809641 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermSmoothAbs.hpp
@@ -50,9 +50,11 @@ class TermSmoothAbs : public TermBase& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
core::StateVector stateDerivative(const core::StateVector& x,
const core::ControlVector& u,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier-impl.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier-impl.hpp
index 0dc7f584d..8728a9c70 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier-impl.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier-impl.hpp
@@ -63,6 +63,7 @@ SCALAR TermStateBarrier::evaluate(
return c;
}
+#ifdef CPPADCG
template
ct::core::ADCGScalar TermStateBarrier::evaluateCppadCg(
const core::StateVector& x,
@@ -74,6 +75,7 @@ ct::core::ADCGScalar TermStateBarrier
void TermStateBarrier::loadConfigFile(const std::string& filename,
diff --git a/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier.hpp b/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier.hpp
index cea4c85da..fac128b8c 100644
--- a/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier.hpp
+++ b/ct_optcon/include/ct/optcon/costfunction/term/TermStateBarrier.hpp
@@ -50,9 +50,11 @@ class TermStateBarrier : public TermBase& u,
const SCALAR& t) override;
+#ifdef CPPADCG
virtual ct::core::ADCGScalar evaluateCppadCg(const core::StateVector& x,
const core::ControlVector& u,
ct::core::ADCGScalar t) override;
+#endif
//! load the term from config file, where the bounds are stored as matrices
virtual void loadConfigFile(const std::string& filename,
diff --git a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp
index be976d3d1..9ec54b6a4 100644
--- a/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp
+++ b/ct_optcon/include/ct/optcon/nloc/NLOCBackendBase-impl.hpp
@@ -69,12 +69,18 @@ NLOCBackendBase::NLOCB
// if the optimal problem has constraints, change
if (systemInterface_->getOptConProblem().getInputBoxConstraints())
+ {
changeInputBoxConstraints(systemInterface_->getOptConProblem().getInputBoxConstraints());
+ }
if (systemInterface_->getOptConProblem().getStateBoxConstraints())
+ {
changeStateBoxConstraints(systemInterface_->getOptConProblem().getStateBoxConstraints());
+ }
if (systemInterface_->getOptConProblem().getGeneralConstraints())
+ {
changeGeneralConstraints(systemInterface_->getOptConProblem().getGeneralConstraints());
+ }
}
template
@@ -287,8 +293,6 @@ void NLOCBackendBase::
computeBoxConstraintErrorOfTrajectory(settings_.nThreads, x_, u_ff_, e_box_norm_);
setInputBoxConstraintsForLQOCProblem();
- lqocSolver_->configureInputBoxConstraints(lqocProblem_);
- lqocSolver_->initializeAndAllocate(); // todo - this is not nice
}
template
@@ -311,8 +315,6 @@ void NLOCBackendBase::
computeBoxConstraintErrorOfTrajectory(settings_.nThreads, x_, u_ff_, e_box_norm_);
setStateBoxConstraintsForLQOCProblem();
- lqocSolver_->configureStateBoxConstraints(lqocProblem_);
- lqocSolver_->initializeAndAllocate(); // todo - this is not nice
}
@@ -352,8 +354,6 @@ void NLOCBackendBase::
lqocProblem_->d_ub_[K_].resize(lqocProblem_->ng_[K_], 1);
lqocSolver_->setProblem(lqocProblem_);
- lqocSolver_->configureGeneralConstraints(lqocProblem_);
- lqocSolver_->initializeAndAllocate();
// TODO can we do this multi-threaded?
if (iteration_ > 0 && (settings_.lineSearchSettings.type != LineSearchSettings::TYPE::NONE))
@@ -803,7 +803,6 @@ void NLOCBackendBase::
p.ng_[k] = generalConstraints_[threadId]->getIntermediateConstraintsCount();
if (p.ng_[k] > 0)
{
- p.hasGenConstraints_ = true;
p.C_[k] = generalConstraints_[threadId]->jacobianStateIntermediate();
p.D_[k] = generalConstraints_[threadId]->jacobianInputIntermediate();
@@ -835,7 +834,6 @@ void NLOCBackendBase::
p.ng_[K_] = generalConstraints_[settings_.nThreads]->getTerminalConstraintsCount();
if (p.ng_[K_] > 0)
{
- p.hasGenConstraints_ = true;
p.C_[K_] = generalConstraints_[settings_.nThreads]->jacobianStateTerminal();
p.D_[K_] = generalConstraints_[settings_.nThreads]->jacobianInputTerminal();
@@ -1284,7 +1282,10 @@ void NLOCBackendBase::
lqpCounter_++;
// if solver is HPIPM, there's nothing to prepare
- if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::HPIPM_SOLVER) {}
+ if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::HPIPM_SOLVER)
+ {
+ // do nothing
+ }
// if solver is GNRiccati - we iterate backward up to the first stage
else if (settings_.lqocp_solver == Settings_t::LQOCP_SOLVER::GNRICCATI_SOLVER)
{
@@ -1328,28 +1329,6 @@ void NLOCBackendBase::
{
lqpCounter_++;
- if (lqocProblem_->isInputBoxConstrained())
- {
- if (settings_.debugPrint)
- std::cout << "LQ Problem has input box constraints. Configuring box constraints now. " << std::endl;
-
- lqocSolver_->configureInputBoxConstraints(lqocProblem_);
- }
- if (lqocProblem_->isStateBoxConstrained())
- {
- if (settings_.debugPrint)
- std::cout << "LQ Problem has state box constraints. Configuring box constraints now. " << std::endl;
-
- lqocSolver_->configureStateBoxConstraints(lqocProblem_);
- }
- if (lqocProblem_->isGeneralConstrained())
- {
- if (settings_.debugPrint)
- std::cout << "LQ Problem has general constraints. Configuring general constraints now. " << std::endl;
-
- lqocSolver_->configureGeneralConstraints(lqocProblem_);
- }
-
lqocSolver_->setProblem(lqocProblem_);
lqocSolver_->solve();
@@ -1633,7 +1612,7 @@ std::vector&
NLOCBackendBase::getStateBoxConstraintsInstances()
{
- return inputBoxConstraints_;
+ return stateBoxConstraints_;
}
diff --git a/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp b/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp
index 00266066b..49d0c8460 100644
--- a/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp
+++ b/ct_optcon/include/ct/optcon/problem/LQOCProblem-impl.hpp
@@ -10,8 +10,7 @@ namespace optcon {
template
-LQOCProblem::LQOCProblem(int N)
- : hasInputBoxConstraints_(false), hasStateBoxConstraints_(false), hasGenConstraints_(false)
+LQOCProblem::LQOCProblem(int N) : nbu_(N, 0), nbx_(N + 1, 0)
{
changeNumStages(N);
}
@@ -21,23 +20,31 @@ bool LQOCProblem::isConstrained() const
{
return (isInputBoxConstrained() | isStateBoxConstrained() | isGeneralConstrained());
}
-
template
bool LQOCProblem::isInputBoxConstrained() const
{
- return hasInputBoxConstraints_;
+ if (std::accumulate(nbu_.begin(), nbu_.end(), 0) > 0)
+ return true;
+
+ return false;
}
template
bool LQOCProblem::isStateBoxConstrained() const
{
- return hasStateBoxConstraints_;
+ if (std::accumulate(nbx_.begin(), nbx_.end(), 0) > 0)
+ return true;
+
+ return false;
}
template
bool LQOCProblem::isGeneralConstrained() const
{
- return hasGenConstraints_;
+ if (std::accumulate(ng_.begin(), ng_.end(), 0) > 0)
+ return true;
+
+ return false;
}
template
@@ -115,10 +122,6 @@ void LQOCProblem::setZero(const int& nGenConstr)
D_[i].resize(nGenConstr, CONTROL_DIM);
D_[i].setZero();
}
-
- hasInputBoxConstraints_ = false;
- hasStateBoxConstraints_ = false;
- hasGenConstraints_ = false;
}
@@ -152,7 +155,6 @@ void LQOCProblem::setInputBoxConstraint(const in
u_lb_[index](i) = u_lb(i) - u_nom_abs(sp(i)); // substract the corresponding entry in nom-control
u_ub_[index](i) = u_ub(i) - u_nom_abs(sp(i)); // substract the corresponding entry in nom-control
}
- hasInputBoxConstraints_ = true;
}
template
@@ -197,8 +199,6 @@ void LQOCProblem::setIntermediateStateBoxConstra
x_lb_[index](i) = x_lb(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state
x_ub_[index](i) = x_ub(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state
}
-
- hasStateBoxConstraints_ = true;
}
template
@@ -241,7 +241,6 @@ void LQOCProblem::setTerminalBoxConstraints(cons
x_lb_[K_](i) = x_lb(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state
x_ub_[K_](i) = x_ub(i) - x_nom_abs(sp(i)); // substract the corresponding entry in nom-state
}
- hasStateBoxConstraints_ = true;
}
}
@@ -255,8 +254,6 @@ void LQOCProblem::setGeneralConstraints(const co
d_ub_.setConstant(d_ub);
C_.setConstant(C);
D_.setConstant(D);
-
- hasGenConstraints_ = true;
}
@@ -269,8 +266,10 @@ void LQOCProblem::setFromTimeInvariantLinearQuad
{
setZero();
- core::StateVector x0; x0.setZero(); // by definition
- core::ControlVector u0; u0.setZero(); // by definition
+ core::StateVector x0;
+ x0.setZero(); // by definition
+ core::ControlVector u0;
+ u0.setZero(); // by definition
core::StateMatrix A;
core::StateControlMatrix B;
@@ -295,10 +294,6 @@ void LQOCProblem::setFromTimeInvariantLinearQuad
// final stage
Q_[K_] = costFunction.stateSecondDerivativeTerminal();
qv_[K_] = costFunction.stateDerivativeTerminal();
-
- hasInputBoxConstraints_ = false;
- hasStateBoxConstraints_ = false;
- hasGenConstraints_ = false;
}
} // namespace optcon
diff --git a/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp b/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp
index c9978d793..631b8d79d 100644
--- a/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp
+++ b/ct_optcon/include/ct/optcon/problem/LQOCProblem.hpp
@@ -251,15 +251,9 @@ class LQOCProblem
//! number of general inequality constraints
std::vector ng_;
- //! bool indicating if the optimization problem is box-constrained
- bool hasInputBoxConstraints_;
- bool hasStateBoxConstraints_;
-
- //! bool indicating if the optimization problem hs general inequality constraints
- bool hasGenConstraints_;
private:
- //! the number of discrete time steps in the LOCP, including terminal stage
+ //! the number of discrete time steps in the LOCP, not including terminal stage
int K_;
};
diff --git a/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h b/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h
index ebbc02680..829644c02 100644
--- a/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h
+++ b/ct_optcon/include/ct/optcon/problem/OptConProblemBase-impl.h
@@ -8,17 +8,6 @@ Licensed under the BSD-2 license (see LICENSE file in main directory)
namespace ct {
namespace optcon {
-
-template
-OptConProblemBase::OptConProblemBase()
-{
-}
-
template > ConstraintPtr_t;
typedef typename SYSTEM_T::time_t time_t;
- OptConProblemBase();
+ OptConProblemBase() = default;
/*!
* @brief Construct a simple unconstrained Optimal Control Problem
diff --git a/ct_optcon/include/ct/optcon/solver/OptConSolver.h b/ct_optcon/include/ct/optcon/solver/OptConSolver.h
index 9db9252f3..ac11af585 100644
--- a/ct_optcon/include/ct/optcon/solver/OptConSolver.h
+++ b/ct_optcon/include/ct/optcon/solver/OptConSolver.h
@@ -318,7 +318,7 @@ class OptConSolver
throw std::runtime_error("getGeneralConstraintsInstances not supported.");
}
-
+#ifdef CPPADCG
/**
* @brief Generates and compiles AD source code which can be used in
* the solver. This method can be called just before solving the
@@ -334,6 +334,7 @@ class OptConSolver
{
throw std::runtime_error("Generate and compile code not implemented for this solver");
}
+#endif
/**
* @brief Generates source AD source code which can be used in the
diff --git a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp
index b8b84b8b0..0677fbbe0 100644
--- a/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp
+++ b/ct_optcon/include/ct/optcon/solver/lqp/HPIPMInterface-impl.hpp
@@ -11,16 +11,11 @@ namespace ct {
namespace optcon {
template
-HPIPMInterface::HPIPMInterface(const int N, const int nbu, const int nbx, const int ng)
- : N_(-1), nbu_(1, nbu), nbx_(1, nbx), ng_(1, ng), settings_(NLOptConSettings())
+HPIPMInterface::HPIPMInterface() : N_(-1), settings_(NLOptConSettings())
{
hb0_.setZero();
hr0_.setZero();
- // by default, set number of box and general constraints to zero
- if (N > 0)
- setSolverDimensions(N, nbu, nbx, ng);
-
configure(settings_);
}
@@ -30,23 +25,19 @@ HPIPMInterface::~HPIPMInterface()
// todo is there memory that needs to be freed?
}
-template
-void HPIPMInterface::setSolverDimensions(const int N,
- const int nbu,
- const int nbx,
- const int ng)
-{
- nbu_.resize(N + 1, nbu); // todo this is bad design, is there no other way to propagate the number of constraints?
- nbx_.resize(N + 1, nbx); // todo this is bad design, is there no other way to propagate the number of constraints?
- ng_.resize(N + 1, ng); // todo this is bad design, is there no other way to propagate the number of constraints?
-
- changeNumberOfStages(N);
- initializeAndAllocate();
-}
-
template
void HPIPMInterface::initializeAndAllocate()
{
+ if (settings_.lqoc_solver_settings.lqoc_debug_print)
+ {
+ std::cout << "HPIPM allocating memory for QP with time horizon: " << N_ << std::endl;
+ for (int i = 0; i < N_ + 1; i++)
+ {
+ std::cout << "HPIPM stage " << i << ": (nx, nu, nbu, nbx, ng) : (" << nx_[i] << ", " << nu_[i] << ", "
+ << nbu_[i] << ", " << nbx_[i] << ", " << ng_[i] << ")" << std::endl;
+ }
+ }
+
// allocate ocp dimensions
dim_size_ = d_ocp_qp_dim_memsize(N_);
dim_mem_ = malloc(dim_size_);
@@ -84,12 +75,6 @@ void HPIPMInterface::initializeAndAllocate()
if (settings_.lqoc_solver_settings.lqoc_debug_print)
{
- std::cout << "HPIPM allocating memory for QP with time horizon: " << N_ << std::endl;
- for (int i = 0; i < N_ + 1; i++)
- {
- std::cout << "HPIPM stage " << i << ": (nx, nu, nbu, nbx, ng) : (" << nx_[i] << ", " << nu_[i] << ", "
- << nbu_[i] << ", " << nbx_[i] << ", " << ng_[i] << ")" << std::endl;
- }
std::cout << "HPIPM qp_size: " << qp_size << std::endl;
std::cout << "HPIPM qp_sol_size: " << qp_sol_size << std::endl;
std::cout << "HPIPM ipm_arg_size: " << ipm_arg_size << std::endl;
@@ -323,30 +308,20 @@ void HPIPMInterface::setProblemImpl(
std::shared_ptr> lqocProblem)
{
// check if the number of stages N changed and adapt problem dimensions
- bool nStagesChanged = changeNumberOfStages(lqocProblem->getNumberOfStages());
+ bool dimsChanged = changeProblemSize(lqocProblem);
// WARNING: the allocation should in practice not have to happen during the loop.
// If possible, prefer receding horizon MPC problems.
// If the number of stages has changed, however, the problem needs to be re-built:
- if (nStagesChanged)
- {
- // update constraint configuration in case the horizon length has changed.
- if (lqocProblem->isInputBoxConstrained())
- configureInputBoxConstraints(lqocProblem);
-
- if (lqocProblem->isStateBoxConstrained())
- configureStateBoxConstraints(lqocProblem);
-
- if (lqocProblem->isGeneralConstrained())
- configureGeneralConstraints(lqocProblem);
- }
// setup unconstrained part of problem
setupCostAndDynamics(lqocProblem->A_, lqocProblem->B_, lqocProblem->b_, lqocProblem->P_, lqocProblem->qv_,
lqocProblem->Q_, lqocProblem->rv_, lqocProblem->R_);
- if (nStagesChanged)
+ if (dimsChanged)
+ {
initializeAndAllocate();
+ }
else
{
// we need to call the setters to transform our data into HPIPM interal structures
@@ -359,59 +334,116 @@ void HPIPMInterface::setProblemImpl(
template
-void HPIPMInterface::configureInputBoxConstraints(
+bool HPIPMInterface::configureInputBoxConstraints(
std::shared_ptr