Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Kartik/typedef optional references #1

Open
wants to merge 34 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
34 commits
Select commit Hold shift + click to select a range
7616d12
compile definitions for conditionally compiling
Jan 4, 2023
bc2686b
changed interface for both unwhitenedError and evaluateError
Jan 4, 2023
446720f
breaks
Jan 4, 2023
f705280
works now
Jan 5, 2023
e725744
type checking works now
Jan 5, 2023
9df24ad
type checing in evaluateError works
Jan 5, 2023
981149f
changed signatures to use OptionalMatrix keyword
Jan 5, 2023
66e7cf0
some changes that get testPriorFactor compiling
Jan 6, 2023
c6eb0be
added using keyword to expose the evaluateError overloads to the deri…
Jan 6, 2023
745a7f6
everything compiles but tests fail in no boost mode
Jan 7, 2023
55aac05
both boost and ptr version compile. ptr version tests failt
Jan 7, 2023
a6a722a
optional jacobian fix
Jan 9, 2023
0e99edc
all of gtsam compiles and tests pass with ptrs instead of optional ma…
Jan 9, 2023
42228e9
removed NO_BOOST definitions and evaluateErrorInterface from expressi…
Jan 10, 2023
f0c1888
added some comments and fixed some formatting
Jan 10, 2023
1d75aa2
removed some more boost optional matrix references
Jan 10, 2023
ed5a443
timePose2 updates
Jan 11, 2023
d0b68c3
some more comments
Jan 11, 2023
9038811
gps factor replace bind calls
Jan 11, 2023
73bcd4c
fixing some mr comments. added new lines
Jan 11, 2023
57bbdb9
addressed MR comments on nonlinearfactor
Jan 11, 2023
0ad019e
return before using statement
Jan 11, 2023
988ceb4
use auto instead
Jan 11, 2023
8e5f056
fixed some mr comments: use auto, change comment style
Jan 11, 2023
eafd55e
removed some new lines
Jan 11, 2023
7f567cc
fixed smart factor and camera set for boost optional references
Jan 13, 2023
ccf7064
iterative solver
Jan 13, 2023
6eae8c3
linear algorithms
Jan 13, 2023
e5d62fd
VariableIndex
Jan 13, 2023
763ce71
testGaussian
Jan 13, 2023
fc72ae5
simwall2d
Jan 13, 2023
9439644
testGaussianISAM2 cleanup
Jan 13, 2023
325582c
rewrite evaluateError to use SFINAE instead of conditional compilation
Jan 17, 2023
f95e445
minor reformatting
Jan 18, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ if(NOT DEFINED CMAKE_MACOSX_RPATH)
set(CMAKE_MACOSX_RPATH 0)
endif()

set(CMAKE_CXX_STANDARD 17)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we not do this somewhere else for c++11?


# Set the version number for the library
set (GTSAM_VERSION_MAJOR 4)
set (GTSAM_VERSION_MINOR 2)
Expand Down Expand Up @@ -87,7 +89,7 @@ add_subdirectory(timing)

# Build gtsam_unstable
if (GTSAM_BUILD_UNSTABLE)
add_subdirectory(gtsam_unstable)
add_subdirectory(gtsam_unstable)
endif()

# This is the new wrapper
Expand Down
7 changes: 5 additions & 2 deletions doc/Code/LocalizationFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,14 @@ class UnaryFactor: public NoiseModelFactor1<Pose2> {
double mx_, my_; ///< X and Y measurements

public:

// Provide access to the Matrix& version of evaluateError:
using gtsam::NoiseModelFactor1<Pose2>::evaluateError;

UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}

