Merge branch 'develop' into main

release/4.3a0
Amado Antonini 2022-07-27 12:04:24 -04:00
commit 1b614a0bd9
32 changed files with 102 additions and 76 deletions

View File

@ -43,46 +43,68 @@ if [ -z ${PYTHON_VERSION+x} ]; then
exit 127
fi
PYTHON="python${PYTHON_VERSION}"
export PYTHON="python${PYTHON_VERSION}"
if [[ $(uname) == "Darwin" ]]; then
function install_dependencies()
{
if [[ $(uname) == "Darwin" ]]; then
brew install wget
else
else
# Install a system package required by our library
sudo apt-get install -y wget libicu-dev python3-pip python3-setuptools
fi
fi
PATH=$PATH:$($PYTHON -c "import site; print(site.USER_BASE)")/bin
export PATH=$PATH:$($PYTHON -c "import site; print(site.USER_BASE)")/bin
[ "${GTSAM_WITH_TBB:-OFF}" = "ON" ] && install_tbb
[ "${GTSAM_WITH_TBB:-OFF}" = "ON" ] && install_tbb
$PYTHON -m pip install -r $GITHUB_WORKSPACE/python/requirements.txt
}
function build()
{
mkdir $GITHUB_WORKSPACE/build
cd $GITHUB_WORKSPACE/build
BUILD_PYBIND="ON"
cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} \
-DGTSAM_BUILD_TESTS=OFF \
-DGTSAM_BUILD_UNSTABLE=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_USE_QUATERNIONS=OFF \
-DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \
-DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \
-DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \
-DGTSAM_BUILD_PYTHON=${BUILD_PYBIND} \
-DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \
-DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \
-DGTSAM_ALLOW_DEPRECATED_SINCE_V42=OFF \
-DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install
BUILD_PYBIND="ON"
# Set to 2 cores so that Actions does not error out during resource provisioning.
make -j2 install
$PYTHON -m pip install -r $GITHUB_WORKSPACE/python/requirements.txt
cd $GITHUB_WORKSPACE/build/python
$PYTHON -m pip install --user .
}
mkdir $GITHUB_WORKSPACE/build
cd $GITHUB_WORKSPACE/build
function test()
{
cd $GITHUB_WORKSPACE/python/gtsam/tests
$PYTHON -m unittest discover -v
}
cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} \
-DGTSAM_BUILD_TESTS=OFF \
-DGTSAM_BUILD_UNSTABLE=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_USE_QUATERNIONS=OFF \
-DGTSAM_WITH_TBB=${GTSAM_WITH_TBB:-OFF} \
-DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \
-DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \
-DGTSAM_BUILD_PYTHON=${BUILD_PYBIND} \
-DGTSAM_UNSTABLE_BUILD_PYTHON=${GTSAM_BUILD_UNSTABLE:-ON} \
-DGTSAM_PYTHON_VERSION=$PYTHON_VERSION \
-DPYTHON_EXECUTABLE:FILEPATH=$(which $PYTHON) \
-DGTSAM_ALLOW_DEPRECATED_SINCE_V42=OFF \
-DCMAKE_INSTALL_PREFIX=$GITHUB_WORKSPACE/gtsam_install
# Set to 2 cores so that Actions does not error out during resource provisioning.
make -j2 install
cd $GITHUB_WORKSPACE/build/python
$PYTHON -m pip install --user .
cd $GITHUB_WORKSPACE/python/gtsam/tests
$PYTHON -m unittest discover -v
# select between build or test
case $1 in
-d)
install_dependencies
;;
-b)
build
;;
-t)
test
;;
esac

View File

@ -113,11 +113,12 @@ jobs:
uses: pierotofy/set-swap-space@master
with:
swap-size-gb: 6
- name: Build (Linux)
if: runner.os == 'Linux'
- name: Install Dependencies
run: |
bash .github/scripts/python.sh
- name: Build (macOS)
if: runner.os == 'macOS'
bash .github/scripts/python.sh -d
- name: Build
run: |
bash .github/scripts/python.sh
bash .github/scripts/python.sh -b
- name: Test
run: |
bash .github/scripts/python.sh -t

View File

@ -11,4 +11,7 @@
@}
*/
\defgroup SLAM Useful SLAM components
@{ @}
*/

View File

