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

Expose GNC params to python #1239

Merged
merged 24 commits into from
Jul 28, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
24 commits
Select commit Hold shift + click to select a range
aee494a
Expose GNC params to python
amadoantonini Jun 14, 2022
4333f9a
Revert changes to verbosity
amadoantonini Jul 7, 2022
26dd94b
Expose remaining attributes, add tests
amadoantonini Jul 8, 2022
9dd1f8f
Adress review comments
amadoantonini Jul 8, 2022
b4fdda4
Run yapf
amadoantonini Jul 8, 2022
01ea316
Make vector<size_t> opaque
amadoantonini Jul 13, 2022
e381a7c
Revert pybind stl include
amadoantonini Jul 14, 2022
3d37034
wrap custom factor in a separate file
varunagrawal Jul 19, 2022
31d174d
add gtsam namespace
varunagrawal Jul 19, 2022
74678fb
Merge pull request #1 from varunagrawal/custom-factor-separate
amadoantonini Jul 19, 2022
90723d9
Remove pybind/stl.h again
amadoantonini Jul 19, 2022
029631e
Merge branch 'develop' into main
amadoantonini Jul 21, 2022
12b35b4
remove pybind stl.h
varunagrawal Jul 19, 2022
7eb9a95
minor fixes
varunagrawal Jul 22, 2022
c15d288
Merge branch 'develop' into custom-factor-separate
varunagrawal Jul 23, 2022
27951b7
use python 3.7
varunagrawal Jul 26, 2022
4edcb41
remove redundant KeyVector definition
varunagrawal Jul 26, 2022
42bab8f
use KeyVector for GNC inliers & outliers
varunagrawal Jul 26, 2022
1d51c4e
Use new GncParams::IndexVector
varunagrawal Jul 26, 2022
aeceb45
Merge pull request #2 from varunagrawal/gnc/index-vector
amadoantonini Jul 27, 2022
1b614a0
Merge branch 'develop' into main
amadoantonini Jul 27, 2022
a3aaaeb
undo CI changes
varunagrawal Jul 28, 2022
5048886
Merge pull request #3 from varunagrawal/openspacelabs-main
amadoantonini Jul 28, 2022
790403c
revert checkout version
varunagrawal Jul 28, 2022
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
21 changes: 0 additions & 21 deletions gtsam/gtsam.i
Original file line number Diff line number Diff line change
Expand Up @@ -66,27 +66,6 @@ class KeySet {
void serialize() const;
};

// Actually a vector<Key>
class KeyVector {
KeyVector();
KeyVector(const gtsam::KeyVector& other);

// Note: no print function

// common STL methods
size_t size() const;
bool empty() const;
void clear();

// structure specific methods
size_t at(size_t i) const;
size_t front() const;
size_t back() const;
void push_back(size_t key) const;

void serialize() const;
};

