Fix windows test
parent
0f7bc5cf2d
commit
62d59c62d4
|
@ -99,26 +99,64 @@ jobs:
|
||||||
cmake -B build -S . -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DBOOST_ROOT="${env:BOOST_ROOT}" -DBOOST_INCLUDEDIR="${env:BOOST_ROOT}\boost\include" -DBOOST_LIBRARYDIR="${env:BOOST_ROOT}\lib"
|
cmake -B build -S . -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DBOOST_ROOT="${env:BOOST_ROOT}" -DBOOST_INCLUDEDIR="${env:BOOST_ROOT}\boost\include" -DBOOST_LIBRARYDIR="${env:BOOST_ROOT}\lib"
|
||||||
|
|
||||||
- name: Build
|
- name: Build
|
||||||
|
shell: cmd
|
||||||
run: |
|
run: |
|
||||||
# Since Visual Studio is a multi-generator, we need to use --config
|
:: Since Visual Studio is a multi-generator, we need to use --config
|
||||||
# https://stackoverflow.com/a/24470998/1236990
|
:: https://stackoverflow.com/a/24470998/1236990
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target gtsam
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target gtsam_unstable
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target gtsam_unstable
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target wrap
|
|
||||||
|
|
||||||
# Run GTSAM tests
|
:: Target doesn't exist
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target wrap
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.basis
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.discrete
|
|
||||||
#cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.geometry
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.inference
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.linear
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.navigation
|
|
||||||
#cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.nonlinear
|
|
||||||
#cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sam
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.sfm
|
|
||||||
#cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.slam
|
|
||||||
cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.symbolic
|
|
||||||
|
|
||||||
# Run GTSAM_UNSTABLE tests
|
- name: Test
|
||||||
#cmake --build build -j 4 --config ${{ matrix.build_type }} --target check.base_unstable
|
shell: cmd
|
||||||
|
run: |
|
||||||
|
:: Run GTSAM tests
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.base
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.basis
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.discrete
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.geometry
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.inference
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.linear
|
||||||
|
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.navigation
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.sam
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.sfm
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.symbolic
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.hybrid
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.nonlinear
|
||||||
|
|
||||||
|
:: Compilation error
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.slam
|
||||||
|
|
||||||
|
|
||||||
|
:: Run GTSAM_UNSTABLE tests
|
||||||
|
cmake --build build -j4 --config ${{ matrix.build_type }} --target check.base_unstable
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.geometry_unstable
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.linear_unstable
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.discrete_unstable
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.dynamics_unstable
|
||||||
|
|
||||||
|
:: Compile. Fail with exception
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.nonlinear_unstable
|
||||||
|
|
||||||
|
:: Compilation error
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.slam_unstable
|
||||||
|
|
||||||
|
:: Compilation error
|
||||||
|
:: cmake --build build -j4 --config ${{ matrix.build_type }} --target check.partition
|
||||||
|
|
|
@ -32,6 +32,14 @@ set (CMAKE_PROJECT_VERSION_PATCH ${GTSAM_VERSION_PATCH})
|
||||||
###############################################################################
|
###############################################################################
|
||||||
# Gather information, perform checks, set defaults
|
# Gather information, perform checks, set defaults
|
||||||
|
|
||||||
|
if(MSVC)
|
||||||
|
set(MSVC_LINKER_FLAGS "/FORCE:MULTIPLE")
|
||||||
|
set(CMAKE_EXE_LINKER_FLAGS ${MSVC_LINKER_FLAGS})
|
||||||
|
set(CMAKE_MODULE_LINKER_FLAGS ${MSVC_LINKER_FLAGS})
|
||||||
|
set(CMAKE_SHARED_LINKER_FLAGS ${MSVC_LINKER_FLAGS})
|
||||||
|
set(CMAKE_STATIC_LINKER_FLAGS ${MSVC_LINKER_FLAGS})
|
||||||
|
endif()
|
||||||
|
|
||||||
set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
|
set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
|
||||||
include(GtsamMakeConfigFile)
|
include(GtsamMakeConfigFile)
|
||||||
include(GNUInstallDirs)
|
include(GNUInstallDirs)
|
||||||
|
|
|
@ -80,7 +80,7 @@ using Weights = Eigen::Matrix<double, 1, -1>; /* 1xN vector */
|
||||||
*
|
*
|
||||||
* @ingroup basis
|
* @ingroup basis
|
||||||
*/
|
*/
|
||||||
Matrix kroneckerProductIdentity(size_t M, const Weights& w);
|
Matrix GTSAM_EXPORT kroneckerProductIdentity(size_t M, const Weights& w);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* CRTP Base class for function bases
|
* CRTP Base class for function bases
|
||||||
|
|
|
@ -22,6 +22,8 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
|
#include <gtsam/dllexport.h>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
/**
|
/**
|
||||||
* @brief A simple parser that replaces the boost spirit parser.
|
* @brief A simple parser that replaces the boost spirit parser.
|
||||||
|
@ -47,7 +49,7 @@ namespace gtsam {
|
||||||
*
|
*
|
||||||
* Also fails if the rows are not of the same size.
|
* Also fails if the rows are not of the same size.
|
||||||
*/
|
*/
|
||||||
struct SignatureParser {
|
struct GTSAM_EXPORT SignatureParser {
|
||||||
using Row = std::vector<double>;
|
using Row = std::vector<double>;
|
||||||
using Table = std::vector<Row>;
|
using Table = std::vector<Row>;
|
||||||
|
|
||||||
|
|
|
@ -146,7 +146,7 @@ class GTSAM_EXPORT Line3 {
|
||||||
* @param Dline - OptionalJacobian of transformed line with respect to l
|
* @param Dline - OptionalJacobian of transformed line with respect to l
|
||||||
* @return Transformed line in camera frame
|
* @return Transformed line in camera frame
|
||||||
*/
|
*/
|
||||||
friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
|
GTSAM_EXPORT friend Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
|
||||||
OptionalJacobian<4, 6> Dpose,
|
OptionalJacobian<4, 6> Dpose,
|
||||||
OptionalJacobian<4, 4> Dline);
|
OptionalJacobian<4, 4> Dline);
|
||||||
};
|
};
|
||||||
|
|
|
@ -36,7 +36,7 @@ namespace gtsam {
|
||||||
* @ingroup geometry
|
* @ingroup geometry
|
||||||
* \nosubgrouping
|
* \nosubgrouping
|
||||||
*/
|
*/
|
||||||
class Pose2: public LieGroup<Pose2, 3> {
|
class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
@ -112,10 +112,10 @@ public:
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
/** print with optional string */
|
/** print with optional string */
|
||||||
GTSAM_EXPORT void print(const std::string& s = "") const;
|
void print(const std::string& s = "") const;
|
||||||
|
|
||||||
/** assert equality up to a tolerance */
|
/** assert equality up to a tolerance */
|
||||||
GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const;
|
bool equals(const Pose2& pose, double tol = 1e-9) const;
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
/// @name Group
|
/// @name Group
|
||||||
|
@ -125,7 +125,7 @@ public:
|
||||||
inline static Pose2 Identity() { return Pose2(); }
|
inline static Pose2 Identity() { return Pose2(); }
|
||||||
|
|
||||||
/// inverse
|
/// inverse
|
||||||
GTSAM_EXPORT Pose2 inverse() const;
|
Pose2 inverse() const;
|
||||||
|
|
||||||
/// compose syntactic sugar
|
/// compose syntactic sugar
|
||||||
inline Pose2 operator*(const Pose2& p2) const {
|
inline Pose2 operator*(const Pose2& p2) const {
|
||||||
|
@ -137,16 +137,16 @@ public:
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$
|
///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$
|
||||||
GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {});
|
static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {});
|
||||||
|
|
||||||
///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation
|
///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation
|
||||||
GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = {});
|
static Vector3 Logmap(const Pose2& p, ChartJacobian H = {});
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Calculate Adjoint map
|
* Calculate Adjoint map
|
||||||
* Ad_pose is 3*3 matrix that when applied to twist xi \f$ [T_x,T_y,\theta] \f$, returns Ad_pose(xi)
|
* Ad_pose is 3*3 matrix that when applied to twist xi \f$ [T_x,T_y,\theta] \f$, returns Ad_pose(xi)
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT Matrix3 AdjointMap() const;
|
Matrix3 AdjointMap() const;
|
||||||
|
|
||||||
/// Apply AdjointMap to twist xi
|
/// Apply AdjointMap to twist xi
|
||||||
inline Vector3 Adjoint(const Vector3& xi) const {
|
inline Vector3 Adjoint(const Vector3& xi) const {
|
||||||
|
@ -156,7 +156,7 @@ public:
|
||||||
/**
|
/**
|
||||||
* Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19
|
* Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v);
|
static Matrix3 adjointMap(const Vector3& v);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Action of the adjointMap on a Lie-algebra vector y, with optional derivatives
|
* Action of the adjointMap on a Lie-algebra vector y, with optional derivatives
|
||||||
|
@ -192,15 +192,15 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Derivative of Expmap
|
/// Derivative of Expmap
|
||||||
GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v);
|
static Matrix3 ExpmapDerivative(const Vector3& v);
|
||||||
|
|
||||||
/// Derivative of Logmap
|
/// Derivative of Logmap
|
||||||
GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v);
|
static Matrix3 LogmapDerivative(const Pose2& v);
|
||||||
|
|
||||||
// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
|
// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
|
||||||
struct ChartAtOrigin {
|
struct GTSAM_EXPORT ChartAtOrigin {
|
||||||
GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = {});
|
static Pose2 Retract(const Vector3& v, ChartJacobian H = {});
|
||||||
GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = {});
|
static Vector3 Local(const Pose2& r, ChartJacobian H = {});
|
||||||
};
|
};
|
||||||
|
|
||||||
using LieGroup<Pose2, 3>::inverse; // version with derivative
|
using LieGroup<Pose2, 3>::inverse; // version with derivative
|
||||||
|
@ -210,7 +210,7 @@ public:
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
/** Return point coordinates in pose coordinate frame */
|
/** Return point coordinates in pose coordinate frame */
|
||||||
GTSAM_EXPORT Point2 transformTo(const Point2& point,
|
Point2 transformTo(const Point2& point,
|
||||||
OptionalJacobian<2, 3> Dpose = {},
|
OptionalJacobian<2, 3> Dpose = {},
|
||||||
OptionalJacobian<2, 2> Dpoint = {}) const;
|
OptionalJacobian<2, 2> Dpoint = {}) const;
|
||||||
|
|
||||||
|
@ -222,7 +222,7 @@ public:
|
||||||
Matrix transformTo(const Matrix& points) const;
|
Matrix transformTo(const Matrix& points) const;
|
||||||
|
|
||||||
/** Return point coordinates in global frame */
|
/** Return point coordinates in global frame */
|
||||||
GTSAM_EXPORT Point2 transformFrom(const Point2& point,
|
Point2 transformFrom(const Point2& point,
|
||||||
OptionalJacobian<2, 3> Dpose = {},
|
OptionalJacobian<2, 3> Dpose = {},
|
||||||
OptionalJacobian<2, 2> Dpoint = {}) const;
|
OptionalJacobian<2, 2> Dpoint = {}) const;
|
||||||
|
|
||||||
|
@ -273,14 +273,14 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
//// return transformation matrix
|
//// return transformation matrix
|
||||||
GTSAM_EXPORT Matrix3 matrix() const;
|
Matrix3 matrix() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Calculate bearing to a landmark
|
* Calculate bearing to a landmark
|
||||||
* @param point 2D location of landmark
|
* @param point 2D location of landmark
|
||||||
* @return 2D rotation \f$ \in SO(2) \f$
|
* @return 2D rotation \f$ \in SO(2) \f$
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT Rot2 bearing(const Point2& point,
|
Rot2 bearing(const Point2& point,
|
||||||
OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const;
|
OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -288,7 +288,7 @@ public:
|
||||||
* @param point SO(2) location of other pose
|
* @param point SO(2) location of other pose
|
||||||
* @return 2D rotation \f$ \in SO(2) \f$
|
* @return 2D rotation \f$ \in SO(2) \f$
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT Rot2 bearing(const Pose2& pose,
|
Rot2 bearing(const Pose2& pose,
|
||||||
OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const;
|
OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -296,7 +296,7 @@ public:
|
||||||
* @param point 2D location of landmark
|
* @param point 2D location of landmark
|
||||||
* @return range (double)
|
* @return range (double)
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT double range(const Point2& point,
|
double range(const Point2& point,
|
||||||
OptionalJacobian<1, 3> H1={},
|
OptionalJacobian<1, 3> H1={},
|
||||||
OptionalJacobian<1, 2> H2={}) const;
|
OptionalJacobian<1, 2> H2={}) const;
|
||||||
|
|
||||||
|
@ -305,7 +305,7 @@ public:
|
||||||
* @param point 2D location of other pose
|
* @param point 2D location of other pose
|
||||||
* @return range (double)
|
* @return range (double)
|
||||||
*/
|
*/
|
||||||
GTSAM_EXPORT double range(const Pose2& point,
|
double range(const Pose2& point,
|
||||||
OptionalJacobian<1, 3> H1={},
|
OptionalJacobian<1, 3> H1={},
|
||||||
OptionalJacobian<1, 3> H2={}) const;
|
OptionalJacobian<1, 3> H2={}) const;
|
||||||
|
|
||||||
|
|
|
@ -204,7 +204,7 @@ public:
|
||||||
static Matrix6 LogmapDerivative(const Pose3& xi);
|
static Matrix6 LogmapDerivative(const Pose3& xi);
|
||||||
|
|
||||||
// Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP
|
// Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP
|
||||||
struct ChartAtOrigin {
|
struct GTSAM_EXPORT ChartAtOrigin {
|
||||||
static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = {});
|
static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = {});
|
||||||
static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = {});
|
static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = {});
|
||||||
};
|
};
|
||||||
|
|
|
@ -35,7 +35,7 @@ using SharedFactor = std::shared_ptr<Factor>;
|
||||||
* Hybrid Factor Graph
|
* Hybrid Factor Graph
|
||||||
* Factor graph with utilities for hybrid factors.
|
* Factor graph with utilities for hybrid factors.
|
||||||
*/
|
*/
|
||||||
class HybridFactorGraph : public FactorGraph<Factor> {
|
class GTSAM_EXPORT HybridFactorGraph : public FactorGraph<Factor> {
|
||||||
public:
|
public:
|
||||||
using Base = FactorGraph<Factor>;
|
using Base = FactorGraph<Factor>;
|
||||||
using This = HybridFactorGraph; ///< this class
|
using This = HybridFactorGraph; ///< this class
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
class HybridSmoother {
|
class GTSAM_EXPORT HybridSmoother {
|
||||||
private:
|
private:
|
||||||
HybridBayesNet hybridBayesNet_;
|
HybridBayesNet hybridBayesNet_;
|
||||||
HybridGaussianFactorGraph remainingFactorGraph_;
|
HybridGaussianFactorGraph remainingFactorGraph_;
|
||||||
|
|
|
@ -43,6 +43,7 @@
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <iterator>
|
#include <iterator>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
#include <numeric>
|
||||||
|
|
||||||
#include "Switching.h"
|
#include "Switching.h"
|
||||||
#include "TinyHybridExample.h"
|
#include "TinyHybridExample.h"
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
class Ordering: public KeyVector {
|
class GTSAM_EXPORT Ordering: public KeyVector {
|
||||||
protected:
|
protected:
|
||||||
typedef KeyVector Base;
|
typedef KeyVector Base;
|
||||||
|
|
||||||
|
@ -44,8 +44,7 @@ public:
|
||||||
typedef Ordering This; ///< Typedef to this class
|
typedef Ordering This; ///< Typedef to this class
|
||||||
typedef std::shared_ptr<This> shared_ptr; ///< shared_ptr to this class
|
typedef std::shared_ptr<This> shared_ptr; ///< shared_ptr to this class
|
||||||
|
|
||||||
/// Create an empty ordering
|
/// Create an empty ordering
|
||||||
GTSAM_EXPORT
|
|
||||||
Ordering() {
|
Ordering() {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -99,7 +98,7 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Compute a fill-reducing ordering using COLAMD from a VariableIndex.
|
/// Compute a fill-reducing ordering using COLAMD from a VariableIndex.
|
||||||
static GTSAM_EXPORT Ordering Colamd(const VariableIndex& variableIndex);
|
static Ordering Colamd(const VariableIndex& variableIndex);
|
||||||
|
|
||||||
/// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details
|
/// Compute a fill-reducing ordering using constrained COLAMD from a factor graph (see details
|
||||||
/// for note on performance). This internally builds a VariableIndex so if you already have a
|
/// for note on performance). This internally builds a VariableIndex so if you already have a
|
||||||
|
@ -124,7 +123,7 @@ public:
|
||||||
/// variables in \c constrainLast will be ordered in the same order specified in the KeyVector
|
/// variables in \c constrainLast will be ordered in the same order specified in the KeyVector
|
||||||
/// \c constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be
|
/// \c constrainLast. If \c forceOrder is false, the variables in \c constrainLast will be
|
||||||
/// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well.
|
/// ordered after all the others, but will be rearranged by CCOLAMD to reduce fill-in as well.
|
||||||
static GTSAM_EXPORT Ordering ColamdConstrainedLast(
|
static Ordering ColamdConstrainedLast(
|
||||||
const VariableIndex& variableIndex, const KeyVector& constrainLast,
|
const VariableIndex& variableIndex, const KeyVector& constrainLast,
|
||||||
bool forceOrder = false);
|
bool forceOrder = false);
|
||||||
|
|
||||||
|
@ -152,7 +151,7 @@ public:
|
||||||
/// KeyVector \c constrainFirst. If \c forceOrder is false, the variables in \c
|
/// KeyVector \c constrainFirst. If \c forceOrder is false, the variables in \c
|
||||||
/// constrainFirst will be ordered before all the others, but will be rearranged by CCOLAMD to
|
/// constrainFirst will be ordered before all the others, but will be rearranged by CCOLAMD to
|
||||||
/// reduce fill-in as well.
|
/// reduce fill-in as well.
|
||||||
static GTSAM_EXPORT Ordering ColamdConstrainedFirst(
|
static Ordering ColamdConstrainedFirst(
|
||||||
const VariableIndex& variableIndex,
|
const VariableIndex& variableIndex,
|
||||||
const KeyVector& constrainFirst, bool forceOrder = false);
|
const KeyVector& constrainFirst, bool forceOrder = false);
|
||||||
|
|
||||||
|
@ -181,7 +180,7 @@ public:
|
||||||
/// appear in \c groups in arbitrary order. Any variables not present in \c groups will be
|
/// appear in \c groups in arbitrary order. Any variables not present in \c groups will be
|
||||||
/// assigned to group 0. This function simply fills the \c cmember argument to CCOLAMD with the
|
/// assigned to group 0. This function simply fills the \c cmember argument to CCOLAMD with the
|
||||||
/// supplied indices, see the CCOLAMD documentation for more information.
|
/// supplied indices, see the CCOLAMD documentation for more information.
|
||||||
static GTSAM_EXPORT Ordering ColamdConstrained(
|
static Ordering ColamdConstrained(
|
||||||
const VariableIndex& variableIndex, const FastMap<Key, int>& groups);
|
const VariableIndex& variableIndex, const FastMap<Key, int>& groups);
|
||||||
|
|
||||||
/// Return a natural Ordering. Typically used by iterative solvers
|
/// Return a natural Ordering. Typically used by iterative solvers
|
||||||
|
@ -195,11 +194,11 @@ public:
|
||||||
|
|
||||||
/// METIS Formatting function
|
/// METIS Formatting function
|
||||||
template<class FACTOR_GRAPH>
|
template<class FACTOR_GRAPH>
|
||||||
static GTSAM_EXPORT void CSRFormat(std::vector<int>& xadj,
|
static void CSRFormat(std::vector<int>& xadj,
|
||||||
std::vector<int>& adj, const FACTOR_GRAPH& graph);
|
std::vector<int>& adj, const FACTOR_GRAPH& graph);
|
||||||
|
|
||||||
/// Compute an ordering determined by METIS from a VariableIndex
|
/// Compute an ordering determined by METIS from a VariableIndex
|
||||||
static GTSAM_EXPORT Ordering Metis(const MetisIndex& met);
|
static Ordering Metis(const MetisIndex& met);
|
||||||
|
|
||||||
template<class FACTOR_GRAPH>
|
template<class FACTOR_GRAPH>
|
||||||
static Ordering Metis(const FACTOR_GRAPH& graph) {
|
static Ordering Metis(const FACTOR_GRAPH& graph) {
|
||||||
|
@ -241,18 +240,16 @@ public:
|
||||||
/// @name Testable
|
/// @name Testable
|
||||||
/// @{
|
/// @{
|
||||||
|
|
||||||
GTSAM_EXPORT
|
|
||||||
void print(const std::string& str = "", const KeyFormatter& keyFormatter =
|
void print(const std::string& str = "", const KeyFormatter& keyFormatter =
|
||||||
DefaultKeyFormatter) const;
|
DefaultKeyFormatter) const;
|
||||||
|
|
||||||
GTSAM_EXPORT
|
|
||||||
bool equals(const Ordering& other, double tol = 1e-9) const;
|
bool equals(const Ordering& other, double tol = 1e-9) const;
|
||||||
|
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Internal COLAMD function
|
/// Internal COLAMD function
|
||||||
static GTSAM_EXPORT Ordering ColamdConstrained(
|
static Ordering ColamdConstrained(
|
||||||
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
const VariableIndex& variableIndex, std::vector<int>& cmember);
|
||||||
|
|
||||||
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
#ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
|
||||||
|
|
|
@ -19,6 +19,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <gtsam_unstable/dllexport.h>
|
||||||
#include <gtsam_unstable/linear/LP.h>
|
#include <gtsam_unstable/linear/LP.h>
|
||||||
#include <gtsam/linear/GaussianFactorGraph.h>
|
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||||
|
|
||||||
|
@ -49,7 +50,7 @@ namespace gtsam {
|
||||||
* inequality constraint, we can't conclude that the problem is infeasible.
|
* inequality constraint, we can't conclude that the problem is infeasible.
|
||||||
* However, whether it is infeasible or unbounded, we don't have a unique solution anyway.
|
* However, whether it is infeasible or unbounded, we don't have a unique solution anyway.
|
||||||
*/
|
*/
|
||||||
class LPInitSolver {
|
class GTSAM_UNSTABLE_EXPORT LPInitSolver {
|
||||||
private:
|
private:
|
||||||
const LP& lp_;
|
const LP& lp_;
|
||||||
|
|
||||||
|
|
|
@ -18,12 +18,13 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <gtsam_unstable/dllexport.h>
|
||||||
#include <gtsam_unstable/linear/QP.h>
|
#include <gtsam_unstable/linear/QP.h>
|
||||||
#include <fstream>
|
#include <fstream>
|
||||||
|
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
class QPSParser {
|
class GTSAM_UNSTABLE_EXPORT QPSParser {
|
||||||
|
|
||||||
private:
|
private:
|
||||||
std::string fileName_;
|
std::string fileName_;
|
||||||
|
|
Loading…
Reference in New Issue