diff --git a/gtsam/constraint/RampFunction.cpp b/gtsam/constraint/InequalityPenaltyFunction.cpp similarity index 75% rename from gtsam/constraint/RampFunction.cpp rename to gtsam/constraint/InequalityPenaltyFunction.cpp index 64038a325..8b048686f 100644 --- a/gtsam/constraint/RampFunction.cpp +++ b/gtsam/constraint/InequalityPenaltyFunction.cpp @@ -10,18 +10,23 @@ * -------------------------------------------------------------------------- */ /** - * @file RampFunction.cpp + * @file InequalityPenaltyFunction.cpp * @brief Ramp function to compute inequality constraint violations. * @author Yetong Zhang * @date Aug 3, 2024 */ -#include +#include namespace gtsam { -/* ************************************************************************* */ -double RampFunction(const double x, OptionalJacobian<1, 1> H) { +/* ********************************************************************************************* */ +InequalityPenaltyFunction::UnaryScalarFunc InequalityPenaltyFunction::function() const { + return [=](const double& x, OptionalJacobian<1, 1> H = {}) -> double { return (*this)(x, H); }; +} + +/* ********************************************************************************************* */ +double RampFunction::Ramp(const double x, OptionalJacobian<1, 1> H) { if (x < 0) { if (H) { H->setConstant(0); @@ -35,13 +40,8 @@ double RampFunction(const double x, OptionalJacobian<1, 1> H) { } } -/* ************************************************************************* */ -SmoothRampFunction::UnaryScalarFunc SmoothRampFunction::function() const { - return [=](const double& x, OptionalJacobian<1, 1> H = {}) -> double { return (*this)(x, H); }; -} - -/* ************************************************************************* */ -double RampFunctionPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) const { +/* ********************************************************************************************* */ +double SmoothRampPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) const { if (x <= 0) { if (H) { H->setZero(); @@ -60,8 +60,8 @@ double RampFunctionPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) } } -/* ************************************************************************* */ -double RampFunctionPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) const { +/* ********************************************************************************************* */ +double SmoothRampPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) const { if (x <= 0) { if (H) { H->setZero(); @@ -80,7 +80,7 @@ double RampFunctionPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) } } -/* ************************************************************************* */ +/* ********************************************************************************************* */ double SoftPlusFunction::operator()(const double& x, OptionalJacobian<1, 1> H) const { if (H) { H->setConstant(1 / (1 + std::exp(-k_ * x))); diff --git a/gtsam/constraint/RampFunction.h b/gtsam/constraint/InequalityPenaltyFunction.h similarity index 51% rename from gtsam/constraint/RampFunction.h rename to gtsam/constraint/InequalityPenaltyFunction.h index 0722551c5..baafaef0b 100644 --- a/gtsam/constraint/RampFunction.h +++ b/gtsam/constraint/InequalityPenaltyFunction.h @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file RampFunction.h + * @file InequalityPenaltyFunction.h * @brief Ramp function to compute inequality constraint violations. * @author Yetong Zhang * @date Aug 3, 2024 @@ -20,31 +20,49 @@ #include #include -#include namespace gtsam { +/** Base class for smooth approximation of the ramp function. */ +class GTSAM_EXPORT InequalityPenaltyFunction { + public: + typedef std::shared_ptr shared_ptr; + typedef std::function H)> + UnaryScalarFunc; + + /** Constructor. */ + InequalityPenaltyFunction() {} + + /** Destructor. */ + virtual ~InequalityPenaltyFunction() {} + + virtual double operator()(const double& x, + OptionalJacobian<1, 1> H = {}) const = 0; + + virtual UnaryScalarFunc function() const; +}; + /** Ramp function f : R -> R. * f(x) = 0 for x <= 0 * x for x > 0 */ -double RampFunction(const double x, OptionalJacobian<1, 1> H = {}); - -/** Base class for smooth approximation of the ramp function. */ -class SmoothRampFunction { +class GTSAM_EXPORT RampFunction : public InequalityPenaltyFunction { public: - typedef std::shared_ptr shared_ptr; - typedef std::function H)> UnaryScalarFunc; + typedef InequalityPenaltyFunction Base; + typedef RampFunction This; + typedef std::shared_ptr shared_ptr; - /** Constructor. */ - SmoothRampFunction() {} + public: + RampFunction() : Base() {} - /** Destructor. */ - virtual ~SmoothRampFunction() {} + virtual double operator()(const double& x, + OptionalJacobian<1, 1> H = {}) const override { + return Ramp(x, H); + } - virtual double operator()(const double& x, OptionalJacobian<1, 1> H = {}) const = 0; + virtual UnaryScalarFunc function() const override { return Ramp; } - UnaryScalarFunc function() const; + static double Ramp(const double x, OptionalJacobian<1, 1> H = {}); }; /** Ramp function approximated with a polynomial of degree 2 in [0, epsilon]. @@ -54,10 +72,10 @@ class SmoothRampFunction { * a * x^2 for 0 < x < epsilon * x - epsilon/2 for x >= epsilon */ -class RampFunctionPoly2 : public SmoothRampFunction { +class GTSAM_EXPORT SmoothRampPoly2 : public InequalityPenaltyFunction { public: - typedef SmoothRampFunction Base; - typedef RampFunctionPoly2 This; + typedef InequalityPenaltyFunction Base; + typedef SmoothRampPoly2 This; typedef std::shared_ptr shared_ptr; protected: @@ -65,9 +83,11 @@ class RampFunctionPoly2 : public SmoothRampFunction { double a_; public: - RampFunctionPoly2(const double epsilon = 1) : Base(), epsilon_(epsilon), a_(0.5 / epsilon) {} + SmoothRampPoly2(const double epsilon = 1) + : Base(), epsilon_(epsilon), a_(0.5 / epsilon) {} - virtual double operator()(const double& x, OptionalJacobian<1, 1> H = {}) const override; + virtual double operator()(const double& x, + OptionalJacobian<1, 1> H = {}) const override; }; /** Ramp function approximated with a polynomial of degree 3 in [0, epsilon]. @@ -78,10 +98,10 @@ class RampFunctionPoly2 : public SmoothRampFunction { * a * x^3 + b * x^2 for 0 < x < epsilon * x for x >= epsilon */ -class RampFunctionPoly3 : public SmoothRampFunction { +class GTSAM_EXPORT SmoothRampPoly3 : public InequalityPenaltyFunction { public: - typedef SmoothRampFunction Base; - typedef RampFunctionPoly3 This; + typedef InequalityPenaltyFunction Base; + typedef SmoothRampPoly3 This; typedef std::shared_ptr shared_ptr; protected: @@ -90,16 +110,20 @@ class RampFunctionPoly3 : public SmoothRampFunction { double b_; public: - RampFunctionPoly3(const double epsilon = 1) - : Base(), epsilon_(epsilon), a_(-1 / (epsilon * epsilon)), b_(2 / epsilon) {} + SmoothRampPoly3(const double epsilon = 1) + : Base(), + epsilon_(epsilon), + a_(-1 / (epsilon * epsilon)), + b_(2 / epsilon) {} - virtual double operator()(const double& x, OptionalJacobian<1, 1> H = {}) const override; + virtual double operator()(const double& x, + OptionalJacobian<1, 1> H = {}) const override; }; /** Softplus function that implements f(x) = log(1 + exp(k*x)) / k. */ -class SoftPlusFunction : public SmoothRampFunction { +class GTSAM_EXPORT SoftPlusFunction : public InequalityPenaltyFunction { public: - typedef SmoothRampFunction Base; + typedef InequalityPenaltyFunction Base; typedef SoftPlusFunction This; typedef std::shared_ptr shared_ptr; @@ -109,7 +133,8 @@ class SoftPlusFunction : public SmoothRampFunction { public: SoftPlusFunction(const double k = 1) : Base(), k_(k) {} - virtual double operator()(const double& x, OptionalJacobian<1, 1> H = {}) const override; + virtual double operator()(const double& x, + OptionalJacobian<1, 1> H = {}) const override; }; } // namespace gtsam diff --git a/gtsam/constraint/NonlinearConstraint.h b/gtsam/constraint/NonlinearConstraint.h index 834ef7991..558818803 100644 --- a/gtsam/constraint/NonlinearConstraint.h +++ b/gtsam/constraint/NonlinearConstraint.h @@ -31,7 +31,7 @@ namespace gtsam { * whitenedError() returns The constraint violation vector. * unwhitenedError() returns the sigma-scaled constraint violation vector. */ -class NonlinearConstraint : public NoiseModelFactor { +class GTSAM_EXPORT NonlinearConstraint : public NoiseModelFactor { public: typedef NoiseModelFactor Base; @@ -54,6 +54,13 @@ class NonlinearConstraint : public NoiseModelFactor { return violation(x) <= tolerance; } + const Vector sigmas() const { return noiseModel()->sigmas(); } + + // return the hessian of unwhitened error function in each dimension. + virtual std::vector unwhitenedHessian(const Values& x) const { + throw std::runtime_error("hessian not implemented"); + } + protected: /** Noise model used for the penalty function. */ SharedDiagonal penaltyNoise(const double mu) const { diff --git a/gtsam/constraint/NonlinearEqualityConstraint-inl.h b/gtsam/constraint/NonlinearEqualityConstraint-inl.h index 625f1e366..c228cf97d 100644 --- a/gtsam/constraint/NonlinearEqualityConstraint-inl.h +++ b/gtsam/constraint/NonlinearEqualityConstraint-inl.h @@ -21,7 +21,7 @@ namespace gtsam { -/* ************************************************************************* */ +/* ********************************************************************************************* */ template ExpressionEqualityConstraint::ExpressionEqualityConstraint(const Expression& expression, const T& rhs, @@ -31,7 +31,7 @@ ExpressionEqualityConstraint::ExpressionEqualityConstraint(const Expression Vector ExpressionEqualityConstraint::unwhitenedError(const Values& x, OptionalMatrixVecType H) const { @@ -45,7 +45,7 @@ Vector ExpressionEqualityConstraint::unwhitenedError(const Values& x, } } -/* ************************************************************************* */ +/* ********************************************************************************************* */ template NoiseModelFactor::shared_ptr ExpressionEqualityConstraint::penaltyFactor(const double mu) const { return std::make_shared>(penaltyNoise(mu), rhs_, expression_); diff --git a/gtsam/constraint/NonlinearEqualityConstraint.cpp b/gtsam/constraint/NonlinearEqualityConstraint.cpp index 0c5b7ea11..8705f7db9 100644 --- a/gtsam/constraint/NonlinearEqualityConstraint.cpp +++ b/gtsam/constraint/NonlinearEqualityConstraint.cpp @@ -19,21 +19,21 @@ namespace gtsam { -/* ************************************************************************* */ +/* ********************************************************************************************* */ ZeroCostConstraint::ZeroCostConstraint(const NoiseModelFactor::shared_ptr& factor) : Base(constrainedNoise(factor->noiseModel()->sigmas()), factor->keys()), factor_(factor) {} -/* ************************************************************************* */ +/* ********************************************************************************************* */ Vector ZeroCostConstraint::unwhitenedError(const Values& x, OptionalMatrixVecType H) const { return factor_->unwhitenedError(x, H); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NoiseModelFactor::shared_ptr ZeroCostConstraint::penaltyFactor(const double mu) const { return factor_->cloneWithNewNoiseModel(penaltyNoise(mu)); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NonlinearEqualityConstraints NonlinearEqualityConstraints::FromCostGraph( const NonlinearFactorGraph& graph) { NonlinearEqualityConstraints constraints; @@ -44,7 +44,7 @@ NonlinearEqualityConstraints NonlinearEqualityConstraints::FromCostGraph( return constraints; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ size_t NonlinearEqualityConstraints::dim() const { size_t dimension = 0; for (const auto& constraint : *this) { @@ -53,7 +53,7 @@ size_t NonlinearEqualityConstraints::dim() const { return dimension; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ Vector NonlinearEqualityConstraints::violationVector(const Values& values, bool whiten) const { Vector violation(dim()); size_t start_idx = 0; @@ -66,12 +66,12 @@ Vector NonlinearEqualityConstraints::violationVector(const Values& values, bool return violation; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ double NonlinearEqualityConstraints::violationNorm(const Values& values) const { return violationVector(values, true).norm(); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NonlinearFactorGraph NonlinearEqualityConstraints::penaltyGraph(const double mu) const { NonlinearFactorGraph graph; for (const auto& constraint : *this) { diff --git a/gtsam/constraint/NonlinearEqualityConstraint.h b/gtsam/constraint/NonlinearEqualityConstraint.h index ab7dca2f0..532c3ab38 100644 --- a/gtsam/constraint/NonlinearEqualityConstraint.h +++ b/gtsam/constraint/NonlinearEqualityConstraint.h @@ -26,7 +26,7 @@ namespace gtsam { /** * Equality constraint base class. */ -class NonlinearEqualityConstraint : public NonlinearConstraint { +class GTSAM_EXPORT NonlinearEqualityConstraint : public NonlinearConstraint { public: typedef NonlinearConstraint Base; typedef NonlinearEqualityConstraint This; @@ -52,7 +52,7 @@ class NonlinearEqualityConstraint : public NonlinearConstraint { /** Equality constraint that force g(x) = M. */ template -class ExpressionEqualityConstraint : public NonlinearEqualityConstraint { +class GTSAM_EXPORT ExpressionEqualityConstraint : public NonlinearEqualityConstraint { public: typedef NonlinearEqualityConstraint Base; typedef ExpressionEqualityConstraint This; @@ -100,7 +100,7 @@ class ExpressionEqualityConstraint : public NonlinearEqualityConstraint { }; /** Equality constraint that enforce the cost factor with zero error. */ -class ZeroCostConstraint : public NonlinearEqualityConstraint { +class GTSAM_EXPORT ZeroCostConstraint : public NonlinearEqualityConstraint { public: typedef NonlinearEqualityConstraint Base; typedef ZeroCostConstraint This; @@ -142,7 +142,7 @@ class ZeroCostConstraint : public NonlinearEqualityConstraint { }; /// Container of NonlinearEqualityConstraint. -class NonlinearEqualityConstraints : public FactorGraph { +class GTSAM_EXPORT NonlinearEqualityConstraints : public FactorGraph { public: typedef std::shared_ptr shared_ptr; typedef FactorGraph Base; diff --git a/gtsam/constraint/NonlinearInequalityConstraint.cpp b/gtsam/constraint/NonlinearInequalityConstraint.cpp index 49003f09f..3404a143c 100644 --- a/gtsam/constraint/NonlinearInequalityConstraint.cpp +++ b/gtsam/constraint/NonlinearInequalityConstraint.cpp @@ -17,11 +17,15 @@ */ #include -#include namespace gtsam { -/* ************************************************************************* */ +/* ********************************************************************************************* */ +Vector NonlinearInequalityConstraint::whitenedExpr(const Values& x) const { + return noiseModel()->whiten(unwhitenedExpr(x)); +} + +/* ********************************************************************************************* */ Vector NonlinearInequalityConstraint::unwhitenedError(const Values& x, OptionalMatrixVecType H) const { Vector error = unwhitenedExpr(x, H); @@ -38,52 +42,52 @@ Vector NonlinearInequalityConstraint::unwhitenedError(const Values& x, return error; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ bool NonlinearInequalityConstraint::active(const Values& x) const { return (unwhitenedExpr(x).array() >= 0).any(); } -/* ************************************************************************* */ -NoiseModelFactor::shared_ptr NonlinearInequalityConstraint::penaltyFactorSmooth( - SmoothRampFunction::shared_ptr func, const double mu) const { +/* ********************************************************************************************* */ +NoiseModelFactor::shared_ptr NonlinearInequalityConstraint::penaltyFactorCustom( + InequalityPenaltyFunction::shared_ptr func, const double mu) const { /// Default behavior, this function should be overriden. return penaltyFactor(mu); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NonlinearEqualityConstraint::shared_ptr NonlinearInequalityConstraint::createEqualityConstraint() const { /// Default behavior, this function should be overriden. return nullptr; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NoiseModelFactor::shared_ptr NonlinearInequalityConstraint::penaltyFactorEquality( const double mu) const { return createEqualityConstraint()->penaltyFactor(mu); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ ScalarExpressionInequalityConstraint::ScalarExpressionInequalityConstraint( const Double_& expression, const double& sigma) : Base(constrainedNoise(Vector1(sigma)), expression.keysAndDims().first), expression_(expression), dims_(expression.keysAndDims().second) {} -/* ************************************************************************* */ +/* ********************************************************************************************* */ ScalarExpressionInequalityConstraint::shared_ptr ScalarExpressionInequalityConstraint::GeqZero( const Double_& expression, const double& sigma) { Double_ neg_expr = Double_(0.0) - expression; return std::make_shared(neg_expr, sigma); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ ScalarExpressionInequalityConstraint::shared_ptr ScalarExpressionInequalityConstraint::LeqZero( const Double_& expression, const double& sigma) { return std::make_shared(expression, sigma); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ Vector ScalarExpressionInequalityConstraint::unwhitenedExpr(const Values& x, OptionalMatrixVecType H) const { // Copy-paste from ExpressionFactor. @@ -94,35 +98,38 @@ Vector ScalarExpressionInequalityConstraint::unwhitenedExpr(const Values& x, } } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NonlinearEqualityConstraint::shared_ptr ScalarExpressionInequalityConstraint::createEqualityConstraint() const { return std::make_shared>( expression_, 0.0, noiseModel()->sigmas()); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NoiseModelFactor::shared_ptr ScalarExpressionInequalityConstraint::penaltyFactor( const double mu) const { - Double_ penalty_expression(RampFunction, expression_); + Double_ penalty_expression(RampFunction::Ramp, expression_); return std::make_shared>(penaltyNoise(mu), 0.0, penalty_expression); } -/* ************************************************************************* */ -NoiseModelFactor::shared_ptr ScalarExpressionInequalityConstraint::penaltyFactorSmooth( - SmoothRampFunction::shared_ptr func, const double mu) const { +/* ********************************************************************************************* */ +NoiseModelFactor::shared_ptr ScalarExpressionInequalityConstraint::penaltyFactorCustom( + InequalityPenaltyFunction::shared_ptr func, const double mu) const { + if (!func) { + return penaltyFactor(mu); + } // TODO(yetong): can we pass the functor directly to construct the expression? Double_ error(func->function(), expression_); return std::make_shared>(penaltyNoise(mu), 0.0, error); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NoiseModelFactor::shared_ptr ScalarExpressionInequalityConstraint::penaltyFactorEquality( const double mu) const { return std::make_shared>(penaltyNoise(mu), 0.0, expression_); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ size_t NonlinearInequalityConstraints::dim() const { size_t dimension = 0; for (const auto& constraint : *this) { @@ -131,7 +138,7 @@ size_t NonlinearInequalityConstraints::dim() const { return dimension; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ Vector NonlinearInequalityConstraints::violationVector(const Values& values, bool whiten) const { Vector violation(dim()); size_t start_idx = 0; @@ -144,12 +151,12 @@ Vector NonlinearInequalityConstraints::violationVector(const Values& values, boo return violation; } -/* ************************************************************************* */ +/* ********************************************************************************************* */ double NonlinearInequalityConstraints::violationNorm(const Values& values) const { return violationVector(values, true).norm(); } -/* ************************************************************************* */ +/* ********************************************************************************************* */ NonlinearFactorGraph NonlinearInequalityConstraints::penaltyGraph(const double mu) const { NonlinearFactorGraph graph; for (const auto& constraint : *this) { @@ -158,12 +165,12 @@ NonlinearFactorGraph NonlinearInequalityConstraints::penaltyGraph(const double m return graph; } -/* ************************************************************************* */ -NonlinearFactorGraph NonlinearInequalityConstraints::penaltyGraphSmooth( - SmoothRampFunction::shared_ptr func, const double mu) const { +/* ********************************************************************************************* */ +NonlinearFactorGraph NonlinearInequalityConstraints::penaltyGraphCustom( + InequalityPenaltyFunction::shared_ptr func, const double mu) const { NonlinearFactorGraph graph; for (const auto& constraint : *this) { - graph.add(constraint->penaltyFactorSmooth(func, mu)); + graph.add(constraint->penaltyFactorCustom(func, mu)); } return graph; } diff --git a/gtsam/constraint/NonlinearInequalityConstraint.h b/gtsam/constraint/NonlinearInequalityConstraint.h index 1a1813ea3..658a29f2f 100644 --- a/gtsam/constraint/NonlinearInequalityConstraint.h +++ b/gtsam/constraint/NonlinearInequalityConstraint.h @@ -18,8 +18,8 @@ #pragma once +#include #include -#include #include namespace gtsam { @@ -27,7 +27,7 @@ namespace gtsam { /** * Inequality constraint base class, enforcing g(x) <= 0. */ -class NonlinearInequalityConstraint : public NonlinearConstraint { +class GTSAM_EXPORT NonlinearInequalityConstraint : public NonlinearConstraint { public: typedef NonlinearConstraint Base; typedef NonlinearInequalityConstraint This; @@ -42,6 +42,8 @@ class NonlinearInequalityConstraint : public NonlinearConstraint { /** Return g(x). */ virtual Vector unwhitenedExpr(const Values& x, OptionalMatrixVecType H = nullptr) const = 0; + virtual Vector whitenedExpr(const Values& x) const; + /** Return ramp(g(x)). */ virtual Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const override; @@ -51,9 +53,9 @@ class NonlinearInequalityConstraint : public NonlinearConstraint { /** Return an equality constraint corresponding to g(x)=0. */ virtual NonlinearEqualityConstraint::shared_ptr createEqualityConstraint() const; - /** Smooth approximation of the ramp function. */ - virtual NoiseModelFactor::shared_ptr penaltyFactorSmooth(SmoothRampFunction::shared_ptr func, - const double mu = 1.0) const; + /** Cost factor using a customized penalty function. */ + virtual NoiseModelFactor::shared_ptr penaltyFactorCustom( + InequalityPenaltyFunction::shared_ptr func, const double mu = 1.0) const; /** penalty function as if the constraint is equality, 0.5 * mu * ||g(x)||^2 */ virtual NoiseModelFactor::shared_ptr penaltyFactorEquality(const double mu = 1.0) const; @@ -73,7 +75,7 @@ class NonlinearInequalityConstraint : public NonlinearConstraint { /** Inequality constraint that force g(x) <= 0, where g(x) is a scalar-valued * nonlinear function. */ -class ScalarExpressionInequalityConstraint : public NonlinearInequalityConstraint { +class GTSAM_EXPORT ScalarExpressionInequalityConstraint : public NonlinearInequalityConstraint { public: typedef NonlinearInequalityConstraint Base; typedef ScalarExpressionInequalityConstraint This; @@ -111,7 +113,7 @@ class ScalarExpressionInequalityConstraint : public NonlinearInequalityConstrain NoiseModelFactor::shared_ptr penaltyFactor(const double mu = 1.0) const override; /** Penalty function using a smooth approxiamtion of the ramp funciton. */ - NoiseModelFactor::shared_ptr penaltyFactorSmooth(SmoothRampFunction::shared_ptr func, + NoiseModelFactor::shared_ptr penaltyFactorCustom(InequalityPenaltyFunction::shared_ptr func, const double mu = 1.0) const override; /** Penalty function as if the constraint is equality, 0.5 * mu * ||g(x)/sigma||^2. */ @@ -141,7 +143,8 @@ class ScalarExpressionInequalityConstraint : public NonlinearInequalityConstrain }; /// Container of NonlinearInequalityConstraint. -class NonlinearInequalityConstraints : public FactorGraph { +class GTSAM_EXPORT NonlinearInequalityConstraints + : public FactorGraph { public: typedef FactorGraph Base; typedef NonlinearInequalityConstraints This; @@ -161,8 +164,8 @@ class NonlinearInequalityConstraints : public FactorGraph -#include -#include -#include -#include +#include #include #include -#include -#include - +#include "gtsam/constraint/NonlinearEqualityConstraint.h" +#include "gtsam/constraint/NonlinearInequalityConstraint.h" namespace constrained_example { using namespace gtsam; /// Exponential function e^x. -double exp_func(const double& x, gtsam::OptionalJacobian<1, 1> H1 = {}) { +inline double exp_func(const double& x, gtsam::OptionalJacobian<1, 1> H1 = {}) { double result = exp(x); if (H1) H1->setConstant(result); return result; } /// Exponential expression e^x. -Double_ exp(const Double_& x) { return Double_(exp_func, x); } +inline Double_ exp(const Double_& x) { return Double_(exp_func, x); } /// Pow functor used for pow function. class PowFunctor { @@ -51,24 +46,23 @@ class PowFunctor { public: PowFunctor(const double& c) : c_(c) {} - double operator()(const double& x, - gtsam::OptionalJacobian<1, 1> H1 = {}) const { + double operator()(const double& x, gtsam::OptionalJacobian<1, 1> H1 = {}) const { if (H1) H1->setConstant(c_ * pow(x, c_ - 1)); return pow(x, c_); } }; /// Pow function. -Double_ pow(const Double_& x, const double& c) { +inline Double_ pow(const Double_& x, const double& c) { PowFunctor pow_functor(c); return Double_(pow_functor, x); } /// Plus between Double expression and double. -Double_ operator+(const Double_& x, const double& d) { return x + Double_(d); } +inline Double_ operator+(const Double_& x, const double& d) { return x + Double_(d); } /// Negative sign operator. -Double_ operator-(const Double_& x) { return Double_(0.0) - x; } +inline Double_ operator-(const Double_& x) { return Double_(0.0) - x; } /// Keys for creating expressions. Symbol x1_key('x', 1); @@ -82,11 +76,11 @@ Double_ x1(x1_key), x2(x2_key); * Constrained optimization example in L. Vandenberghe slides: * https://www.seas.ucla.edu/~vandenbe/133B/lectures/nllseq.pdf * f(x) = 0.5*||x1 + e^(-x2)||^2 + 0.5*||x1^2 + 2*x2 + 1||^2 - * h(x) = x1 + x1^3 + x2 + x2^2 + * h(x) = x1 + x1^3 + x2 + x2^2 = 0 */ -namespace e_constrained_example { +namespace constrained_example1 { using namespace constrained_example; -NonlinearFactorGraph GetCost() { +NonlinearFactorGraph Cost() { NonlinearFactorGraph graph; auto f1 = x1 + exp(-x2); auto f2 = pow(x1, 2.0) + 2.0 * x2 + 1.0; @@ -96,28 +90,49 @@ NonlinearFactorGraph GetCost() { return graph; } -NonlinearEqualityConstraints GetConstraints() { +NonlinearEqualityConstraints EqConstraints() { NonlinearEqualityConstraints constraints; - Vector scale = Vector1(0.1); + Vector sigmas = Vector1(1.0); auto h1 = x1 + pow(x1, 3) + x2 + pow(x2, 2); constraints.push_back(NonlinearEqualityConstraint::shared_ptr( - new ExpressionEqualityConstraint(h1, 0.0, scale))); + new ExpressionEqualityConstraint(h1, 0.0, sigmas))); return constraints; } -NonlinearFactorGraph cost = GetCost(); -NonlinearEqualityConstraints constraints = GetConstraints(); -} // namespace e_constrained_example +Values InitValues() { + Values values; + values.insert(x1_key, -0.2); + values.insert(x2_key, -0.2); + return values; +} + +Values OptimalValues() { + Values values; + values.insert(x1_key, 0.0); + values.insert(x2_key, 0.0); + return values; +} + +NonlinearFactorGraph costs = Cost(); +NonlinearEqualityConstraints e_constraints = EqConstraints(); +NonlinearInequalityConstraints i_constraints; +Values init_values = InitValues(); +ConstrainedOptProblem::shared_ptr problem = + std::make_shared(costs, e_constraints, i_constraints, init_values); +Values optimal_values = OptimalValues(); +} // namespace constrained_example1 /* ************************************************************************* */ /** * Constrained optimization example with inequality constraints + * Approach a point while staying on unit circle, and within an ellipse. * f(x) = 0.5 * ||x1-1||^2 + 0.5 * ||x2-1||^2 - * g(x) = 1 - x1^2 - x2^2 + * h(x) = x1^2 + x2^2 - 1 = 0 + * g(x) = 4*x1^2 + 0.25*x2^2 - 1 <= 0 */ -namespace i_constrained_example { +namespace constrained_example2 { using namespace constrained_example; -NonlinearFactorGraph GetCost() { +NonlinearFactorGraph Cost() { NonlinearFactorGraph graph; auto cost_noise = gtsam::noiseModel::Isotropic::Sigma(1, 1.0); graph.addPrior(x1_key, 1.0, cost_noise); @@ -125,44 +140,42 @@ NonlinearFactorGraph GetCost() { return graph; } -// InequalityConstraints GetIConstraints() { -// InequalityConstraints i_constraints; -// Double_ g1 = Double_(1.0) - x1 * x1 - x2 * x2; -// double tolerance = 0.2; -// i_constraints.emplace_shared(g1, tolerance); -// return i_constraints; -// } - -NonlinearFactorGraph cost = GetCost(); -NonlinearEqualityConstraints e_constraints; -// InequalityConstraints i_constraints = GetIConstraints(); -} // namespace i_constrained_example - -/* ************************************************************************* */ -/** - * Constrained optimization example with inequality constraints - * f(x) = 0.5 * ||x1||^2 + 0.5 * ||x2||^2 - * h(x) = x1 + x2 - 1 - */ -namespace e_constrained_example2 { -using namespace constrained_example; -NonlinearFactorGraph GetCost() { - NonlinearFactorGraph graph; - auto cost_noise = gtsam::noiseModel::Isotropic::Sigma(1, 1.0); - graph.addPrior(x1_key, 1.0, cost_noise); - // graph.addPrior(x2_key, 0.0, cost_noise); - // graph.emplace_shared>(x1_key, x2_key, 1.0, cost_noise); - return graph; +NonlinearEqualityConstraints EqConstraints() { + NonlinearEqualityConstraints constraints; + Vector1 sigmas(1.0); + Double_ h1 = x1 * x1 + x2 * x2; + constraints.emplace_shared>(h1, 1.0, sigmas); + return constraints; } -NonlinearEqualityConstraints GetEConstraints() { - NonlinearEqualityConstraints e_constraints; - // Double_ h1 = x1 + x2 - Double_(1.0); - // double tolerance = 0.2; - // e_constraints.emplace_shared(h1, tolerance); - return e_constraints; +NonlinearInequalityConstraints IneqConstraints() { + NonlinearInequalityConstraints constraints; + Double_ g1 = 4 * x1 * x1 + 0.25 * x2 * x2 - Double_(1.0); + double sigma = 1; + constraints.emplace_shared(g1, sigma); + return constraints; } -NonlinearFactorGraph cost = GetCost(); -NonlinearEqualityConstraints e_constraints = GetEConstraints(); -} // namespace i_constrained_example +Values InitValues() { + Values values; + values.insert(x1_key, -1.0); + values.insert(x2_key, 2.0); + return values; +} + +Values OptimalValues() { + Values values; + values.insert(x1_key, 1.0 / sqrt(5)); + values.insert(x2_key, 2.0 / sqrt(5)); + return values; +} + +NonlinearFactorGraph costs = Cost(); +NonlinearEqualityConstraints e_constraints = EqConstraints(); +NonlinearInequalityConstraints i_constraints = IneqConstraints(); +Values init_values = InitValues(); +ConstrainedOptProblem::shared_ptr problem = + std::make_shared(costs, e_constraints, i_constraints, init_values); +Values optimal_values = OptimalValues(); + +} // namespace constrained_example2 diff --git a/gtsam/constraint/tests/testRampFunction.cpp b/gtsam/constraint/tests/testInequalityPenaltyFunction.cpp similarity index 84% rename from gtsam/constraint/tests/testRampFunction.cpp rename to gtsam/constraint/tests/testInequalityPenaltyFunction.cpp index 2e8036d74..09cd17d5b 100644 --- a/gtsam/constraint/tests/testRampFunction.cpp +++ b/gtsam/constraint/tests/testInequalityPenaltyFunction.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file testRampFunction.h + * @file testInequalityPenaltyFunction.h * @brief unit tests for ramp functions * @author Yetong Zhang * @date Aug 3, 2024 @@ -20,13 +20,14 @@ #include #include #include -#include +#include using namespace gtsam; +/* ********************************************************************************************* */ TEST(RampFunction, error_and_jacobian) { /// Helper function for numerical Jacobian computation. - auto ramp_helper = [&](const double& x) { return RampFunction(x); }; + auto ramp_helper = [&](const double& x) { return RampFunction::Ramp(x); }; /// Create a set of values to test the function. static std::vector x_vec{-3.0, 0.0, 1.0, 2.0, 3.0}; @@ -35,7 +36,7 @@ TEST(RampFunction, error_and_jacobian) { for (size_t i = 0; i < x_vec.size(); i++) { double x = x_vec.at(i); Matrix H; - double r = RampFunction(x, H); + double r = RampFunction::Ramp(x, H); /// Check function evaluation. EXPECT_DOUBLES_EQUAL(expected_r_vec.at(i), r, 1e-9); @@ -48,9 +49,10 @@ TEST(RampFunction, error_and_jacobian) { } } +/* ********************************************************************************************* */ TEST(RampFunctionPoly2, error_and_jacobian) { /// Helper function for numerical Jacobian computation. - RampFunctionPoly2 p_ramp(2.0); + SmoothRampPoly2 p_ramp(2.0); auto ramp_helper = [&](const double& x) { return p_ramp(x); }; /// Create a set of values to test the function. @@ -71,9 +73,10 @@ TEST(RampFunctionPoly2, error_and_jacobian) { } } +/* ********************************************************************************************* */ TEST(RampFunctionPoly3, error_and_jacobian) { /// Helper function for numerical Jacobian computation. - RampFunctionPoly3 p_ramp(2.0); + SmoothRampPoly3 p_ramp(2.0); auto ramp_helper = [&](const double& x) { return p_ramp(x); }; /// Create a set of values to test the function. @@ -94,6 +97,7 @@ TEST(RampFunctionPoly3, error_and_jacobian) { } } +/* ********************************************************************************************* */ TEST(SoftPlusFunction, error_and_jacobian) { /// Helper function for numerical Jacobian computation. SoftPlusFunction soft_plus(0.5); diff --git a/gtsam/constraint/tests/testNonlinearEqualityConstraint.cpp b/gtsam/constraint/tests/testNonlinearEqualityConstraint.cpp index 8309de0b3..70dabff45 100644 --- a/gtsam/constraint/tests/testNonlinearEqualityConstraint.cpp +++ b/gtsam/constraint/tests/testNonlinearEqualityConstraint.cpp @@ -22,7 +22,6 @@ #include #include #include -#include #include #include @@ -155,7 +154,6 @@ TEST(ExpressionEqualityConstraint, Vector2) { EXPECT_CORRECT_FACTOR_JACOBIANS(*merit_factor, values2, 1e-7, 1e-5); } - // Test methods of FactorZeroErrorConstraint. TEST(ZeroCostConstraint, BetweenFactor) { Key x1_key = 1; @@ -218,9 +216,6 @@ TEST(ZeroCostConstraint, BetweenFactor) { EXPECT_CORRECT_FACTOR_JACOBIANS(*merit_factor, values2, 1e-7, 1e-5); } - - - TEST(NonlinearEqualityConstraints, Container) { NonlinearEqualityConstraints constraints; @@ -254,12 +249,9 @@ TEST(NonlinearEqualityConstraints, Container) { EXPECT(assert_container_equality(expected_vi_x2, vi[x2_key])); // Check constraint violation. - } - -TEST(NonlinearEqualityConstraints, FromCostGraph) { -} +TEST(NonlinearEqualityConstraints, FromCostGraph) {} int main() { TestResult tr;