@ -123,7 +123,7 @@ public:
* it is received from the IMU) so as to avoid costly integration at time of
* factor construction.
*
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType {
@ -252,7 +252,7 @@ public:
* the correlation between the bias uncertainty and the preintegrated
* measurements uncertainty.
*
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, Pose3,
Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {

View File

@ -66,7 +66,7 @@ typedef ManifoldPreintegration PreintegrationType;
* as soon as it is received from the IMU) so as to avoid costly integration
* at time of factor construction.
*
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
@ -165,7 +165,7 @@ public:
* (which are usually slowly varying quantities), which is up to the caller.
* See also CombinedImuFactor for a class that does this for you.
*
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
imuBias::ConstantBias> {
@ -256,7 +256,7 @@ public:
/**
* ImuFactor2 is a ternary factor that uses NavStates rather than Pose/Velocity.
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
private:

View File

@ -24,7 +24,7 @@ namespace gtsam {
/**
* A class for a soft prior on any Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
class PriorFactor: public NoiseModelFactor1<VALUE> {

View File

@ -27,7 +27,7 @@ namespace gtsam {
/**
* Binary factor for a bearing/range measurement
* @addtogroup SLAM
* @ingroup SLAM
*/
template <typename A1, typename A2,
typename B = typename Bearing<A1, A2>::result_type,

View File

@ -26,7 +26,7 @@ namespace gtsam {
* A class for downdating an existing factor from a graph. The AntiFactor returns the same
* linearized Hessian matrices of the original factor, but with the opposite sign. This effectively
* cancels out any affects of the original factor during optimization."
* @addtogroup SLAM
* @ingroup SLAM
*/
class AntiFactor: public NonlinearFactor {

View File

@ -34,7 +34,7 @@ namespace gtsam {
/**
* A class for a measurement predicted by "between(config[key1],config[key2])"
* @tparam VALUE the Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {

View File

@ -27,7 +27,7 @@ namespace gtsam {
* greater/less than a fixed threshold. The function
* will need to have its value function implemented to return
* a scalar for comparison.
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {

View File

@ -25,7 +25,7 @@ namespace gtsam {
/**
* Binary factor between two Pose3 variables induced by an EssentialMatrix measurement
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactor2<Pose3, Pose3> {

View File

@ -54,7 +54,7 @@ namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement.
* The calibration is unknown here compared to GenericProjectionFactor
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class CAMERA, class LANDMARK>
class GeneralSFMFactor: public NoiseModelFactor2<CAMERA, LANDMARK> {

View File

@ -33,7 +33,7 @@ namespace gtsam {
* Non-linear factor for a constraint derived from a 2D measurement.
* The calibration is known here.
* The main building block for visual SLAM.
* @addtogroup SLAM
* @ingroup SLAM
*/
template <class POSE = Pose3, class LANDMARK = Point3,
class CALIBRATION = Cal3_S2>

View File

@ -24,7 +24,7 @@
namespace gtsam {
/**
*
* @addtogroup SLAM
* @ingroup SLAM
*
* If you are using the factor, please cite:
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating conditionally
@ -39,7 +39,7 @@ namespace gtsam {
* The factor only constrains poses (variable dimension is 6).
* This factor requires that values contains the involved poses (Pose3).
* If the calibration should be optimized, as well, use SmartProjectionFactor instead!
* @addtogroup SLAM
* @ingroup SLAM
*/
template <class CALIBRATION>
class SmartProjectionPoseFactor

View File

@ -29,7 +29,7 @@
namespace gtsam {
/**
*
* @addtogroup SLAM
* @ingroup SLAM
*
* If you are using the factor, please cite:
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating
@ -46,7 +46,7 @@ namespace gtsam {
* calibration (i.e., are from the same camera), use SmartProjectionPoseFactor
* instead! If the calibration should be optimized, as well, use
* SmartProjectionFactor instead!
* @addtogroup SLAM
* @ingroup SLAM
*/
template <class CAMERA>
class SmartProjectionRigFactor : public SmartProjectionFactor<CAMERA> {

View File

@ -25,7 +25,7 @@ namespace gtsam {
/**
* A Generic Stereo Factor
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class POSE, class LANDMARK>
class GenericStereoFactor: public NoiseModelFactor2<POSE, LANDMARK> {

View File

@ -27,7 +27,7 @@ namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement.
* The calibration and pose are assumed known.
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class CAMERA>
class TriangulationFactor: public NoiseModelFactor1<Point3> {

View File

@ -28,7 +28,7 @@ namespace gtsam {
/**
* A class for a measurement predicted by "between(config[key1],config[key2])"
* @tparam VALUE the Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
class BetweenFactorEM: public NonlinearFactor {

View File

@ -25,7 +25,7 @@ namespace gtsam {
/**
* A class to model GPS measurements, including a bias term which models
* common-mode errors and that can be partially corrected if other sensors are used
* @addtogroup SLAM
* @ingroup SLAM
*/
class BiasedGPSFactor: public NoiseModelFactor2<Pose3, Point3> {

View File

@ -29,7 +29,7 @@ namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
* i.e. the main building block for visual SLAM.
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
class MultiProjectionFactor: public NoiseModelFactor {

View File

@ -26,7 +26,7 @@ namespace gtsam {
/**
* A class for a measurement predicted by "between(config[key1],config[key2])"
* @tparam POSE the Pose type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class POSE>
class PoseBetweenFactor: public NoiseModelFactor2<POSE, POSE> {

View File

@ -23,7 +23,7 @@ namespace gtsam {
/**
* A class for a soft prior on any Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class POSE>
class PosePriorFactor: public NoiseModelFactor1<POSE> {

View File

@ -18,7 +18,7 @@ namespace gtsam {
/**
* A class for a measurement between a pose and a point.
* @addtogroup SLAM
* @ingroup SLAM
*/
template<typename POSE = Pose3, typename POINT = Point3>
class PoseToPointFactor : public NoiseModelFactor2<POSE, POINT> {

View File

@ -28,7 +28,7 @@ namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
* i.e. the main building block for visual SLAM.
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
class ProjectionFactorPPP: public NoiseModelFactor3<POSE, POSE, LANDMARK> {

View File

@ -30,7 +30,7 @@ namespace gtsam {
/**
* Non-linear factor for a constraint derived from a 2D measurement. This factor
* estimates the body pose, body-camera transform, 3D landmark, and calibration.
* @addtogroup SLAM
* @ingroup SLAM
*/
template <class POSE, class LANDMARK, class CALIBRATION = Cal3_S2>
class GTSAM_UNSTABLE_EXPORT ProjectionFactorPPPC

View File

@ -38,7 +38,7 @@ namespace gtsam {
* define the alpha = (t_p - t_A) / (t_B - t_A), we will use the pose
* interpolated between A and B by the alpha to project the corresponding
* landmark to Point2.
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_UNSTABLE_EXPORT ProjectionFactorRollingShutter

View File

@ -25,7 +25,7 @@
namespace gtsam {
/**
*
* @addtogroup SLAM
* @ingroup SLAM
*
* If you are using the factor, please cite:
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
@ -39,7 +39,7 @@ namespace gtsam {
* shutter model of the camera with given readout time. The factor requires that
* values contain (for each pixel observation) two consecutive camera poses from
* which the pixel observation pose can be interpolated.
* @addtogroup SLAM
* @ingroup SLAM
*/
template <class CAMERA>
class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter

View File

@ -24,7 +24,7 @@ namespace gtsam {
/**
* Smart factor for range SLAM
* @addtogroup SLAM
* @ingroup SLAM
*/
class SmartRangeFactor: public NoiseModelFactor {
protected:

View File

@ -23,7 +23,7 @@
namespace gtsam {
/**
*
* @addtogroup SLAM
* @ingroup SLAM
*
* If you are using the factor, please cite:
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
@ -38,7 +38,7 @@ namespace gtsam {
* calibration or the same calibration can be shared by multiple cameras. This
* factor requires that values contain the involved poses and extrinsics (both
* are Pose3 variables).
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP
: public SmartStereoProjectionFactor {

View File

@ -26,7 +26,7 @@
namespace gtsam {
/**
*
* @addtogroup SLAM
* @ingroup SLAM
*
* If you are using the factor, please cite:
* L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert,
@ -41,7 +41,7 @@ namespace gtsam {
* has its own calibration.
* The factor only constrains poses (variable dimension is 6).
* This factor requires that values contains the involved poses (Pose3).
* @addtogroup SLAM
* @ingroup SLAM
*/
class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor
: public SmartStereoProjectionFactor {

View File

@ -29,7 +29,7 @@ namespace gtsam {
/**
* A class for a measurement predicted by "between(config[key1],config[key2])"
* @tparam VALUE the Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
class TransformBtwRobotsUnaryFactor: public NonlinearFactor { // TODO why not NoiseModelFactor1 ?

View File

@ -31,7 +31,7 @@ namespace gtsam {
/**
* A class for a measurement predicted by "between(config[key1],config[key2])"
* @tparam VALUE the Value type
* @addtogroup SLAM
* @ingroup SLAM
*/
template<class VALUE>
class TransformBtwRobotsUnaryFactorEM: public NonlinearFactor {