Vector evaluateError(const Pose2& q,
boost::optional<Matrix&> H = boost::none) const override {
Vector evaluateError(const Pose2& q, OptionalMatrixType H) const override {
const Rot2& R = q.rotation();
if (H) (*H) = (gtsam::Matrix(2, 3) <<
R.c(), -R.s(), 0.0,
Expand Down
5 changes: 2 additions & 3 deletions examples/CameraResectioning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,9 @@ class ResectioningFactor: public NoiseModelFactorN<Pose3> {
}

/// evaluate the error
Vector evaluateError(const Pose3& pose, boost::optional<Matrix&> H =
boost::none) const override {
Vector evaluateError(const Pose3& pose, OptionalMatrixType H) const override {
PinholeCamera<Cal3_S2> camera(pose, *K_);
return camera.project(P_, H, boost::none, boost::none) - p_;
return camera.project(P_, H, OptionalNone, OptionalNone) - p_;
}
};

Expand Down
6 changes: 5 additions & 1 deletion examples/LocalizationExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,10 @@ class UnaryFactor: public NoiseModelFactorN<Pose2> {
double mx_, my_;

public:

// Provide access to Matrix& version of evaluateError:
using NoiseModelFactor1<Pose2>::evaluateError;

/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<UnaryFactor> shared_ptr;

Expand All @@ -84,7 +88,7 @@ class UnaryFactor: public NoiseModelFactorN<Pose2> {
// The first is the 'evaluateError' function. This function implements the desired measurement
// function, returning a vector of errors when evaluated at the provided variable value. It
// must also calculate the Jacobians for this measurement function, if requested.
Vector evaluateError(const Pose2& q, boost::optional<Matrix&> H = boost::none) const override {
Vector evaluateError(const Pose2& q, OptionalMatrixType H) const override {
// The measurement function for a GPS-like measurement h(q) which predicts the measurement (m) is h(q) = q, q = [qx qy qtheta]
// The error is then simply calculated as E(q) = h(q) - m:
// error_x = q.x - mx
Expand Down
6 changes: 4 additions & 2 deletions gtsam/base/OptionalJacobian.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,10 @@ class OptionalJacobian {
/// Constructor that will resize a dynamic matrix (unless already correct)
OptionalJacobian(Eigen::MatrixXd* dynamic) :
map_(nullptr) {
dynamic->resize(Rows, Cols); // no malloc if correct size
usurp(dynamic->data());
if (dynamic) {
dynamic->resize(Rows, Cols); // no malloc if correct size
usurp(dynamic->data());
}
}

/**
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/numericalDerivative.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ namespace gtsam {
*
* Usage of the boost bind version to rearrange arguments:
* for a function with one relevant param and an optional derivative:
* Foo bar(const Obj& a, boost::optional<Matrix&> H1)
* Foo bar(const Obj& a, OptionalMatrixType H1)
* Use boost.bind to restructure:
* std::bind(bar, std::placeholders::_1, boost::none)
* This syntax will fix the optional argument to boost::none, while using the first argument provided
Expand Down
29 changes: 25 additions & 4 deletions gtsam/geometry/CameraSet.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,8 +106,8 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
*/
template <class POINT>
ZVector project2(const POINT& point, //
boost::optional<FBlocks&> Fs = boost::none, //
boost::optional<Matrix&> E = boost::none) const {
FBlocks* Fs = nullptr, //
Matrix* E = nullptr) const {
static const int N = FixedDimension<POINT>::value;

// Allocate result
Expand All @@ -131,14 +131,35 @@ class CameraSet : public std::vector<CAMERA, Eigen::aligned_allocator<CAMERA>> {
return z;
}

/** An overload o the project2 function to accept
* full matrices and vectors and pass it to the pointer
* version of the function
*/
template <class POINT, class... OptArgs>
ZVector project2(const POINT& point, OptArgs&... args) const {
// pass it to the pointer version of the function
return project2(point, (&args)...);
}

/// Calculate vector [project2(point)-z] of re-projection errors
template <class POINT>
Vector reprojectionError(const POINT& point, const ZVector& measured,
boost::optional<FBlocks&> Fs = boost::none, //
boost::optional<Matrix&> E = boost::none) const {
FBlocks* Fs = nullptr, //
Matrix* E = nullptr) const {
return ErrorVector(project2(point, Fs, E), measured);
}

/** An overload o the reprojectionError function to accept
* full matrices and vectors and pass it to the pointer
* version of the function
*/
template <class POINT, class... OptArgs>
Vector reprojectionError(const POINT& point, const ZVector& measured,
OptArgs&... args) const {
// pass it to the pointer version of the function
return reprojectionError(point, measured, (&args)...);
}

/**
* Do Schur complement, given Jacobian as Fs,E,P, return SymmetricBlockMatrix
* G = F' * F - F' * E * P * E' * F
Expand Down
3 changes: 1 addition & 2 deletions gtsam/inference/VariableIndex-inl.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,7 @@ namespace gtsam {

/* ************************************************************************* */
template<class FG>
void VariableIndex::augment(const FG& factors,
boost::optional<const FactorIndices&> newFactorIndices) {
void VariableIndex::augment(const FG& factors, const FactorIndices* newFactorIndices) {
gttic(VariableIndex_augment);

// Augment index for each factor
Expand Down
11 changes: 10 additions & 1 deletion gtsam/inference/VariableIndex.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,16 @@ class GTSAM_EXPORT VariableIndex {
* solving problems incrementally.
*/
template<class FG>
void augment(const FG& factors, boost::optional<const FactorIndices&> newFactorIndices = boost::none);
void augment(const FG& factors, const FactorIndices* newFactorIndices = nullptr);

/**
* An overload of augment() that takes a single factor. and l-value
* reference to FactorIndeces.
*/
template<class FG>
void augment(const FG& factor, const FactorIndices& newFactorIndices) {
augment(factor, &newFactorIndices);
}

/**
* Augment the variable index after an existing factor now affects to more
Expand Down
3 changes: 1 addition & 2 deletions gtsam/linear/IterativeSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,8 +84,7 @@ string IterativeOptimizationParameters::verbosityTranslator(

/*****************************************************************************/
VectorValues IterativeSolver::optimize(const GaussianFactorGraph &gfg,
boost::optional<const KeyInfo&> keyInfo,
boost::optional<const std::map<Key, Vector>&> lambda) {
const KeyInfo* keyInfo, const std::map<Key, Vector>* lambda) {
return optimize(gfg, keyInfo ? *keyInfo : KeyInfo(gfg),
lambda ? *lambda : std::map<Key, Vector>());
}
Expand Down
4 changes: 2 additions & 2 deletions gtsam/linear/IterativeSolver.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,8 +93,8 @@ class IterativeSolver {

/* interface to the nonlinear optimizer, without metadata, damping and initial estimate */
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg,
boost::optional<const KeyInfo&> = boost::none,
boost::optional<const std::map<Key, Vector>&> lambda = boost::none);
const KeyInfo* = nullptr,
const std::map<Key, Vector>* lambda = nullptr);

/* interface to the nonlinear optimizer, without initial estimate */
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo,
Expand Down
7 changes: 4 additions & 3 deletions gtsam/linear/linearAlgorithms-inst.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,10 @@
#include <gtsam/linear/GaussianConditional.h>
#include <gtsam/base/treeTraversal-inst.h>

#include <boost/optional.hpp>
#include <boost/shared_ptr.hpp>

#include <optional>

namespace gtsam
{
namespace internal
Expand All @@ -32,7 +33,7 @@ namespace gtsam
{
/* ************************************************************************* */
struct OptimizeData {
boost::optional<OptimizeData&> parentData;
OptimizeData* parentData = nullptr;
FastMap<Key, VectorValues::const_iterator> cliqueResults;
//VectorValues ancestorResults;
//VectorValues results;
Expand All @@ -55,7 +56,7 @@ namespace gtsam
OptimizeData& parentData)
{
OptimizeData myData;
myData.parentData = parentData;
myData.parentData = &parentData;
// Take any ancestor results we'll need
for(Key parent: clique->conditional_->parents())
myData.cliqueResults.emplace(parent, myData.parentData->cliqueResults.at(parent));
Expand Down
4 changes: 2 additions & 2 deletions gtsam/navigation/AHRSFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,8 @@ bool AHRSFactor::equals(const NonlinearFactor& other, double tol) const {

//------------------------------------------------------------------------------
Vector AHRSFactor::evaluateError(const Rot3& Ri, const Rot3& Rj,
const Vector3& bias, boost::optional<Matrix&> H1,
boost::optional<Matrix&> H2, boost::optional<Matrix&> H3) const {
const Vector3& bias, OptionalMatrixType H1,
OptionalMatrixType H2, OptionalMatrixType H3) const {

// Do bias correction, if (H3) will contain 3*3 derivative used below
const Vector3 biascorrectedOmega = _PIM_.predict(bias, H3);
Expand Down
8 changes: 5 additions & 3 deletions gtsam/navigation/AHRSFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,9 @@ class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {

public:

// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;

/** Shorthand for a smart pointer to a factor */
#if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
typedef typename boost::shared_ptr<AHRSFactor> shared_ptr;
Expand Down Expand Up @@ -179,9 +182,8 @@ class GTSAM_EXPORT AHRSFactor: public NoiseModelFactorN<Rot3, Rot3, Vector3> {

/// vector of errors
Vector evaluateError(const Rot3& rot_i, const Rot3& rot_j,
const Vector3& bias, boost::optional<Matrix&> H1 = boost::none,
boost::optional<Matrix&> H2 = boost::none, boost::optional<Matrix&> H3 =
boost::none) const override;
const Vector3& bias, OptionalMatrixType H1,
OptionalMatrixType H2, OptionalMatrixType H3) const override;

/// predicted states from IMU
/// TODO(frank): relationship with PIM predict ??
Expand Down
12 changes: 8 additions & 4 deletions gtsam/navigation/AttitudeFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,9 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public At

public:

// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;

/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<Rot3AttitudeFactor> shared_ptr;

Expand Down Expand Up @@ -121,8 +124,7 @@ class GTSAM_EXPORT Rot3AttitudeFactor: public NoiseModelFactorN<Rot3>, public At
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;

/** vector of errors */
Vector evaluateError(const Rot3& nRb, //
boost::optional<Matrix&> H = boost::none) const override {
Vector evaluateError(const Rot3& nRb, OptionalMatrixType H) const override {
return attitudeError(nRb, H);
}

Expand Down Expand Up @@ -157,6 +159,9 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,

public:

// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;

/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<Pose3AttitudeFactor> shared_ptr;

Expand Down Expand Up @@ -196,8 +201,7 @@ class GTSAM_EXPORT Pose3AttitudeFactor: public NoiseModelFactorN<Pose3>,
bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;

/** vector of errors */
Vector evaluateError(const Pose3& nTb, //
boost::optional<Matrix&> H = boost::none) const override {
Vector evaluateError(const Pose3& nTb, OptionalMatrixType H) const override {
Vector e = attitudeError(nTb.rotation(), H);
if (H) {
Matrix H23 = *H;
Expand Down
4 changes: 2 additions & 2 deletions gtsam/navigation/BarometricFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,8 @@ bool BarometricFactor::equals(const NonlinearFactor& expected,

//***************************************************************************
Vector BarometricFactor::evaluateError(const Pose3& p, const double& bias,
boost::optional<Matrix&> H,
boost::optional<Matrix&> H2) const {
OptionalMatrixType H,
OptionalMatrixType H2) const {
Matrix tH;
Vector ret = (Vector(1) << (p.translation(tH).z() + bias - nT_)).finished();
if (H) (*H) = tH.block<1, 6>(2, 0);
Expand Down
10 changes: 6 additions & 4 deletions gtsam/navigation/BarometricFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,10 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
double nT_; ///< Height Measurement based on a standard atmosphere

public:

// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;

/// shorthand for a smart pointer to a factor
typedef boost::shared_ptr<BarometricFactor> shared_ptr;

Expand Down Expand Up @@ -76,10 +80,8 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN<Pose3, double> {
double tol = 1e-9) const override;

/// vector of errors
Vector evaluateError(
const Pose3& p, const double& b,
boost::optional<Matrix&> H = boost::none,
boost::optional<Matrix&> H2 = boost::none) const override;
Vector evaluateError(const Pose3& p, const double& b,
OptionalMatrixType H, OptionalMatrixType H2) const override;

inline const double& measurementIn() const { return nT_; }

Expand Down
6 changes: 3 additions & 3 deletions gtsam/navigation/CombinedImuFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,9 +222,9 @@ bool CombinedImuFactor::equals(const NonlinearFactor& other, double tol) const {
Vector CombinedImuFactor::evaluateError(const Pose3& pose_i,
const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j,
const imuBias::ConstantBias& bias_i, const imuBias::ConstantBias& bias_j,
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2,
boost::optional<Matrix&> H3, boost::optional<Matrix&> H4,
boost::optional<Matrix&> H5, boost::optional<Matrix&> H6) const {
OptionalMatrixType H1, OptionalMatrixType H2,
OptionalMatrixType H3, OptionalMatrixType H4,
OptionalMatrixType H5, OptionalMatrixType H6) const {

// error wrt bias evolution model (random walk)
Matrix6 Hbias_i, Hbias_j;
Expand Down
10 changes: 6 additions & 4 deletions gtsam/navigation/CombinedImuFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,9 @@ class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, P

public:

// Provide access to Matrix& version of evaluateError:
using Base::evaluateError;

/** Shorthand for a smart pointer to a factor */
#if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
typedef typename boost::shared_ptr<CombinedImuFactor> shared_ptr;
Expand Down Expand Up @@ -324,10 +327,9 @@ class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, P
Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
const Pose3& pose_j, const Vector3& vel_j,
const imuBias::ConstantBias& bias_i, const imuBias::ConstantBias& bias_j,
boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
boost::none, boost::optional<Matrix&> H3 = boost::none,
boost::optional<Matrix&> H4 = boost::none, boost::optional<Matrix&> H5 =
boost::none, boost::optional<Matrix&> H6 = boost::none) const override;
OptionalMatrixType H1, OptionalMatrixType H2,
OptionalMatrixType H3, OptionalMatrixType H4,
OptionalMatrixType H5, OptionalMatrixType H6) const override;

private:
/** Serialization function */
Expand Down
8 changes: 5 additions & 3 deletions gtsam/navigation/ConstantVelocityFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,10 @@ class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
double dt_;

public:
using Base = NoiseModelFactorN<NavState, NavState>;
using Base = NoiseModelFactor2<NavState, NavState>;

// Provide access to the Matrix& version of evaluateError:
using Base::evaluateError;

public:
ConstantVelocityFactor(Key i, Key j, double dt, const SharedNoiseModel &model)
Expand All @@ -48,8 +51,7 @@ class ConstantVelocityFactor : public NoiseModelFactorN<NavState, NavState> {
* @return * Vector
*/
gtsam::Vector evaluateError(const NavState &x1, const NavState &x2,
boost::optional<gtsam::Matrix &> H1 = boost::none,
boost::optional<gtsam::Matrix &> H2 = boost::none) const override {
OptionalMatrixType H1, OptionalMatrixType H2) const override {
// only used to use update() below
static const Vector3 b_accel{0.0, 0.0, 0.0};
static const Vector3 b_omega{0.0, 0.0, 0.0};
Expand Down
Loading