fix GTSAM_POSE3_EXPMAP warnings. Add GTSAM_ROT3_EXPMAP option.
parent
fcc6b804d1
commit
a48864452b
|
@ -53,11 +53,12 @@ if(GTSAM_UNSTABLE_AVAILABLE)
|
||||||
endif()
|
endif()
|
||||||
option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON)
|
option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON)
|
||||||
option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" OFF)
|
option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" OFF)
|
||||||
option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices" OFF)
|
option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices. If enable, Rot3::EXPMAP is enforced by default." OFF)
|
||||||
if(NOT MSVC)
|
if(NOT MSVC)
|
||||||
option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" OFF)
|
option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" OFF)
|
||||||
endif()
|
endif()
|
||||||
option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF)
|
option(GTSAM_POSE3_EXPMAP "Enable/Disable using Pose3::EXPMAP as the default mode. If disabled, Pose3::FIRST_ORDER will be used." OFF)
|
||||||
|
option(GTSAM_ROT3_EXPMAP "Ignore if GTSAM_USE_QUATERNIONS is OFF (Rot3::EXPMAP by default). Otherwise, enable Rot3::EXPMAP, or if disabled, use Rot3::CAYLEY." OFF)
|
||||||
option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF)
|
option(GTSAM_ENABLE_CONSISTENCY_CHECKS "Enable/Disable expensive consistency checks" OFF)
|
||||||
|
|
||||||
# Options relating to MATLAB wrapper
|
# Options relating to MATLAB wrapper
|
||||||
|
@ -181,10 +182,6 @@ if(GTSAM_ENABLE_CONSISTENCY_CHECKS)
|
||||||
add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS)
|
add_definitions(-DGTSAM_EXTRA_CONSISTENCY_CHECKS)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(GTSAM_POSE3_EXPMAP)
|
|
||||||
add_definitions(-DGTSAM_POSE3_EXPMAP)
|
|
||||||
endif()
|
|
||||||
|
|
||||||
###############################################################################
|
###############################################################################
|
||||||
# Add components
|
# Add components
|
||||||
|
|
||||||
|
|
|
@ -26,3 +26,8 @@
|
||||||
|
|
||||||
// Whether GTSAM is compiled to use Pose3::EXPMAP as the default coordinates mode for Pose3's retract and localCoordinates (otherwise, Pose3::FIRST_ORDER will be used)
|
// Whether GTSAM is compiled to use Pose3::EXPMAP as the default coordinates mode for Pose3's retract and localCoordinates (otherwise, Pose3::FIRST_ORDER will be used)
|
||||||
#cmakedefine GTSAM_POSE3_EXPMAP
|
#cmakedefine GTSAM_POSE3_EXPMAP
|
||||||
|
|
||||||
|
// Whether GTSAM is compiled to use Rot3::EXPMAP as the default coordinates mode for Rot3's retract and localCoordinates (otherwise, Pose3::CAYLEY will be used)
|
||||||
|
#ifndef GTSAM_USE_QUATERNIONS
|
||||||
|
#cmakedefine GTSAM_ROT3_EXPMAP
|
||||||
|
#endif
|
|
@ -25,13 +25,18 @@
|
||||||
|
|
||||||
// You can override the default coordinate mode using this flag
|
// You can override the default coordinate mode using this flag
|
||||||
#ifndef ROT3_DEFAULT_COORDINATES_MODE
|
#ifndef ROT3_DEFAULT_COORDINATES_MODE
|
||||||
#ifdef GTSAM_USE_QUATERNIONS
|
#ifdef GTSAM_USE_QUATERNIONS
|
||||||
// Exponential map is very cheap for quaternions
|
// Exponential map is very cheap for quaternions
|
||||||
#define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
|
#define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
|
||||||
#else
|
#else
|
||||||
// For rotation matrices, the Cayley transform is a fast retract alternative
|
// If user doesn't require GTSAM_ROT3_EXPMAP in cmake when building
|
||||||
#define ROT3_DEFAULT_COORDINATES_MODE Rot3::CAYLEY
|
#ifndef GTSAM_ROT3_EXPMAP
|
||||||
#endif
|
// For rotation matrices, the Cayley transform is a fast retract alternative
|
||||||
|
#define ROT3_DEFAULT_COORDINATES_MODE Rot3::CAYLEY
|
||||||
|
#else
|
||||||
|
#define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#include <gtsam/base/DerivedValue.h>
|
#include <gtsam/base/DerivedValue.h>
|
||||||
|
|
Loading…
Reference in New Issue