-
Notifications
You must be signed in to change notification settings - Fork 792
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #1789 from borglab/feature/constrained_optimization
add definition of constraints
- Loading branch information
Showing
21 changed files
with
1,713 additions
and
58 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -6,6 +6,7 @@ project(gtsam LANGUAGES CXX) | |
set (gtsam_subdirs | ||
base | ||
basis | ||
constrained | ||
geometry | ||
inference | ||
symbolic | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,6 @@ | ||
# Install headers | ||
file(GLOB constraint_headers "*.h") | ||
install(FILES ${constraint_headers} DESTINATION include/gtsam/constrained) | ||
|
||
# Build tests | ||
add_subdirectory(tests) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,91 @@ | ||
/* ---------------------------------------------------------------------------- | ||
* GTSAM Copyright 2010, Georgia Tech Research Corporation, | ||
* Atlanta, Georgia 30332-0415 | ||
* All Rights Reserved | ||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) | ||
* See LICENSE for the license information | ||
* -------------------------------------------------------------------------- */ | ||
|
||
/** | ||
* @file InequalityPenaltyFunction.cpp | ||
* @brief Ramp function to compute inequality constraint violations. | ||
* @author Yetong Zhang | ||
* @date Aug 3, 2024 | ||
*/ | ||
|
||
#include <gtsam/constrained/InequalityPenaltyFunction.h> | ||
|
||
namespace gtsam { | ||
|
||
/* ********************************************************************************************* */ | ||
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); | ||
} | ||
return 0; | ||
} else { | ||
if (H) { | ||
H->setConstant(1); | ||
} | ||
return x; | ||
} | ||
} | ||
|
||
/* ********************************************************************************************* */ | ||
double SmoothRampPoly2::operator()(const double& x, OptionalJacobian<1, 1> H) const { | ||
if (x <= 0) { | ||
if (H) { | ||
H->setZero(); | ||
} | ||
return 0; | ||
} else if (x < epsilon_) { | ||
if (H) { | ||
H->setConstant(2 * a_ * x); | ||
} | ||
return a_ * pow(x, 2); | ||
} else { | ||
if (H) { | ||
H->setOnes(); | ||
} | ||
return x - epsilon_ / 2; | ||
} | ||
} | ||
|
||
/* ********************************************************************************************* */ | ||
double SmoothRampPoly3::operator()(const double& x, OptionalJacobian<1, 1> H) const { | ||
if (x <= 0) { | ||
if (H) { | ||
H->setZero(); | ||
} | ||
return 0; | ||
} else if (x < epsilon_) { | ||
if (H) { | ||
H->setConstant(3 * a_ * pow(x, 2) + 2 * b_ * x); | ||
} | ||
return a_ * pow(x, 3) + b_ * pow(x, 2); | ||
} else { | ||
if (H) { | ||
H->setOnes(); | ||
} | ||
return x; | ||
} | ||
} | ||
|
||
/* ********************************************************************************************* */ | ||
double SoftPlusFunction::operator()(const double& x, OptionalJacobian<1, 1> H) const { | ||
if (H) { | ||
H->setConstant(1 / (1 + std::exp(-k_ * x))); | ||
} | ||
return std::log(1 + std::exp(k_ * x)) / k_; | ||
} | ||
|
||
} // namespace gtsam |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,149 @@ | ||
/* ---------------------------------------------------------------------------- | ||
* GTSAM Copyright 2010, Georgia Tech Research Corporation, | ||
* Atlanta, Georgia 30332-0415 | ||
* All Rights Reserved | ||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) | ||
* See LICENSE for the license information | ||
* -------------------------------------------------------------------------- */ | ||
|
||
/** | ||
* @file InequalityPenaltyFunction.h | ||
* @brief Ramp function to compute inequality constraint violations. | ||
* @author Yetong Zhang | ||
* @date Aug 3, 2024 | ||
*/ | ||
|
||
#pragma once | ||
|
||
#include <gtsam/nonlinear/ExpressionFactor.h> | ||
#include <gtsam/nonlinear/expressions.h> | ||
|
||
namespace gtsam { | ||
|
||
/** Base class for smooth approximation of the ramp function. */ | ||
class GTSAM_EXPORT InequalityPenaltyFunction { | ||
public: | ||
typedef std::shared_ptr<InequalityPenaltyFunction> shared_ptr; | ||
typedef std::function<double(const double& x, OptionalJacobian<1, 1> 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 | ||
*/ | ||
class GTSAM_EXPORT RampFunction : public InequalityPenaltyFunction { | ||
public: | ||
typedef InequalityPenaltyFunction Base; | ||
typedef RampFunction This; | ||
typedef std::shared_ptr<This> shared_ptr; | ||
|
||
public: | ||
RampFunction() : Base() {} | ||
|
||
virtual double operator()(const double& x, | ||
OptionalJacobian<1, 1> H = {}) const override { | ||
return Ramp(x, H); | ||
} | ||
|
||
virtual UnaryScalarFunc function() const override { return Ramp; } | ||
|
||
static double Ramp(const double x, OptionalJacobian<1, 1> H = {}); | ||
}; | ||
|
||
/** Ramp function approximated with a polynomial of degree 2 in [0, epsilon]. | ||
* The coefficients are computed as | ||
* a = 1 / (2 * epsilon) | ||
* Function f(x) = 0 for x <= 0 | ||
* a * x^2 for 0 < x < epsilon | ||
* x - epsilon/2 for x >= epsilon | ||
*/ | ||
class GTSAM_EXPORT SmoothRampPoly2 : public InequalityPenaltyFunction { | ||
public: | ||
typedef InequalityPenaltyFunction Base; | ||
typedef SmoothRampPoly2 This; | ||
typedef std::shared_ptr<This> shared_ptr; | ||
|
||
protected: | ||
double epsilon_; | ||
double a_; | ||
|
||
public: | ||
/** Constructor. | ||
* @param epsilon parameter for adjusting the smoothness of the function. | ||
*/ | ||
SmoothRampPoly2(const double epsilon = 1) | ||
: Base(), epsilon_(epsilon), a_(0.5 / epsilon) {} | ||
|
||
virtual double operator()(const double& x, | ||
OptionalJacobian<1, 1> H = {}) const override; | ||
}; | ||
|
||
/** Ramp function approximated with a polynomial of degree 3 in [0, epsilon]. | ||
* The coefficients are computed as | ||
* a = -1 / epsilon^2 | ||
* b = 2 / epsilon | ||
* Function f(x) = 0 for x <= 0 | ||
* a * x^3 + b * x^2 for 0 < x < epsilon | ||
* x for x >= epsilon | ||
*/ | ||
class GTSAM_EXPORT SmoothRampPoly3 : public InequalityPenaltyFunction { | ||
public: | ||
typedef InequalityPenaltyFunction Base; | ||
typedef SmoothRampPoly3 This; | ||
typedef std::shared_ptr<This> shared_ptr; | ||
|
||
protected: | ||
double epsilon_; | ||
double a_; | ||
double b_; | ||
|
||
public: | ||
/** Constructor. | ||
* @param epsilon parameter for adjusting the smoothness of the function. | ||
*/ | ||
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; | ||
}; | ||
|
||
/** Softplus function that implements f(x) = log(1 + exp(k*x)) / k. */ | ||
class GTSAM_EXPORT SoftPlusFunction : public InequalityPenaltyFunction { | ||
public: | ||
typedef InequalityPenaltyFunction Base; | ||
typedef SoftPlusFunction This; | ||
typedef std::shared_ptr<This> shared_ptr; | ||
|
||
protected: | ||
double k_; | ||
|
||
public: | ||
/** Constructor. | ||
* @param k parameter for adjusting the smoothness of the function. | ||
*/ | ||
SoftPlusFunction(const double k = 1) : Base(), k_(k) {} | ||
|
||
virtual double operator()(const double& x, | ||
OptionalJacobian<1, 1> H = {}) const override; | ||
}; | ||
|
||
} // namespace gtsam |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,91 @@ | ||
/* ---------------------------------------------------------------------------- | ||
* GTSAM Copyright 2010, Georgia Tech Research Corporation, | ||
* Atlanta, Georgia 30332-0415 | ||
* All Rights Reserved | ||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list) | ||
* See LICENSE for the license information | ||
* -------------------------------------------------------------------------- */ | ||
|
||
/** | ||
* @file NonlinearConstraint.h | ||
* @brief Nonlinear constraints in constrained optimization. | ||
* @author Yetong Zhang, Frank Dellaert | ||
* @date Aug 3, 2024 | ||
*/ | ||
|
||
#pragma once | ||
|
||
#include <gtsam/inference/FactorGraph.h> | ||
#include <gtsam/inference/FactorGraph-inst.h> | ||
#include <gtsam/nonlinear/NonlinearFactor.h> | ||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION | ||
#include <boost/serialization/base_object.hpp> | ||
#endif | ||
|
||
namespace gtsam { | ||
|
||
/** | ||
* Base class for nonlinear constraint. | ||
* The constraint is represented as a NoiseModelFactor with Constrained noise model. | ||
* whitenedError() returns The constraint violation vector. | ||
* unwhitenedError() returns the sigma-scaled constraint violation vector. | ||
*/ | ||
class GTSAM_EXPORT NonlinearConstraint : public NoiseModelFactor { | ||
public: | ||
typedef NoiseModelFactor Base; | ||
|
||
/** Use constructors of NoiseModelFactor. */ | ||
using Base::Base; | ||
|
||
using NonlinearFactor::error; | ||
|
||
/** Destructor. */ | ||
virtual ~NonlinearConstraint() {} | ||
|
||
/** Create a cost factor representing the L2 penalty function with scaling coefficient mu. */ | ||
virtual NoiseModelFactor::shared_ptr penaltyFactor(const double mu = 1.0) const { | ||
return cloneWithNewNoiseModel(penaltyNoise(mu)); | ||
} | ||
|
||
/** Return the norm of the constraint violation vector. */ | ||
virtual double violation(const Values& x) const { return sqrt(2 * error(x)); } | ||
|
||
/** Check if constraint violation is within tolerance. */ | ||
virtual bool feasible(const Values& x, const double tolerance = 1e-5) const { | ||
return violation(x) <= tolerance; | ||
} | ||
|
||
const Vector sigmas() const { return noiseModel()->sigmas(); } | ||
|
||
// return the hessian of unwhitened error function in each dimension. | ||
virtual std::vector<Matrix> 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 { | ||
return noiseModel::Diagonal::Sigmas(noiseModel()->sigmas() / sqrt(mu)); | ||
} | ||
|
||
/** Default constrained noisemodel used for construction of constraint. */ | ||
static SharedNoiseModel constrainedNoise(const Vector& sigmas) { | ||
return noiseModel::Constrained::MixedSigmas(1.0, sigmas); | ||
} | ||
|
||
private: | ||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION | ||
/** Serialization function */ | ||
friend class boost::serialization::access; | ||
template <class ARCHIVE> | ||
void serialize(ARCHIVE& ar, const unsigned int /*version*/) { | ||
ar& boost::serialization::make_nvp("NonlinearConstraint", | ||
boost::serialization::base_object<Base>(*this)); | ||
} | ||
#endif | ||
}; | ||
|
||
} // namespace gtsam |
Oops, something went wrong.