17 #ifndef OPTIMIZATION__OPTIMIZATION_PROBLEM_HPP_
18 #define OPTIMIZATION__OPTIMIZATION_PROBLEM_HPP_
37 namespace optimization
45 template<
typename Derived,
typename DomainValueT,
int NumJacobianColsT,
int NumVarsT>
49 static constexpr
auto NumJacobianCols = NumJacobianColsT;
50 static constexpr
auto NumVars = NumVarsT;
53 using Jacobian = Eigen::Matrix<Value, NumVars, NumJacobianCols>;
54 using Hessian = Eigen::Matrix<Value, NumVars, NumVars>;
63 return this->impl().score_(
x);
71 this->impl().jacobian_(
x, out);
79 this->impl().hessian_(
x, out);
107 template<
typename Derived,
typename DomainValueT,
int NumJacobianColsT,
int NumVarsT,
108 typename ComparatorT>
110 Expression<CachedExpression<Derived, DomainValueT,
111 NumJacobianColsT, NumVarsT, ComparatorT>,
112 DomainValueT, NumJacobianColsT, NumVarsT>
119 using Jacobian = Eigen::Matrix<Value, NumVars, NumJacobianCols>;
120 using Hessian = Eigen::Matrix<Value, NumVars, NumVars>;
121 using JacobianRef = Eigen::Ref<Eigen::Matrix<Value, NumVars, NumJacobianCols>>;
122 using HessianRef = Eigen::Ref<Eigen::Matrix<Value, NumVars, NumVars>>;
125 : m_score{0.0}, m_jacobian(Jacobian::Zero()), m_hessian{Hessian::Zero()},
126 m_cache_state(comparator) {}
157 m_cache_state.update(
x, mode);
159 static_cast<Derived *
>(
this)->evaluate_(
x, mode);
197 template<
typename Derived,
typename DomainValueT,
int NumJacobianColsT,
int NumVarsT,
198 typename ObjectiveT,
typename EqualityConstraintsT,
typename InequalityConstraintsT>
206 template<
typename Derived,
207 typename ... EqualityConstraints,
208 typename ... InequalityConstraints,
209 typename ObjectiveT,
typename DomainValueT,
int NumJacobianColsT,
int NumVarsT>
212 std::tuple<EqualityConstraints...>,
213 std::tuple<InequalityConstraints...>>
214 :
public Expression<Derived, DomainValueT, NumJacobianColsT, NumVarsT>
220 using Jacobian = Eigen::Matrix<Value, NumVarsT, NumJacobianColsT>;
221 using Hessian = Eigen::Matrix<Value, NumVarsT, NumVarsT>;
224 static constexpr
bool8_t is_unconstrained{(std::tuple_size<EqualityConstraintsT>::value == 0U) &&
225 (std::tuple_size<InequalityConstraintsT>::value == 0U)};
228 ObjectiveT && objective,
232 : m_objective(std::forward<ObjectiveT>(objective)),
238 template<
typename ... Args,
typename Dummy = void,
typename = std::enable_if_t<
239 is_unconstrained, Dummy>>
243 : m_objective(std::forward<Args>(args)...)
247 template<
bool8_t enabled = is_unconstrained>
248 typename std::enable_if_t<enabled, Value>
score_(
const DomainValueT &
x)
250 return m_objective(
x);
253 template<
bool8_t enabled = is_unconstrained>
254 typename std::enable_if_t<!enabled, Value>
score_(
const DomainValueT &
x)
256 return opt_impl()->score_opt_(
x);
259 template<
bool8_t enabled = is_unconstrained>
262 m_objective.jacobian(
x, out);
265 template<
bool8_t enabled = is_unconstrained>
268 opt_impl()->jacobian_opt_(
x, out);
271 template<
bool8_t enabled = is_unconstrained>
274 m_objective.hessian(
x, out);
277 template<
bool8_t enabled = is_unconstrained>
280 opt_impl()->hessian_opt_(
x, out);
283 template<
bool8_t enabled = is_unconstrained>
285 const DomainValueT &
x,
288 m_objective.evaluate(
x, mode);
291 template<
bool8_t enabled = is_unconstrained>
292 typename std::enable_if_t<!enabled, void>
evaluate(
293 const DomainValueT &
x,
296 opt_impl()->evaluate_(
x, mode);
307 return m_equality_constraints;
312 return m_inequality_constraints;
318 return static_cast<Derived *
>(
this);
321 ObjectiveT m_objective;
322 EqualityConstraintsT m_equality_constraints;
323 InequalityConstraintsT m_inequality_constraints;
331 template<
typename ObjectiveT,
typename DomainValueT,
int NumVarsT>
334 DomainValueT, 1U, NumVarsT, ObjectiveT, std::tuple<>, std::tuple<>>
336 using OptimizationProblem<UnconstrainedOptimizationProblem<ObjectiveT, DomainValueT, NumVarsT>,
344 #endif // OPTIMIZATION__OPTIMIZATION_PROBLEM_HPP_