// Actually a FastMap<Key,int>
class KeyGroupMap {
KeyGroupMap();
Expand Down
2 changes: 0 additions & 2 deletions gtsam/nonlinear/CustomFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,6 @@

#include <gtsam/nonlinear/NonlinearFactor.h>

using namespace gtsam;

namespace gtsam {

using JacobianVector = std::vector<Matrix>;
Expand Down
16 changes: 11 additions & 5 deletions gtsam/nonlinear/GncParams.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,8 +72,14 @@ class GTSAM_EXPORT GncParams {
double relativeCostTol = 1e-5; ///< If relative cost change is below this threshold, stop iterating
double weightsTol = 1e-4; ///< If the weights are within weightsTol from being binary, stop iterating (only for TLS)
Verbosity verbosity = SILENT; ///< Verbosity level
std::vector<size_t> knownInliers = std::vector<size_t>(); ///< Slots in the factor graph corresponding to measurements that we know are inliers
std::vector<size_t> knownOutliers = std::vector<size_t>(); ///< Slots in the factor graph corresponding to measurements that we know are outliers

//TODO(Varun) replace IndexVector with vector<size_t> once pybind11/stl.h is globally enabled.
/// Use IndexVector for inliers and outliers since it is fast + wrapping
using IndexVector = FastVector<uint64_t>;
///< Slots in the factor graph corresponding to measurements that we know are inliers
IndexVector knownInliers = IndexVector();
///< Slots in the factor graph corresponding to measurements that we know are outliers
IndexVector knownOutliers = IndexVector();

/// Set the robust loss function to be used in GNC (chosen among the ones in GncLossType).
void setLossType(const GncLossType type) {
Expand Down Expand Up @@ -114,7 +120,7 @@ class GTSAM_EXPORT GncParams {
* This functionality is commonly used in SLAM when one may assume the odometry is outlier free, and
* only apply GNC to prune outliers from the loop closures.
* */
void setKnownInliers(const std::vector<size_t>& knownIn) {
void setKnownInliers(const IndexVector& knownIn) {
for (size_t i = 0; i < knownIn.size(); i++){
knownInliers.push_back(knownIn[i]);
}
Expand All @@ -125,7 +131,7 @@ class GTSAM_EXPORT GncParams {
* corresponds to the slots in the factor graph. For instance, if you have a nonlinear factor graph nfg,
* and you provide knownOut = {0, 2, 15}, GNC will not apply outlier rejection to nfg[0], nfg[2], and nfg[15].
* */
void setKnownOutliers(const std::vector<size_t>& knownOut) {
void setKnownOutliers(const IndexVector& knownOut) {
for (size_t i = 0; i < knownOut.size(); i++){
knownOutliers.push_back(knownOut[i]);
}
Expand Down Expand Up @@ -163,7 +169,7 @@ class GTSAM_EXPORT GncParams {
std::cout << "knownInliers: " << knownInliers[i] << "\n";
for (size_t i = 0; i < knownOutliers.size(); i++)
std::cout << "knownOutliers: " << knownOutliers[i] << "\n";
baseOptimizerParams.print(str);
baseOptimizerParams.print("Base optimizer params: ");
}
};

Expand Down
3 changes: 2 additions & 1 deletion gtsam/nonlinear/NonlinearFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,9 @@ boost::shared_ptr<GaussianFactor> NoiseModelFactor::linearize(
return GaussianFactor::shared_ptr(
new JacobianFactor(terms, b,
boost::static_pointer_cast<Constrained>(noiseModel_)->unit()));
else
else {
return GaussianFactor::shared_ptr(new JacobianFactor(terms, b));
}
}

/* ************************************************************************* */
Expand Down
38 changes: 38 additions & 0 deletions gtsam/nonlinear/custom.i
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
//*************************************************************************
// Custom Factor wrapping
//*************************************************************************

namespace gtsam {

#include <gtsam/nonlinear/CustomFactor.h>
virtual class CustomFactor : gtsam::NoiseModelFactor {
/*
* Note CustomFactor will not be wrapped for MATLAB, as there is no supporting
* machinery there. This is achieved by adding `gtsam::CustomFactor` to the
* ignore list in `matlab/CMakeLists.txt`.
*/
CustomFactor();
/*
* Example:
* ```
* def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]):
* <calculated error>
* if not H is None:
* <calculate the Jacobian>
* H[0] = J1 # 2-d numpy array for a Jacobian block
* H[1] = J2
* ...
* return error # 1-d numpy array
*
* cf = CustomFactor(noise_model, keys, error_func)
* ```
*/
CustomFactor(const gtsam::SharedNoiseModel& noiseModel,
const gtsam::KeyVector& keys,
const gtsam::CustomErrorFunction& errorFunction);

void print(string s = "",
gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter);
};

}
68 changes: 32 additions & 36 deletions gtsam/nonlinear/nonlinear.i
Original file line number Diff line number Diff line change
Expand Up @@ -99,11 +99,11 @@ class NonlinearFactorGraph {
string dot(
const gtsam::Values& values,
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
const GraphvizFormatting& writer = GraphvizFormatting());
const gtsam::GraphvizFormatting& writer = gtsam::GraphvizFormatting());
void saveGraph(
const string& s, const gtsam::Values& values,
const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter,
const GraphvizFormatting& writer = GraphvizFormatting()) const;
const gtsam::GraphvizFormatting& writer = gtsam::GraphvizFormatting()) const;

// enabling serialization functionality
void serialize() const;
Expand Down Expand Up @@ -135,37 +135,6 @@ virtual class NoiseModelFactor : gtsam::NonlinearFactor {
Vector whitenedError(const gtsam::Values& x) const;
};

#include <gtsam/nonlinear/CustomFactor.h>
virtual class CustomFactor : gtsam::NoiseModelFactor {
/*
* Note CustomFactor will not be wrapped for MATLAB, as there is no supporting
* machinery there. This is achieved by adding `gtsam::CustomFactor` to the
* ignore list in `matlab/CMakeLists.txt`.
*/
CustomFactor();
/*
* Example:
* ```
* def error_func(this: CustomFactor, v: gtsam.Values, H: List[np.ndarray]):
* <calculated error>
* if not H is None:
* <calculate the Jacobian>
* H[0] = J1 # 2-d numpy array for a Jacobian block
* H[1] = J2
* ...
* return error # 1-d numpy array
*
* cf = CustomFactor(noise_model, keys, error_func)
* ```
*/
CustomFactor(const gtsam::SharedNoiseModel& noiseModel,
const gtsam::KeyVector& keys,
const gtsam::CustomErrorFunction& errorFunction);

void print(string s = "",
gtsam::KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter);
};

#include <gtsam/nonlinear/Values.h>
class Values {
Values();
Expand Down Expand Up @@ -544,12 +513,34 @@ virtual class DoglegParams : gtsam::NonlinearOptimizerParams {
};

#include <gtsam/nonlinear/GncParams.h>
enum GncLossType {
GM /*Geman McClure*/,
TLS /*Truncated least squares*/
};

template<PARAMS>
virtual class GncParams {
GncParams(const PARAMS& baseOptimizerParams);
GncParams();
void setVerbosityGNC(const This::Verbosity value);
void print(const string& str) const;
BaseOptimizerParameters baseOptimizerParams;
gtsam::GncLossType lossType;
size_t maxIterations;
double muStep;
double relativeCostTol;
double weightsTol;
Verbosity verbosity;
gtsam::KeyVector knownInliers;
gtsam::KeyVector knownOutliers;

void setLossType(const gtsam::GncLossType type);
void setMaxIterations(const size_t maxIter);
void setMuStep(const double step);
void setRelativeCostTol(double value);
void setWeightsTol(double value);
void setVerbosityGNC(const gtsam::This::Verbosity value);
void setKnownInliers(const gtsam::KeyVector& knownIn);
void setKnownOutliers(const gtsam::KeyVector& knownOut);
void print(const string& str = "GncParams: ") const;

enum Verbosity {
SILENT,
Expand Down Expand Up @@ -597,6 +588,11 @@ virtual class GncOptimizer {
GncOptimizer(const gtsam::NonlinearFactorGraph& graph,
const gtsam::Values& initialValues,
const PARAMS& params);
void setInlierCostThresholds(const double inth);
const Vector& getInlierCostThresholds();
void setInlierCostThresholdsAtProbability(const double alpha);
void setWeights(const Vector w);
const Vector& getWeights();
gtsam::Values optimize();
};

Expand Down Expand Up @@ -873,7 +869,7 @@ template <T = {gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
gtsam::PinholeCamera<gtsam::Cal3Unified>,
gtsam::imuBias::ConstantBias}>
virtual class NonlinearEquality2 : gtsam::NoiseModelFactor {
NonlinearEquality2(Key key1, Key key2, double mu = 1e4);
NonlinearEquality2(gtsam::Key key1, gtsam::Key key2, double mu = 1e4);
gtsam::Vector evaluateError(const T& x1, const T& x2);
};

Expand Down
1 change: 1 addition & 0 deletions matlab/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ set(interface_files
${GTSAM_SOURCE_DIR}/gtsam/geometry/geometry.i
${GTSAM_SOURCE_DIR}/gtsam/linear/linear.i
${GTSAM_SOURCE_DIR}/gtsam/nonlinear/nonlinear.i
${GTSAM_SOURCE_DIR}/gtsam/nonlinear/custom.i
${GTSAM_SOURCE_DIR}/gtsam/symbolic/symbolic.i
${GTSAM_SOURCE_DIR}/gtsam/sam/sam.i
${GTSAM_SOURCE_DIR}/gtsam/slam/slam.i
Expand Down
1 change: 1 addition & 0 deletions python/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ set(interface_headers
${PROJECT_SOURCE_DIR}/gtsam/geometry/geometry.i
${PROJECT_SOURCE_DIR}/gtsam/linear/linear.i
${PROJECT_SOURCE_DIR}/gtsam/nonlinear/nonlinear.i
${PROJECT_SOURCE_DIR}/gtsam/nonlinear/custom.i
${PROJECT_SOURCE_DIR}/gtsam/symbolic/symbolic.i
${PROJECT_SOURCE_DIR}/gtsam/sam/sam.i
${PROJECT_SOURCE_DIR}/gtsam/slam/slam.i
Expand Down
12 changes: 12 additions & 0 deletions python/gtsam/preamble/custom.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
/* Please refer to:
* https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html
* These are required to save one copy operation on Python calls.
*
* NOTES
* =================
*
* `PYBIND11_MAKE_OPAQUE` will mark the type as "opaque" for the pybind11
* automatic STL binding, such that the raw objects can be accessed in Python.
* Without this they will be automatically converted to a Python object, and all
* mutations on Python side will not be reflected on C++.
*/
2 changes: 1 addition & 1 deletion python/gtsam/preamble/nonlinear.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,4 @@
* automatic STL binding, such that the raw objects can be accessed in Python.
* Without this they will be automatically converted to a Python object, and all
* mutations on Python side will not be reflected on C++.
*/
*/
12 changes: 12 additions & 0 deletions python/gtsam/specializations/custom.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
/* Please refer to:
* https://pybind11.readthedocs.io/en/stable/advanced/cast/stl.html
* These are required to save one copy operation on Python calls.
*
* NOTES
* =================
*
* `py::bind_vector` and similar machinery gives the std container a Python-like
* interface, but without the `<pybind11/stl.h>` copying mechanism. Combined
* with `PYBIND11_MAKE_OPAQUE` this allows the types to be modified with Python,
* and saves one copy operation.
*/
2 changes: 1 addition & 1 deletion python/gtsam/specializations/nonlinear.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,4 @@
* interface, but without the `<pybind11/stl.h>` copying mechanism. Combined
* with `PYBIND11_MAKE_OPAQUE` this allows the types to be modified with Python,
* and saves one copy operation.
*/
*/
Loading