17 #ifndef OPTIMIZATION__UTILS_HPP_
18 #define OPTIMIZATION__UTILS_HPP_
32 namespace optimization
63 bool8_t jacobian()
const noexcept;
66 bool8_t hessian()
const noexcept;
89 template<
typename T,
int H,
int W>
90 typename std::enable_if_t<std::is_floating_point<T>::value,
bool8_t>
91 operator()(
const Eigen::Matrix<T, H, W> & lhs,
const Eigen::Matrix<T, H, W> & rhs)
const
93 return lhs.isApprox(rhs, std::numeric_limits<T>::epsilon());
96 template<
typename T,
int H,
int W>
97 typename std::enable_if_t<std::is_integral<T>::value,
bool8_t>
98 operator()(
const Eigen::Matrix<T, H, W> & lhs,
const Eigen::Matrix<T, H, W> & rhs)
const
107 template<typename DomainValue, typename ComparatorT = decltype(std::equal_to<DomainValue>())>
111 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
115 : m_comparator(comparator) {}
122 const DomainValue & value,
const ComputeMode & mode,
123 const ComparatorT & comparator = ComparatorT())
124 : m_comparator(comparator), m_last_mode(mode), m_last_value(value)
134 m_last_value = value;
146 if (m_comparator(
x, m_last_value)) {
149 ret = m_last_mode.score();
152 ret = m_last_mode.jacobian();
155 ret = m_last_mode.hessian();
165 const ComparatorT m_comparator;
166 DomainValue m_last_value;
174 #endif // OPTIMIZATION__UTILS_HPP_