Autoware.Auto
autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT > Class Template Reference

#include <optimization_problem.hpp>

Inheritance diagram for autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >:
Collaboration diagram for autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >:

Public Types

using DomainValue = DomainValueT
 
using Value = autoware::common::types::float64_t
 
using Jacobian = Eigen::Matrix< Value, NumVars, NumJacobianCols >
 
using Hessian = Eigen::Matrix< Value, NumVars, NumVars >
 
using JacobianRef = Eigen::Ref< Jacobian >
 
using HessianRef = Eigen::Ref< Hessian >
 

Public Member Functions

Value operator() (const DomainValue &x)
 
void jacobian (const DomainValue &x, JacobianRef out)
 
void hessian (const DomainValue &x, HessianRef out)
 
void evaluate (const DomainValue &x, const ComputeMode &mode)
 

Static Public Attributes

static constexpr auto NumJacobianCols = NumJacobianColsT
 
static constexpr auto NumVars = NumVarsT
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::common::helper_functions::crtp< Derived >
const Derived & impl () const
 
Derived & impl ()
 

Detailed Description

template<typename Derived, typename DomainValueT, int NumJacobianColsT, int NumVarsT>
class autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >

CRTP base class for a mathematical expression.

Template Parameters
DerivedImplementation class. Must implement score_(..), jacobian_() and hessian(..).
DomainValueTParameter type.
NumJacobianColsTNumber of columns in the jacobian matrix.
NumVarsTNumber of variables.

Member Typedef Documentation

◆ DomainValue

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::DomainValue = DomainValueT

◆ Hessian

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::Hessian = Eigen::Matrix<Value, NumVars, NumVars>

◆ HessianRef

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::HessianRef = Eigen::Ref<Hessian>

◆ Jacobian

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::Jacobian = Eigen::Matrix<Value, NumVars, NumJacobianCols>

◆ JacobianRef

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::JacobianRef = Eigen::Ref<Jacobian>

◆ Value

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
using autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::Value = autoware::common::types::float64_t

Member Function Documentation

◆ evaluate()

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
void autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::evaluate ( const DomainValue x,
const ComputeMode mode 
)
inline

Pre-compute and cache the score/jacobian/hessian values. Which terms are to be computed is specified with the ComputeMode argument. By default, this function does nothing. You can implement and hide this function in your implementation to allow for some caching behavior. Though it is encouraged to use CachedExpression which already handles a big portion of the cache state management.

Parameters
xParameter value.
modeComputation mode. Which terms (score, jacobian, hessian) are to be computed can be set within this element.

◆ hessian()

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
void autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::hessian ( const DomainValue x,
HessianRef  out 
)
inline

Get the hessian at a given parameter value.

Parameters
xParameter value.{
outEvaluated hessian matrix.

◆ jacobian()

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
void autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::jacobian ( const DomainValue x,
JacobianRef  out 
)
inline

Get the jacobian at a given parameter value.

Parameters
xParameter value.
outEvaluated jacobian matrix.

◆ operator()()

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
Value autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::operator() ( const DomainValue x)
inline

Get the result of an expression for a given parameter value.

Parameters
xParameter value
Returns
Evaluated score

Member Data Documentation

◆ NumJacobianCols

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
constexpr auto autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::NumJacobianCols = NumJacobianColsT
staticconstexpr

◆ NumVars

template<typename Derived , typename DomainValueT , int NumJacobianColsT, int NumVarsT>
constexpr auto autoware::common::optimization::Expression< Derived, DomainValueT, NumJacobianColsT, NumVarsT >::NumVars = NumVarsT
staticconstexpr

The documentation for this class was generated from the following file: