Merge pull request #85 from borglab/msvc-fixes
Changes to get gtsam to compile in Windows and fix matlab buildsrelease/4.3a0
commit
ec04369c88
|
@ -179,20 +179,18 @@ option(GTSAM_DISABLE_NEW_TIMERS "Disables using Boost.chrono for timing" OFF)
|
|||
# so we downgraded this to classic filenames-based variables, and manually adding
|
||||
# the target_include_directories(xxx ${Boost_INCLUDE_DIR})
|
||||
set(GTSAM_BOOST_LIBRARIES
|
||||
optimized
|
||||
${Boost_SERIALIZATION_LIBRARY_RELEASE}
|
||||
${Boost_SYSTEM_LIBRARY_RELEASE}
|
||||
${Boost_FILESYSTEM_LIBRARY_RELEASE}
|
||||
${Boost_THREAD_LIBRARY_RELEASE}
|
||||
${Boost_DATE_TIME_LIBRARY_RELEASE}
|
||||
${Boost_REGEX_LIBRARY_RELEASE}
|
||||
debug
|
||||
${Boost_SERIALIZATION_LIBRARY_DEBUG}
|
||||
${Boost_SYSTEM_LIBRARY_DEBUG}
|
||||
${Boost_FILESYSTEM_LIBRARY_DEBUG}
|
||||
${Boost_THREAD_LIBRARY_DEBUG}
|
||||
${Boost_DATE_TIME_LIBRARY_DEBUG}
|
||||
${Boost_REGEX_LIBRARY_DEBUG}
|
||||
optimized ${Boost_SERIALIZATION_LIBRARY_RELEASE}
|
||||
optimized ${Boost_SYSTEM_LIBRARY_RELEASE}
|
||||
optimized ${Boost_FILESYSTEM_LIBRARY_RELEASE}
|
||||
optimized ${Boost_THREAD_LIBRARY_RELEASE}
|
||||
optimized ${Boost_DATE_TIME_LIBRARY_RELEASE}
|
||||
optimized ${Boost_REGEX_LIBRARY_RELEASE}
|
||||
debug ${Boost_SERIALIZATION_LIBRARY_DEBUG}
|
||||
debug ${Boost_SYSTEM_LIBRARY_DEBUG}
|
||||
debug ${Boost_FILESYSTEM_LIBRARY_DEBUG}
|
||||
debug ${Boost_THREAD_LIBRARY_DEBUG}
|
||||
debug ${Boost_DATE_TIME_LIBRARY_DEBUG}
|
||||
debug ${Boost_REGEX_LIBRARY_DEBUG}
|
||||
)
|
||||
message(STATUS "GTSAM_BOOST_LIBRARIES: ${GTSAM_BOOST_LIBRARIES}")
|
||||
if (GTSAM_DISABLE_NEW_TIMERS)
|
||||
|
@ -201,12 +199,10 @@ if (GTSAM_DISABLE_NEW_TIMERS)
|
|||
else()
|
||||
if(Boost_TIMER_LIBRARY)
|
||||
list(APPEND GTSAM_BOOST_LIBRARIES
|
||||
optimized
|
||||
${Boost_TIMER_LIBRARY_RELEASE}
|
||||
${Boost_CHRONO_LIBRARY_RELEASE}
|
||||
debug
|
||||
${Boost_TIMER_LIBRARY_DEBUG}
|
||||
${Boost_CHRONO_LIBRARY_DEBUG}
|
||||
optimized ${Boost_TIMER_LIBRARY_RELEASE}
|
||||
optimized ${Boost_CHRONO_LIBRARY_RELEASE}
|
||||
debug ${Boost_TIMER_LIBRARY_DEBUG}
|
||||
debug ${Boost_CHRONO_LIBRARY_DEBUG}
|
||||
)
|
||||
else()
|
||||
list(APPEND GTSAM_BOOST_LIBRARIES rt) # When using the header-only boost timer library, need -lrt
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
# Using GTSAM_EXPORT
|
||||
|
||||
To create a DLL in windows, the `GTSAM_EXPORT` keyword has been created and needs to be applied to different methods and classes in the code to expose this code outside of the DLL. However, there are several intricacies that make this more difficult than it sounds. In general, if you follow the following three rules, GTSAM_EXPORT should work properly. The rest of the document also describes (1) the common error message encountered when you are not following these rules and (2) the reasoning behind these usage rules.
|
||||
|
||||
## Usage Rules
|
||||
1. Put `GTSAM_EXPORT` in front of any function that you want exported in the DLL _if and only if_ that function is declared in a .cpp file, not just a .h file.
|
||||
2. Use `GTSAM_EXPORT` in a class definition (i.e. `class GSTAM_EXPORT MyClass {...}`) only if:
|
||||
* At least one of the functions inside that class is declared in a .cpp file and not just the .h file.
|
||||
* You can `GTSAM_EXPORT` any class it inherits from as well. (Note that this implictly requires the class does not derive from a "header-only" class. Note that Eigen is a "header-only" library, so if your class derives from Eigen, _do not_ use `GTSAM_EXPORT` in the class definition!)
|
||||
3. If you have defined a class using `GTSAM_EXPORT`, do not use `GTSAM_EXPORT` in any of its individual function declarations. (Note that you _can_ put `GTSAM_EXPORT` in the definition of individual functions within a class as long as you don't put `GTSAM_EXPORT` in the class definition.)
|
||||
|
||||
## When is GTSAM_EXPORT being used incorrectly
|
||||
Unfortunately, using `GTSAM_EXPORT` incorrectly often does not cause a compiler or linker error in the library that is being compiled, but only when you try to use that DLL in a different library. For example, an error in gtsam/base will often show up when compiling the check_base_program or the MATLAB wrapper, but not when compiling/linking gtsam itself. The most common errors will say something like:
|
||||
|
||||
```
|
||||
Error LNK2019 unresolved external symbol "public: void __cdecl gtsam::SO3::print(class std::basic_string<char,struct std::char_traits<char>,class std::allocator<char> > const &)const " (?print@SO3@gtsam@@QEBAXAEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) referenced in function "public: static void __cdecl gtsam::Testable<class gtsam::SO3>::Print(class gtsam::SO3 const &,class std::basic_string<char,struct std::char_traits<char>,class std::allocator<char> > const &)" (?Print@?$Testable@VSO3@gtsam@@@gtsam@@SAXAEBVSO3@2@AEBV?$basic_string@DU?$char_traits@D@std@@V?$allocator@D@2@@std@@@Z) check_geometry_program C:\AFIT\lib\gtsam\build\gtsam\geometry\tests\testSO3.obj
|
||||
```
|
||||
|
||||
Let's analyze this error statement. First, there is an unresolved symbol `gtsam::SO3::print`. This can occur because _either_ `GTSAM_EXPORT` was not added to the print function definition when it should have been, _OR_ because `GTSAM_EXPORT` was added to the print function definition when it is fully declared in the header. This error was detected while compiling `check_geometry_program` and pulling in `...\testSO3.obj`. Specifically, within the function call `gtsam::Testable<class gtsam::SO3>::Print (...)`. Note that this error did _not_ occur when compiling the library that actually has SO3 inside of it.
|
||||
|
||||
## But Why?
|
||||
I believe that how the compiler/linker interacts with GTSAM_EXPORT can be explained by understanding the rules that MSVC operates under.
|
||||
|
||||
But first, we need to understand exactly what `GTSAM_EXPORT` is. `GTSAM_EXPORT` is a `#define` macro that is created by CMAKE when GTSAM is being compiled on a Windows machine. Inside the GTSAM project, GTSAM export will be set to a "dllexport" command. A "dllexport" command tells the compiler that this function should go into the DLL and be visible externally. In any other library, `GTSAM_EXPORT` will be set to a "dllimport" command, telling the linker it should find this function in a DLL somewhere. This leads to the first rule the compiler uses. (Note that I say "compiler rules" when the rules may actually be in the linker, but I am conflating the two terms here when I speak of the "compiler rules".)
|
||||
|
||||
***Compiler Rule #1*** If a `dllimport` command is used in defining a function or class, that function or class _must_ be found in a DLL.
|
||||
|
||||
Rule #1 doesn't seem very bad, until you combine it with rule #2
|
||||
|
||||
***Compiler Rule #2*** Anything declared in a header file is not included in a DLL.
|
||||
|
||||
When these two rules are combined, you get some very confusing results. For example, a class which is completely defined in a header (e.g. LieMatrix) cannot use `GTSAM_EXPORT` in its definition. If LieMatrix is defined with `GTSAM_EXPORT`, then the compiler _must_ find LieMatrix in a DLL. Because LieMatrix is a header-only class, however, it can't find it, leading to a very confusing "I can't find this symbol" type of error. Note that the linker says it can't find the symbol even though the compiler found the header file that completely defines the class.
|
||||
|
||||
Also note that when a class that you want to export inherits from another class that is not exportable, this can cause significant issues. According to this [MSVC Warning page](https://docs.microsoft.com/en-us/cpp/error-messages/compiler-warnings/compiler-warning-level-2-c4275?view=vs-2019), it may not strictly be a rule, but we have seen several linker errors when a class that is defined with `GTSAM_EXPORT` extended an Eigen class. In general, it appears that any inheritance of non-exportable class by an exportable class is a bad idea.
|
||||
|
||||
## Conclusion
|
||||
Hopefully, this little document clarifies when `GTSAM_EXPORT` should and should not be used whenever future GTSAM code is being written. Following the usage rules above, we have been able to get all of the libraries, together with their test and wrapping libraries, to compile/link successfully.
|
|
@ -77,7 +77,10 @@ set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_PROFILING "NDEBUG" CACHE STRING "(Us
|
|||
set(GTSAM_COMPILE_DEFINITIONS_PRIVATE_TIMING "NDEBUG;ENABLE_TIMING" CACHE STRING "(User editable) Private preprocessor macros for Timing configuration.")
|
||||
if(MSVC)
|
||||
# Common to all configurations:
|
||||
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE WINDOWS_LEAN_AND_MEAN)
|
||||
list_append_cache(GTSAM_COMPILE_DEFINITIONS_PRIVATE
|
||||
WINDOWS_LEAN_AND_MEAN
|
||||
NOMINMAX
|
||||
)
|
||||
endif()
|
||||
|
||||
# Other (non-preprocessor macros) compiler flags:
|
||||
|
|
|
@ -35,7 +35,11 @@ mark_as_advanced(FORCE MEX_COMMAND)
|
|||
# Now that we have mex, trace back to find the Matlab installation root
|
||||
get_filename_component(MEX_COMMAND "${MEX_COMMAND}" REALPATH)
|
||||
get_filename_component(mex_path "${MEX_COMMAND}" PATH)
|
||||
get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE)
|
||||
if(mex_path MATCHES ".*/win64$")
|
||||
get_filename_component(MATLAB_ROOT "${mex_path}/../.." ABSOLUTE)
|
||||
else()
|
||||
get_filename_component(MATLAB_ROOT "${mex_path}/.." ABSOLUTE)
|
||||
endif()
|
||||
set(MATLAB_ROOT "${MATLAB_ROOT}" CACHE PATH "Path to MATLAB installation root (e.g. /usr/local/MATLAB/R2012a)")
|
||||
|
||||
|
||||
|
@ -78,28 +82,29 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex
|
|||
set(mexModuleExt mexw32)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
|
||||
# Wrap codegen interface
|
||||
#usage: wrap interfacePath moduleName toolboxPath headerPath
|
||||
# interfacePath : *absolute* path to directory of module interface file
|
||||
# moduleName : the name of the module, interface file must be called moduleName.h
|
||||
# toolboxPath : the directory in which to generate the wrappers
|
||||
# headerPath : path to matlab.h
|
||||
|
||||
# headerPath : path to matlab.h
|
||||
|
||||
# Extract module name from interface header file name
|
||||
get_filename_component(interfaceHeader "${interfaceHeader}" ABSOLUTE)
|
||||
get_filename_component(modulePath "${interfaceHeader}" PATH)
|
||||
get_filename_component(moduleName "${interfaceHeader}" NAME_WE)
|
||||
|
||||
|
||||
# Paths for generated files
|
||||
set(generated_files_path "${PROJECT_BINARY_DIR}/wrap/${moduleName}")
|
||||
set(generated_cpp_file "${generated_files_path}/${moduleName}_wrapper.cpp")
|
||||
set(compiled_mex_modules_root "${PROJECT_BINARY_DIR}/wrap/${moduleName}_mex")
|
||||
|
||||
|
||||
message(STATUS "Building wrap module ${moduleName}")
|
||||
|
||||
|
||||
# Find matlab.h in GTSAM
|
||||
if("${PROJECT_NAME}" STREQUAL "GTSAM")
|
||||
if(("${PROJECT_NAME}" STREQUAL "gtsam") OR
|
||||
("${PROJECT_NAME}" STREQUAL "gtsam_unstable"))
|
||||
set(matlab_h_path "${PROJECT_SOURCE_DIR}")
|
||||
else()
|
||||
if(NOT GTSAM_INCLUDE_DIR)
|
||||
|
@ -221,6 +226,7 @@ function(wrap_library_internal interfaceHeader linkLibraries extraIncludeDirs ex
|
|||
string(REPLACE ";" " " mexFlagsSpaced "${GTSAM_BUILD_MEX_BINARY_FLAGS}")
|
||||
add_library(${moduleName}_matlab_wrapper MODULE ${generated_cpp_file} ${interfaceHeader} ${otherSourcesAndObjects})
|
||||
target_link_libraries(${moduleName}_matlab_wrapper ${correctedOtherLibraries})
|
||||
target_link_libraries(${moduleName}_matlab_wrapper ${moduleName})
|
||||
set_target_properties(${moduleName}_matlab_wrapper PROPERTIES
|
||||
OUTPUT_NAME "${moduleName}_wrapper"
|
||||
PREFIX ""
|
||||
|
|
|
@ -299,7 +299,7 @@ GTSAM_EXPORT std::pair<Matrix,Matrix> qr(const Matrix& A);
|
|||
* @param A is the input matrix, and is the output
|
||||
* @param clear_below_diagonal enables zeroing out below diagonal
|
||||
*/
|
||||
void inplace_QR(Matrix& A);
|
||||
GTSAM_EXPORT void inplace_QR(Matrix& A);
|
||||
|
||||
/**
|
||||
* Imperative algorithm for in-place full elimination with
|
||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
|||
* we can directly add double, Vector, and Matrix into values now, because of
|
||||
* gtsam::traits.
|
||||
*/
|
||||
struct GTSAM_EXPORT LieMatrix : public Matrix {
|
||||
struct LieMatrix : public Matrix {
|
||||
|
||||
/// @name Constructors
|
||||
/// @{
|
||||
|
|
|
@ -28,7 +28,7 @@ namespace gtsam {
|
|||
* we can directly add double, Vector, and Matrix into values now, because of
|
||||
* gtsam::traits.
|
||||
*/
|
||||
struct GTSAM_EXPORT LieScalar {
|
||||
struct LieScalar {
|
||||
|
||||
enum { dimension = 1 };
|
||||
|
||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
|||
* we can directly add double, Vector, and Matrix into values now, because of
|
||||
* gtsam::traits.
|
||||
*/
|
||||
struct GTSAM_EXPORT LieVector : public Vector {
|
||||
struct LieVector : public Vector {
|
||||
|
||||
enum { dimension = Eigen::Dynamic };
|
||||
|
||||
|
|
|
@ -142,7 +142,7 @@ namespace gtsam {
|
|||
/**
|
||||
* Timing Entry, arranged in a tree
|
||||
*/
|
||||
class GTSAM_EXPORT TimingOutline {
|
||||
class TimingOutline {
|
||||
protected:
|
||||
size_t id_;
|
||||
size_t t_;
|
||||
|
@ -174,21 +174,21 @@ namespace gtsam {
|
|||
|
||||
public:
|
||||
/// Constructor
|
||||
TimingOutline(const std::string& label, size_t myId);
|
||||
size_t time() const; ///< time taken, including children
|
||||
GTSAM_EXPORT TimingOutline(const std::string& label, size_t myId);
|
||||
GTSAM_EXPORT size_t time() const; ///< time taken, including children
|
||||
double secs() const { return double(time()) / 1000000.0;} ///< time taken, in seconds, including children
|
||||
double self() const { return double(t_) / 1000000.0;} ///< self time only, in seconds
|
||||
double wall() const { return double(tWall_) / 1000000.0;} ///< wall time, in seconds
|
||||
double min() const { return double(tMin_) / 1000000.0;} ///< min time, in seconds
|
||||
double max() const { return double(tMax_) / 1000000.0;} ///< max time, in seconds
|
||||
double mean() const { return self() / double(n_); } ///< mean self time, in seconds
|
||||
void print(const std::string& outline = "") const;
|
||||
void print2(const std::string& outline = "", const double parentTotal = -1.0) const;
|
||||
const boost::shared_ptr<TimingOutline>&
|
||||
GTSAM_EXPORT void print(const std::string& outline = "") const;
|
||||
GTSAM_EXPORT void print2(const std::string& outline = "", const double parentTotal = -1.0) const;
|
||||
GTSAM_EXPORT const boost::shared_ptr<TimingOutline>&
|
||||
child(size_t child, const std::string& label, const boost::weak_ptr<TimingOutline>& thisPtr);
|
||||
void tic();
|
||||
void toc();
|
||||
void finishedIteration();
|
||||
GTSAM_EXPORT void tic();
|
||||
GTSAM_EXPORT void toc();
|
||||
GTSAM_EXPORT void finishedIteration();
|
||||
|
||||
GTSAM_EXPORT friend void toc(size_t id, const char *label);
|
||||
}; // \TimingOutline
|
||||
|
|
|
@ -29,8 +29,7 @@
|
|||
|
||||
namespace gtsam {
|
||||
|
||||
class GTSAM_EXPORT CheiralityException: public ThreadsafeException<
|
||||
CheiralityException> {
|
||||
class GTSAM_EXPORT CheiralityException: public ThreadsafeException<CheiralityException> {
|
||||
public:
|
||||
CheiralityException()
|
||||
: CheiralityException(std::numeric_limits<Key>::max()) {}
|
||||
|
|
|
@ -23,7 +23,7 @@ namespace gtsam {
|
|||
* but here we choose instead to parameterize it as a (Rot3,Unit3) pair.
|
||||
* We can then non-linearly optimize immediately on this 5-dimensional manifold.
|
||||
*/
|
||||
class GTSAM_EXPORT EssentialMatrix {
|
||||
class EssentialMatrix {
|
||||
private:
|
||||
Rot3 R_; ///< Rotation
|
||||
Unit3 t_; ///< Translation
|
||||
|
@ -48,12 +48,12 @@ class GTSAM_EXPORT EssentialMatrix {
|
|||
}
|
||||
|
||||
/// Named constructor with derivatives
|
||||
static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb,
|
||||
GTSAM_EXPORT static EssentialMatrix FromRotationAndDirection(const Rot3& aRb, const Unit3& aTb,
|
||||
OptionalJacobian<5, 3> H1 = boost::none,
|
||||
OptionalJacobian<5, 2> H2 = boost::none);
|
||||
|
||||
/// Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
|
||||
static EssentialMatrix FromPose3(const Pose3& _1P2_,
|
||||
GTSAM_EXPORT static EssentialMatrix FromPose3(const Pose3& _1P2_,
|
||||
OptionalJacobian<5, 6> H = boost::none);
|
||||
|
||||
/// Random, using Rot3::Random and Unit3::Random
|
||||
|
@ -70,7 +70,7 @@ class GTSAM_EXPORT EssentialMatrix {
|
|||
/// @{
|
||||
|
||||
/// print with optional string
|
||||
void print(const std::string& s = "") const;
|
||||
GTSAM_EXPORT void print(const std::string& s = "") const;
|
||||
|
||||
/// assert equality up to a tolerance
|
||||
bool equals(const EssentialMatrix& other, double tol = 1e-8) const {
|
||||
|
@ -138,7 +138,7 @@ class GTSAM_EXPORT EssentialMatrix {
|
|||
* @param Dpoint optional 3*3 Jacobian wrpt point
|
||||
* @return point in pose coordinates
|
||||
*/
|
||||
Point3 transformTo(const Point3& p,
|
||||
GTSAM_EXPORT Point3 transformTo(const Point3& p,
|
||||
OptionalJacobian<3, 5> DE = boost::none,
|
||||
OptionalJacobian<3, 3> Dpoint = boost::none) const;
|
||||
|
||||
|
@ -147,7 +147,7 @@ class GTSAM_EXPORT EssentialMatrix {
|
|||
* @param cRb rotation from body frame to camera frame
|
||||
* @param E essential matrix E in camera frame C
|
||||
*/
|
||||
EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE =
|
||||
GTSAM_EXPORT EssentialMatrix rotate(const Rot3& cRb, OptionalJacobian<5, 5> HE =
|
||||
boost::none, OptionalJacobian<5, 3> HR = boost::none) const;
|
||||
|
||||
/**
|
||||
|
@ -160,7 +160,7 @@ class GTSAM_EXPORT EssentialMatrix {
|
|||
}
|
||||
|
||||
/// epipolar error, algebraic
|
||||
double error(const Vector3& vA, const Vector3& vB,
|
||||
GTSAM_EXPORT double error(const Vector3& vA, const Vector3& vB,
|
||||
OptionalJacobian<1, 5> H = boost::none) const;
|
||||
|
||||
/// @}
|
||||
|
|
|
@ -37,7 +37,7 @@ namespace gtsam {
|
|||
* @addtogroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class GTSAM_EXPORT Point2 : public Vector2 {
|
||||
class Point2 : public Vector2 {
|
||||
private:
|
||||
|
||||
public:
|
||||
|
@ -66,10 +66,10 @@ public:
|
|||
/// @{
|
||||
|
||||
/// print with optional string
|
||||
void print(const std::string& s = "") const;
|
||||
GTSAM_EXPORT void print(const std::string& s = "") const;
|
||||
|
||||
/// equals with an tolerance, prints out message if unequal
|
||||
bool equals(const Point2& q, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const Point2& q, double tol = 1e-9) const;
|
||||
|
||||
/// @}
|
||||
/// @name Group
|
||||
|
@ -86,10 +86,10 @@ public:
|
|||
Point2 unit() const { return *this/norm(); }
|
||||
|
||||
/** norm of point, with derivative */
|
||||
double norm(OptionalJacobian<1,2> H = boost::none) const;
|
||||
GTSAM_EXPORT double norm(OptionalJacobian<1,2> H = boost::none) const;
|
||||
|
||||
/** distance between two points */
|
||||
double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none,
|
||||
GTSAM_EXPORT double distance(const Point2& p2, OptionalJacobian<1,2> H1 = boost::none,
|
||||
OptionalJacobian<1,2> H2 = boost::none) const;
|
||||
|
||||
/// @}
|
||||
|
@ -124,9 +124,9 @@ public:
|
|||
static Vector2 Logmap(const Point2& p) { return p;}
|
||||
static Point2 Expmap(const Vector2& v) { return Point2(v);}
|
||||
inline double dist(const Point2& p2) const {return distance(p2);}
|
||||
static boost::optional<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
|
||||
static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
|
||||
static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
|
||||
GTSAM_EXPORT static boost::optional<Point2> CircleCircleIntersection(double R_d, double r_d, double tol = 1e-9);
|
||||
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, Point2 c2, boost::optional<Point2> fh);
|
||||
GTSAM_EXPORT static std::list<Point2> CircleCircleIntersection(Point2 c1, double r1, Point2 c2, double r2, double tol = 1e-9);
|
||||
/// @}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -42,7 +42,7 @@ namespace gtsam {
|
|||
* @addtogroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class GTSAM_EXPORT Point3 : public Vector3 {
|
||||
class Point3 : public Vector3 {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -63,10 +63,10 @@ class GTSAM_EXPORT Point3 : public Vector3 {
|
|||
/// @{
|
||||
|
||||
/** print with optional string */
|
||||
void print(const std::string& s = "") const;
|
||||
GTSAM_EXPORT void print(const std::string& s = "") const;
|
||||
|
||||
/** equals with an tolerance */
|
||||
bool equals(const Point3& p, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const Point3& p, double tol = 1e-9) const;
|
||||
|
||||
/// @}
|
||||
/// @name Group
|
||||
|
@ -80,21 +80,21 @@ class GTSAM_EXPORT Point3 : public Vector3 {
|
|||
/// @{
|
||||
|
||||
/** distance between two points */
|
||||
double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none,
|
||||
GTSAM_EXPORT double distance(const Point3& p2, OptionalJacobian<1, 3> H1 = boost::none,
|
||||
OptionalJacobian<1, 3> H2 = boost::none) const;
|
||||
|
||||
/** Distance of the point from the origin, with Jacobian */
|
||||
double norm(OptionalJacobian<1,3> H = boost::none) const;
|
||||
GTSAM_EXPORT double norm(OptionalJacobian<1,3> H = boost::none) const;
|
||||
|
||||
/** normalize, with optional Jacobian */
|
||||
Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const;
|
||||
GTSAM_EXPORT Point3 normalized(OptionalJacobian<3, 3> H = boost::none) const;
|
||||
|
||||
/** cross product @return this x q */
|
||||
Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, //
|
||||
GTSAM_EXPORT Point3 cross(const Point3 &q, OptionalJacobian<3, 3> H_p = boost::none, //
|
||||
OptionalJacobian<3, 3> H_q = boost::none) const;
|
||||
|
||||
/** dot product @return this * q*/
|
||||
double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, //
|
||||
GTSAM_EXPORT double dot(const Point3 &q, OptionalJacobian<1, 3> H_p = boost::none, //
|
||||
OptionalJacobian<1, 3> H_q = boost::none) const;
|
||||
|
||||
/// @}
|
||||
|
@ -130,9 +130,9 @@ class GTSAM_EXPORT Point3 : public Vector3 {
|
|||
static Point3 Expmap(const Vector3& v) { return Point3(v);}
|
||||
inline double dist(const Point3& q) const { return (q - *this).norm(); }
|
||||
Point3 normalize(OptionalJacobian<3, 3> H = boost::none) const { return normalized(H);}
|
||||
Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
GTSAM_EXPORT Point3 add(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
OptionalJacobian<3, 3> H2 = boost::none) const;
|
||||
Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
GTSAM_EXPORT Point3 sub(const Point3& q, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
OptionalJacobian<3, 3> H2 = boost::none) const;
|
||||
/// @}
|
||||
#endif
|
||||
|
|
|
@ -33,7 +33,7 @@ namespace gtsam {
|
|||
* @addtogroup geometry
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
|
||||
class Pose2: public LieGroup<Pose2, 3> {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -97,10 +97,10 @@ public:
|
|||
/// @{
|
||||
|
||||
/** print with optional string */
|
||||
void print(const std::string& s = "") const;
|
||||
GTSAM_EXPORT void print(const std::string& s = "") const;
|
||||
|
||||
/** assert equality up to a tolerance */
|
||||
bool equals(const Pose2& pose, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const;
|
||||
|
||||
/// @}
|
||||
/// @name Group
|
||||
|
@ -110,7 +110,7 @@ public:
|
|||
inline static Pose2 identity() { return Pose2(); }
|
||||
|
||||
/// inverse
|
||||
Pose2 inverse() const;
|
||||
GTSAM_EXPORT Pose2 inverse() const;
|
||||
|
||||
/// compose syntactic sugar
|
||||
inline Pose2 operator*(const Pose2& p2) const {
|
||||
|
@ -122,16 +122,16 @@ public:
|
|||
/// @{
|
||||
|
||||
///Exponential map at identity - create a rotation from canonical coordinates \f$ [T_x,T_y,\theta] \f$
|
||||
static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = boost::none);
|
||||
|
||||
///Log map at identity - return the canonical coordinates \f$ [T_x,T_y,\theta] \f$ of this rotation
|
||||
static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = boost::none);
|
||||
|
||||
/**
|
||||
* 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)
|
||||
*/
|
||||
Matrix3 AdjointMap() const;
|
||||
GTSAM_EXPORT Matrix3 AdjointMap() const;
|
||||
|
||||
/// Apply AdjointMap to twist xi
|
||||
inline Vector3 Adjoint(const Vector3& xi) const {
|
||||
|
@ -141,7 +141,7 @@ public:
|
|||
/**
|
||||
* Compute the [ad(w,v)] operator for SE2 as in [Kobilarov09siggraph], pg 19
|
||||
*/
|
||||
static Matrix3 adjointMap(const Vector3& v);
|
||||
GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v);
|
||||
|
||||
/**
|
||||
* Action of the adjointMap on a Lie-algebra vector y, with optional derivatives
|
||||
|
@ -177,15 +177,15 @@ public:
|
|||
}
|
||||
|
||||
/// Derivative of Expmap
|
||||
static Matrix3 ExpmapDerivative(const Vector3& v);
|
||||
GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v);
|
||||
|
||||
/// Derivative of Logmap
|
||||
static Matrix3 LogmapDerivative(const Pose2& v);
|
||||
GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v);
|
||||
|
||||
// Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
|
||||
struct ChartAtOrigin {
|
||||
static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none);
|
||||
static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = boost::none);
|
||||
};
|
||||
|
||||
using LieGroup<Pose2, 3>::inverse; // version with derivative
|
||||
|
@ -195,12 +195,12 @@ public:
|
|||
/// @{
|
||||
|
||||
/** Return point coordinates in pose coordinate frame */
|
||||
Point2 transformTo(const Point2& point,
|
||||
GTSAM_EXPORT Point2 transformTo(const Point2& point,
|
||||
OptionalJacobian<2, 3> Dpose = boost::none,
|
||||
OptionalJacobian<2, 2> Dpoint = boost::none) const;
|
||||
|
||||
/** Return point coordinates in global frame */
|
||||
Point2 transformFrom(const Point2& point,
|
||||
GTSAM_EXPORT Point2 transformFrom(const Point2& point,
|
||||
OptionalJacobian<2, 3> Dpose = boost::none,
|
||||
OptionalJacobian<2, 2> Dpoint = boost::none) const;
|
||||
|
||||
|
@ -233,14 +233,14 @@ public:
|
|||
inline const Rot2& rotation() const { return r_; }
|
||||
|
||||
//// return transformation matrix
|
||||
Matrix3 matrix() const;
|
||||
GTSAM_EXPORT Matrix3 matrix() const;
|
||||
|
||||
/**
|
||||
* Calculate bearing to a landmark
|
||||
* @param point 2D location of landmark
|
||||
* @return 2D rotation \f$ \in SO(2) \f$
|
||||
*/
|
||||
Rot2 bearing(const Point2& point,
|
||||
GTSAM_EXPORT Rot2 bearing(const Point2& point,
|
||||
OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 2> H2=boost::none) const;
|
||||
|
||||
/**
|
||||
|
@ -248,7 +248,7 @@ public:
|
|||
* @param point SO(2) location of other pose
|
||||
* @return 2D rotation \f$ \in SO(2) \f$
|
||||
*/
|
||||
Rot2 bearing(const Pose2& pose,
|
||||
GTSAM_EXPORT Rot2 bearing(const Pose2& pose,
|
||||
OptionalJacobian<1, 3> H1=boost::none, OptionalJacobian<1, 3> H2=boost::none) const;
|
||||
|
||||
/**
|
||||
|
@ -256,7 +256,7 @@ public:
|
|||
* @param point 2D location of landmark
|
||||
* @return range (double)
|
||||
*/
|
||||
double range(const Point2& point,
|
||||
GTSAM_EXPORT double range(const Point2& point,
|
||||
OptionalJacobian<1, 3> H1=boost::none,
|
||||
OptionalJacobian<1, 2> H2=boost::none) const;
|
||||
|
||||
|
@ -265,7 +265,7 @@ public:
|
|||
* @param point 2D location of other pose
|
||||
* @return range (double)
|
||||
*/
|
||||
double range(const Pose2& point,
|
||||
GTSAM_EXPORT double range(const Pose2& point,
|
||||
OptionalJacobian<1, 3> H1=boost::none,
|
||||
OptionalJacobian<1, 3> H2=boost::none) const;
|
||||
|
||||
|
|
|
@ -62,13 +62,13 @@ public:
|
|||
}
|
||||
|
||||
/// Static, named constructor TODO think about relation with above
|
||||
static SO3 AxisAngle(const Vector3& axis, double theta);
|
||||
GTSAM_EXPORT static SO3 AxisAngle(const Vector3& axis, double theta);
|
||||
|
||||
/// @}
|
||||
/// @name Testable
|
||||
/// @{
|
||||
|
||||
void print(const std::string& s) const;
|
||||
GTSAM_EXPORT void print(const std::string& s) const;
|
||||
|
||||
bool equals(const SO3 & R, double tol) const {
|
||||
return equal_with_abs_tol(*this, R, tol);
|
||||
|
@ -96,19 +96,19 @@ public:
|
|||
* Exponential map at identity - create a rotation from canonical coordinates
|
||||
* \f$ [R_x,R_y,R_z] \f$ using Rodrigues' formula
|
||||
*/
|
||||
static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static SO3 Expmap(const Vector3& omega, ChartJacobian H = boost::none);
|
||||
|
||||
/// Derivative of Expmap
|
||||
static Matrix3 ExpmapDerivative(const Vector3& omega);
|
||||
GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& omega);
|
||||
|
||||
/**
|
||||
* Log map at identity - returns the canonical coordinates
|
||||
* \f$ [R_x,R_y,R_z] \f$ of this rotation
|
||||
*/
|
||||
static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none);
|
||||
GTSAM_EXPORT static Vector3 Logmap(const SO3& R, ChartJacobian H = boost::none);
|
||||
|
||||
/// Derivative of Logmap
|
||||
static Matrix3 LogmapDerivative(const Vector3& omega);
|
||||
GTSAM_EXPORT static Matrix3 LogmapDerivative(const Vector3& omega);
|
||||
|
||||
Matrix3 AdjointMap() const {
|
||||
return *this;
|
||||
|
@ -156,14 +156,14 @@ class GTSAM_EXPORT ExpmapFunctor {
|
|||
};
|
||||
|
||||
/// Functor that implements Exponential map *and* its derivatives
|
||||
class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor {
|
||||
class DexpFunctor : public ExpmapFunctor {
|
||||
const Vector3 omega;
|
||||
double a, b;
|
||||
Matrix3 dexp_;
|
||||
|
||||
public:
|
||||
/// Constructor with element of Lie algebra so(3)
|
||||
DexpFunctor(const Vector3& omega, bool nearZeroApprox = false);
|
||||
GTSAM_EXPORT DexpFunctor(const Vector3& omega, bool nearZeroApprox = false);
|
||||
|
||||
// NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation
|
||||
// (10.86) and following equations in G.S. Chirikjian, "Stochastic Models,
|
||||
|
@ -174,11 +174,11 @@ class GTSAM_EXPORT DexpFunctor : public ExpmapFunctor {
|
|||
const Matrix3& dexp() const { return dexp_; }
|
||||
|
||||
/// Multiplies with dexp(), with optional derivatives
|
||||
Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
GTSAM_EXPORT Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none,
|
||||
OptionalJacobian<3, 3> H2 = boost::none) const;
|
||||
|
||||
/// Multiplies with dexp().inverse(), with optional derivatives
|
||||
Vector3 applyInvDexp(const Vector3& v,
|
||||
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3& v,
|
||||
OptionalJacobian<3, 3> H1 = boost::none,
|
||||
OptionalJacobian<3, 3> H2 = boost::none) const;
|
||||
};
|
||||
|
|
|
@ -39,7 +39,7 @@
|
|||
namespace gtsam {
|
||||
|
||||
/// Represents a 3D point on a unit sphere.
|
||||
class GTSAM_EXPORT Unit3 {
|
||||
class Unit3 {
|
||||
|
||||
private:
|
||||
|
||||
|
@ -94,11 +94,11 @@ public:
|
|||
}
|
||||
|
||||
/// Named constructor from Point3 with optional Jacobian
|
||||
static Unit3 FromPoint3(const Point3& point, //
|
||||
GTSAM_EXPORT static Unit3 FromPoint3(const Point3& point, //
|
||||
OptionalJacobian<2, 3> H = boost::none);
|
||||
|
||||
/// Random direction, using boost::uniform_on_sphere
|
||||
static Unit3 Random(boost::mt19937 & rng);
|
||||
GTSAM_EXPORT static Unit3 Random(boost::mt19937 & rng);
|
||||
|
||||
/// @}
|
||||
|
||||
|
@ -108,7 +108,7 @@ public:
|
|||
friend std::ostream& operator<<(std::ostream& os, const Unit3& pair);
|
||||
|
||||
/// The print fuction
|
||||
void print(const std::string& s = std::string()) const;
|
||||
GTSAM_EXPORT void print(const std::string& s = std::string()) const;
|
||||
|
||||
/// The equals function with tolerance
|
||||
bool equals(const Unit3& s, double tol = 1e-9) const {
|
||||
|
@ -125,16 +125,16 @@ public:
|
|||
* tangent to the sphere at the current direction.
|
||||
* Provides derivatives of the basis with the two basis vectors stacked up as a 6x1.
|
||||
*/
|
||||
const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
|
||||
GTSAM_EXPORT const Matrix32& basis(OptionalJacobian<6, 2> H = boost::none) const;
|
||||
|
||||
/// Return skew-symmetric associated with 3D point on unit sphere
|
||||
Matrix3 skew() const;
|
||||
GTSAM_EXPORT Matrix3 skew() const;
|
||||
|
||||
/// Return unit-norm Point3
|
||||
Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
|
||||
GTSAM_EXPORT Point3 point3(OptionalJacobian<3, 2> H = boost::none) const;
|
||||
|
||||
/// Return unit-norm Vector
|
||||
Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
|
||||
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian<3, 2> H = boost::none) const;
|
||||
|
||||
/// Return scaled direction as Point3
|
||||
friend Point3 operator*(double s, const Unit3& d) {
|
||||
|
@ -142,20 +142,20 @@ public:
|
|||
}
|
||||
|
||||
/// Return dot product with q
|
||||
double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
|
||||
GTSAM_EXPORT double dot(const Unit3& q, OptionalJacobian<1,2> H1 = boost::none, //
|
||||
OptionalJacobian<1,2> H2 = boost::none) const;
|
||||
|
||||
/// Signed, vector-valued error between two directions
|
||||
/// @deprecated, errorVector has the proper derivatives, this confusingly has only the second.
|
||||
Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
|
||||
GTSAM_EXPORT Vector2 error(const Unit3& q, OptionalJacobian<2, 2> H_q = boost::none) const;
|
||||
|
||||
/// Signed, vector-valued error between two directions
|
||||
/// NOTE(hayk): This method has zero derivatives if this (p) and q are orthogonal.
|
||||
Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
|
||||
GTSAM_EXPORT Vector2 errorVector(const Unit3& q, OptionalJacobian<2, 2> H_p = boost::none, //
|
||||
OptionalJacobian<2, 2> H_q = boost::none) const;
|
||||
|
||||
/// Distance between two directions
|
||||
double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
|
||||
GTSAM_EXPORT double distance(const Unit3& q, OptionalJacobian<1, 2> H = boost::none) const;
|
||||
|
||||
/// Cross-product between two Unit3s
|
||||
Unit3 cross(const Unit3& q) const {
|
||||
|
@ -188,10 +188,10 @@ public:
|
|||
};
|
||||
|
||||
/// The retract function
|
||||
Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
|
||||
GTSAM_EXPORT Unit3 retract(const Vector2& v, OptionalJacobian<2,2> H = boost::none) const;
|
||||
|
||||
/// The local coordinates function
|
||||
Vector2 localCoordinates(const Unit3& s) const;
|
||||
GTSAM_EXPORT Vector2 localCoordinates(const Unit3& s) const;
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -206,7 +206,7 @@ TEST( CalibratedCamera, DBackprojectFromCamera)
|
|||
static Point3 backproject(const Pose3& pose, const Point2& point, const double& depth) {
|
||||
return CalibratedCamera(pose).backproject(point, depth);
|
||||
}
|
||||
TEST( PinholePose, Dbackproject)
|
||||
TEST( PinholePose, DbackprojectCalibCamera)
|
||||
{
|
||||
Matrix36 Dpose;
|
||||
Matrix31 Ddepth;
|
||||
|
|
|
@ -58,6 +58,7 @@ TEST( PinholePose, constructor)
|
|||
}
|
||||
|
||||
//******************************************************************************
|
||||
/* Already in testPinholeCamera???
|
||||
TEST(PinholeCamera, Pose) {
|
||||
|
||||
Matrix actualH;
|
||||
|
@ -69,6 +70,7 @@ TEST(PinholeCamera, Pose) {
|
|||
Matrix numericalH = numericalDerivative11<Pose3,Camera>(f,camera);
|
||||
EXPECT(assert_equal(numericalH, actualH, 1e-9));
|
||||
}
|
||||
*/
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST( PinholePose, lookat)
|
||||
|
@ -207,7 +209,7 @@ static Point3 backproject(const Pose3& pose, const Cal3_S2& cal,
|
|||
return Camera(pose, cal.vector()).backproject(p, depth);
|
||||
}
|
||||
|
||||
TEST( PinholePose, Dbackproject)
|
||||
TEST( PinholePose, DbackprojectRegCamera)
|
||||
{
|
||||
Matrix36 Dpose;
|
||||
Matrix31 Ddepth;
|
||||
|
|
|
@ -81,13 +81,14 @@ TEST(Quaternion , Compose) {
|
|||
}
|
||||
|
||||
//******************************************************************************
|
||||
Vector3 z_axis(0, 0, 1);
|
||||
Q id(Eigen::AngleAxisd(0, z_axis));
|
||||
Q R1(Eigen::AngleAxisd(1, z_axis));
|
||||
Vector3 Q_z_axis(0, 0, 1);
|
||||
Q id(Eigen::AngleAxisd(0, Q_z_axis));
|
||||
Q R1(Eigen::AngleAxisd(1, Q_z_axis));
|
||||
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)));
|
||||
|
||||
//******************************************************************************
|
||||
TEST(Quaternion , Between) {
|
||||
Vector3 z_axis(0, 0, 1);
|
||||
Q q1(Eigen::AngleAxisd(0.2, z_axis));
|
||||
Q q2(Eigen::AngleAxisd(0.1, z_axis));
|
||||
|
||||
|
@ -98,6 +99,7 @@ TEST(Quaternion , Between) {
|
|||
|
||||
//******************************************************************************
|
||||
TEST(Quaternion , Inverse) {
|
||||
Vector3 z_axis(0, 0, 1);
|
||||
Q q1(Eigen::AngleAxisd(0.1, z_axis));
|
||||
Q expected(Eigen::AngleAxisd(-0.1, z_axis));
|
||||
|
||||
|
|
|
@ -386,7 +386,7 @@ private:
|
|||
/**
|
||||
* TriangulationResult is an optional point, along with the reasons why it is invalid.
|
||||
*/
|
||||
class GTSAM_EXPORT TriangulationResult: public boost::optional<Point3> {
|
||||
class TriangulationResult: public boost::optional<Point3> {
|
||||
enum Status {
|
||||
VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT
|
||||
};
|
||||
|
|
|
@ -58,7 +58,7 @@ static const gtsam::KeyFormatter MultiRobotKeyFormatter =
|
|||
struct StreamedKey {
|
||||
const Key &key_;
|
||||
explicit StreamedKey(const Key &key) : key_(key) {}
|
||||
friend std::ostream &operator<<(std::ostream &, const StreamedKey &);
|
||||
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const StreamedKey &);
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -72,8 +72,8 @@ struct StreamedKey {
|
|||
class key_formatter {
|
||||
public:
|
||||
explicit key_formatter(KeyFormatter v) : formatter_(v) {}
|
||||
friend std::ostream &operator<<(std::ostream &, const key_formatter &);
|
||||
friend std::ostream &operator<<(std::ostream &, const StreamedKey &);
|
||||
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const key_formatter &);
|
||||
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &, const StreamedKey &);
|
||||
|
||||
private:
|
||||
KeyFormatter formatter_;
|
||||
|
|
|
@ -76,7 +76,7 @@ TEST(Key, ChrTest) {
|
|||
|
||||
/* ************************************************************************* */
|
||||
// A custom (nonsensical) formatter.
|
||||
string myFormatter(Key key) {
|
||||
string keyMyFormatter(Key key) {
|
||||
return "special";
|
||||
}
|
||||
|
||||
|
@ -91,7 +91,7 @@ TEST(Key, Formatting) {
|
|||
|
||||
// use key_formatter with a function pointer
|
||||
stringstream ss2;
|
||||
ss2 << key_formatter(myFormatter) << StreamedKey(key);
|
||||
ss2 << key_formatter(keyMyFormatter) << StreamedKey(key);
|
||||
EXPECT("special" == ss2.str());
|
||||
|
||||
// use key_formatter with a function object.
|
||||
|
|
|
@ -81,7 +81,7 @@ TEST(LabeledSymbol, ChrTest) {
|
|||
|
||||
/* ************************************************************************* */
|
||||
// A custom (nonsensical) formatter.
|
||||
string myFormatter(Key key) {
|
||||
string labeledSymbolMyFormatter(Key key) {
|
||||
return "special";
|
||||
}
|
||||
|
||||
|
@ -90,7 +90,7 @@ TEST(LabeledSymbol, Formatting) {
|
|||
|
||||
// use key_formatter with a function pointer
|
||||
stringstream ss2;
|
||||
ss2 << key_formatter(myFormatter) << symbol;
|
||||
ss2 << key_formatter(labeledSymbolMyFormatter) << symbol;
|
||||
EXPECT("special" == ss2.str());
|
||||
|
||||
// use key_formatter with a function object.
|
||||
|
|
|
@ -23,7 +23,7 @@ using namespace gtsam;
|
|||
|
||||
/* ************************************************************************* */
|
||||
// A custom (nonsensical) formatter.
|
||||
string myFormatter(Key key) {
|
||||
string symbolMyFormatter(Key key) {
|
||||
return "special";
|
||||
}
|
||||
|
||||
|
@ -32,7 +32,7 @@ TEST(Symbol, Formatting) {
|
|||
|
||||
// use key_formatter with a function pointer
|
||||
stringstream ss2;
|
||||
ss2 << key_formatter(myFormatter) << symbol;
|
||||
ss2 << key_formatter(symbolMyFormatter) << symbol;
|
||||
EXPECT("special" == ss2.str());
|
||||
|
||||
// use key_formatter with a function object.
|
||||
|
|
|
@ -41,7 +41,7 @@ class VectorValues;
|
|||
/**
|
||||
* parameters for iterative linear solvers
|
||||
*/
|
||||
class GTSAM_EXPORT IterativeOptimizationParameters {
|
||||
class IterativeOptimizationParameters {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -63,27 +63,27 @@ public:
|
|||
inline Verbosity verbosity() const {
|
||||
return verbosity_;
|
||||
}
|
||||
std::string getVerbosity() const;
|
||||
void setVerbosity(const std::string &s);
|
||||
GTSAM_EXPORT std::string getVerbosity() const;
|
||||
GTSAM_EXPORT void setVerbosity(const std::string &s);
|
||||
|
||||
/* matlab interface */
|
||||
void print() const;
|
||||
GTSAM_EXPORT void print() const;
|
||||
|
||||
/* virtual print function */
|
||||
virtual void print(std::ostream &os) const;
|
||||
GTSAM_EXPORT virtual void print(std::ostream &os) const;
|
||||
|
||||
/* for serialization */
|
||||
friend std::ostream& operator<<(std::ostream &os,
|
||||
const IterativeOptimizationParameters &p);
|
||||
|
||||
static Verbosity verbosityTranslator(const std::string &s);
|
||||
static std::string verbosityTranslator(Verbosity v);
|
||||
GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s);
|
||||
GTSAM_EXPORT static std::string verbosityTranslator(Verbosity v);
|
||||
};
|
||||
|
||||
/**
|
||||
* Base class for Iterative Solvers like SubgraphSolver
|
||||
*/
|
||||
class GTSAM_EXPORT IterativeSolver {
|
||||
class IterativeSolver {
|
||||
public:
|
||||
typedef boost::shared_ptr<IterativeSolver> shared_ptr;
|
||||
IterativeSolver() {
|
||||
|
@ -92,12 +92,12 @@ public:
|
|||
}
|
||||
|
||||
/* interface to the nonlinear optimizer, without metadata, damping and initial estimate */
|
||||
VectorValues optimize(const GaussianFactorGraph &gfg,
|
||||
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg,
|
||||
boost::optional<const KeyInfo&> = boost::none,
|
||||
boost::optional<const std::map<Key, Vector>&> lambda = boost::none);
|
||||
|
||||
/* interface to the nonlinear optimizer, without initial estimate */
|
||||
VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo,
|
||||
GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo,
|
||||
const std::map<Key, Vector> &lambda);
|
||||
|
||||
/* interface to the nonlinear optimizer that the subclasses have to implement */
|
||||
|
|
|
@ -36,7 +36,7 @@ static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix& covariance) {
|
|||
* Simple class to test navigation scenarios.
|
||||
* Takes a trajectory scenario as input, and can generate IMU measurements
|
||||
*/
|
||||
class ScenarioRunner {
|
||||
class GTSAM_EXPORT ScenarioRunner {
|
||||
public:
|
||||
typedef imuBias::ConstantBias Bias;
|
||||
typedef boost::shared_ptr<PreintegrationParams> SharedParams;
|
||||
|
|
|
@ -38,7 +38,7 @@ namespace gtsam {
|
|||
* converging, and about how much work was required for the update. See member
|
||||
* variables for details and information about each entry.
|
||||
*/
|
||||
struct GTSAM_EXPORT ISAM2Result {
|
||||
struct ISAM2Result {
|
||||
/** The nonlinear error of all of the factors, \a including new factors and
|
||||
* variables added during the current call to ISAM2::update(). This error is
|
||||
* calculated using the following variable values:
|
||||
|
|
|
@ -29,7 +29,7 @@ namespace gtsam {
|
|||
* This struct is used by ISAM2::update() to pass additional parameters to
|
||||
* give the user a fine-grained control on how factors and relinearized, etc.
|
||||
*/
|
||||
struct GTSAM_EXPORT ISAM2UpdateParams {
|
||||
struct ISAM2UpdateParams {
|
||||
ISAM2UpdateParams() = default;
|
||||
|
||||
/** Indices of factors to remove from system (default: empty) */
|
||||
|
|
|
@ -23,7 +23,7 @@ namespace gtsam {
|
|||
* This factor does have the ability to perform relinearization under small-angle and
|
||||
* linearity assumptions if a linearization point is added.
|
||||
*/
|
||||
class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor {
|
||||
class LinearContainerFactor : public NonlinearFactor {
|
||||
protected:
|
||||
|
||||
GaussianFactor::shared_ptr factor_;
|
||||
|
@ -33,7 +33,7 @@ protected:
|
|||
LinearContainerFactor() {}
|
||||
|
||||
/** direct copy constructor */
|
||||
LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
|
||||
GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const boost::optional<Values>& linearizationPoint);
|
||||
|
||||
// Some handy typedefs
|
||||
typedef NonlinearFactor Base;
|
||||
|
@ -44,13 +44,13 @@ public:
|
|||
typedef boost::shared_ptr<This> shared_ptr;
|
||||
|
||||
/** Primary constructor: store a linear factor with optional linearization point */
|
||||
LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
|
||||
GTSAM_EXPORT LinearContainerFactor(const JacobianFactor& factor, const Values& linearizationPoint = Values());
|
||||
|
||||
/** Primary constructor: store a linear factor with optional linearization point */
|
||||
LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
|
||||
GTSAM_EXPORT LinearContainerFactor(const HessianFactor& factor, const Values& linearizationPoint = Values());
|
||||
|
||||
/** Constructor from shared_ptr */
|
||||
LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
|
||||
GTSAM_EXPORT LinearContainerFactor(const GaussianFactor::shared_ptr& factor, const Values& linearizationPoint = Values());
|
||||
|
||||
// Access
|
||||
|
||||
|
@ -59,10 +59,10 @@ public:
|
|||
// Testable
|
||||
|
||||
/** print */
|
||||
void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const;
|
||||
GTSAM_EXPORT void print(const std::string& s = "", const KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const;
|
||||
|
||||
/** Check if two factors are equal */
|
||||
bool equals(const NonlinearFactor& f, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const NonlinearFactor& f, double tol = 1e-9) const;
|
||||
|
||||
// NonlinearFactor
|
||||
|
||||
|
@ -74,10 +74,10 @@ public:
|
|||
*
|
||||
* @return nonlinear error if linearizationPoint present, zero otherwise
|
||||
*/
|
||||
double error(const Values& c) const;
|
||||
GTSAM_EXPORT double error(const Values& c) const;
|
||||
|
||||
/** get the dimension of the factor: rows of linear factor */
|
||||
size_t dim() const;
|
||||
GTSAM_EXPORT size_t dim() const;
|
||||
|
||||
/** Extract the linearization point used in recalculating error */
|
||||
const boost::optional<Values>& linearizationPoint() const { return linearizationPoint_; }
|
||||
|
@ -98,17 +98,17 @@ public:
|
|||
* TODO: better approximation of relinearization
|
||||
* TODO: switchable modes for approximation technique
|
||||
*/
|
||||
GaussianFactor::shared_ptr linearize(const Values& c) const;
|
||||
GTSAM_EXPORT GaussianFactor::shared_ptr linearize(const Values& c) const;
|
||||
|
||||
/**
|
||||
* Creates an anti-factor directly
|
||||
*/
|
||||
GaussianFactor::shared_ptr negateToGaussian() const;
|
||||
GTSAM_EXPORT GaussianFactor::shared_ptr negateToGaussian() const;
|
||||
|
||||
/**
|
||||
* Creates the equivalent anti-factor as another LinearContainerFactor.
|
||||
*/
|
||||
NonlinearFactor::shared_ptr negateToNonlinear() const;
|
||||
GTSAM_EXPORT NonlinearFactor::shared_ptr negateToNonlinear() const;
|
||||
|
||||
/**
|
||||
* Creates a shared_ptr clone of the factor - needs to be specialized to allow
|
||||
|
@ -127,31 +127,31 @@ public:
|
|||
/**
|
||||
* Simple checks whether this is a Jacobian or Hessian factor
|
||||
*/
|
||||
bool isJacobian() const;
|
||||
bool isHessian() const;
|
||||
GTSAM_EXPORT bool isJacobian() const;
|
||||
GTSAM_EXPORT bool isHessian() const;
|
||||
|
||||
/** Casts to JacobianFactor */
|
||||
boost::shared_ptr<JacobianFactor> toJacobian() const;
|
||||
GTSAM_EXPORT boost::shared_ptr<JacobianFactor> toJacobian() const;
|
||||
|
||||
/** Casts to HessianFactor */
|
||||
boost::shared_ptr<HessianFactor> toHessian() const;
|
||||
GTSAM_EXPORT boost::shared_ptr<HessianFactor> toHessian() const;
|
||||
|
||||
/**
|
||||
* Utility function for converting linear graphs to nonlinear graphs
|
||||
* consisting of LinearContainerFactors.
|
||||
*/
|
||||
static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph,
|
||||
GTSAM_EXPORT static NonlinearFactorGraph ConvertLinearGraph(const GaussianFactorGraph& linear_graph,
|
||||
const Values& linearizationPoint = Values());
|
||||
|
||||
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
|
||||
static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph,
|
||||
GTSAM_EXPORT static NonlinearFactorGraph convertLinearGraph(const GaussianFactorGraph& linear_graph,
|
||||
const Values& linearizationPoint = Values()) {
|
||||
return ConvertLinearGraph(linear_graph, linearizationPoint);
|
||||
}
|
||||
#endif
|
||||
|
||||
protected:
|
||||
void initializeLinearizationPoint(const Values& linearizationPoint);
|
||||
GTSAM_EXPORT void initializeLinearizationPoint(const Values& linearizationPoint);
|
||||
|
||||
private:
|
||||
|
||||
|
|
|
@ -31,7 +31,7 @@ namespace gtsam {
|
|||
/** The common parameters for Nonlinear optimizers. Most optimizers
|
||||
* deriving from NonlinearOptimizer also subclass the parameters.
|
||||
*/
|
||||
class GTSAM_EXPORT NonlinearOptimizerParams {
|
||||
class NonlinearOptimizerParams {
|
||||
public:
|
||||
/** See NonlinearOptimizerParams::verbosity */
|
||||
enum Verbosity {
|
||||
|
@ -52,7 +52,7 @@ public:
|
|||
|
||||
virtual ~NonlinearOptimizerParams() {
|
||||
}
|
||||
virtual void print(const std::string& str = "") const;
|
||||
GTSAM_EXPORT virtual void print(const std::string& str = "") const;
|
||||
|
||||
size_t getMaxIterations() const { return maxIterations; }
|
||||
double getRelativeErrorTol() const { return relativeErrorTol; }
|
||||
|
@ -68,8 +68,8 @@ public:
|
|||
verbosity = verbosityTranslator(src);
|
||||
}
|
||||
|
||||
static Verbosity verbosityTranslator(const std::string &s) ;
|
||||
static std::string verbosityTranslator(Verbosity value) ;
|
||||
GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s) ;
|
||||
GTSAM_EXPORT static std::string verbosityTranslator(Verbosity value) ;
|
||||
|
||||
/** See NonlinearOptimizerParams::linearSolverType */
|
||||
enum LinearSolverType {
|
||||
|
@ -144,10 +144,10 @@ public:
|
|||
}
|
||||
|
||||
private:
|
||||
std::string linearSolverTranslator(LinearSolverType linearSolverType) const;
|
||||
LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const;
|
||||
std::string orderingTypeTranslator(Ordering::OrderingType type) const;
|
||||
Ordering::OrderingType orderingTypeTranslator(const std::string& type) const;
|
||||
GTSAM_EXPORT std::string linearSolverTranslator(LinearSolverType linearSolverType) const;
|
||||
GTSAM_EXPORT LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const;
|
||||
GTSAM_EXPORT std::string orderingTypeTranslator(Ordering::OrderingType type) const;
|
||||
GTSAM_EXPORT Ordering::OrderingType orderingTypeTranslator(const std::string& type) const;
|
||||
};
|
||||
|
||||
// For backward compatibility:
|
||||
|
|
|
@ -422,7 +422,7 @@ namespace gtsam {
|
|||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
class GTSAM_EXPORT ValuesKeyAlreadyExists : public std::exception {
|
||||
class ValuesKeyAlreadyExists : public std::exception {
|
||||
protected:
|
||||
const Key key_; ///< The key that already existed
|
||||
|
||||
|
@ -440,11 +440,11 @@ namespace gtsam {
|
|||
Key key() const throw() { return key_; }
|
||||
|
||||
/// The message to be displayed to the user
|
||||
virtual const char* what() const throw();
|
||||
GTSAM_EXPORT virtual const char* what() const throw();
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
class GTSAM_EXPORT ValuesKeyDoesNotExist : public std::exception {
|
||||
class ValuesKeyDoesNotExist : public std::exception {
|
||||
protected:
|
||||
const char* operation_; ///< The operation that attempted to access the key
|
||||
const Key key_; ///< The key that does not exist
|
||||
|
@ -463,11 +463,11 @@ namespace gtsam {
|
|||
Key key() const throw() { return key_; }
|
||||
|
||||
/// The message to be displayed to the user
|
||||
virtual const char* what() const throw();
|
||||
GTSAM_EXPORT virtual const char* what() const throw();
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
class GTSAM_EXPORT ValuesIncorrectType : public std::exception {
|
||||
class ValuesIncorrectType : public std::exception {
|
||||
protected:
|
||||
const Key key_; ///< The key requested
|
||||
const std::type_info& storedTypeId_;
|
||||
|
@ -494,11 +494,11 @@ namespace gtsam {
|
|||
const std::type_info& requestedTypeId() const { return requestedTypeId_; }
|
||||
|
||||
/// The message to be displayed to the user
|
||||
virtual const char* what() const throw();
|
||||
GTSAM_EXPORT virtual const char* what() const throw();
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
class GTSAM_EXPORT DynamicValuesMismatched : public std::exception {
|
||||
class DynamicValuesMismatched : public std::exception {
|
||||
|
||||
public:
|
||||
DynamicValuesMismatched() throw() {}
|
||||
|
@ -511,7 +511,7 @@ namespace gtsam {
|
|||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
class GTSAM_EXPORT NoMatchFoundForFixed: public std::exception {
|
||||
class NoMatchFoundForFixed: public std::exception {
|
||||
|
||||
protected:
|
||||
const size_t M1_, N1_;
|
||||
|
@ -528,7 +528,7 @@ namespace gtsam {
|
|||
virtual ~NoMatchFoundForFixed() throw () {
|
||||
}
|
||||
|
||||
virtual const char* what() const throw ();
|
||||
GTSAM_EXPORT virtual const char* what() const throw ();
|
||||
};
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -27,7 +27,7 @@ namespace gtsam {
|
|||
/** Symbolic Bayes Net
|
||||
* \nosubgrouping
|
||||
*/
|
||||
class GTSAM_EXPORT SymbolicBayesNet : public FactorGraph<SymbolicConditional> {
|
||||
class SymbolicBayesNet : public FactorGraph<SymbolicConditional> {
|
||||
|
||||
public:
|
||||
|
||||
|
@ -61,14 +61,14 @@ namespace gtsam {
|
|||
/// @{
|
||||
|
||||
/** Check equality */
|
||||
bool equals(const This& bn, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const This& bn, double tol = 1e-9) const;
|
||||
|
||||
/// @}
|
||||
|
||||
/// @name Standard Interface
|
||||
/// @{
|
||||
|
||||
void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||
GTSAM_EXPORT void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
|
||||
|
||||
/// @}
|
||||
|
||||
|
|
|
@ -30,7 +30,7 @@ namespace gtsam {
|
|||
|
||||
/* ************************************************************************* */
|
||||
/// A clique in a SymbolicBayesTree
|
||||
class GTSAM_EXPORT SymbolicBayesTreeClique :
|
||||
class SymbolicBayesTreeClique :
|
||||
public BayesTreeCliqueBase<SymbolicBayesTreeClique, SymbolicFactorGraph>
|
||||
{
|
||||
public:
|
||||
|
@ -45,7 +45,7 @@ namespace gtsam {
|
|||
/* ************************************************************************* */
|
||||
/// A Bayes tree that represents the connectivity between variables but is not associated with any
|
||||
/// probability functions.
|
||||
class GTSAM_EXPORT SymbolicBayesTree :
|
||||
class SymbolicBayesTree :
|
||||
public BayesTree<SymbolicBayesTreeClique>
|
||||
{
|
||||
private:
|
||||
|
@ -59,7 +59,7 @@ namespace gtsam {
|
|||
SymbolicBayesTree() {}
|
||||
|
||||
/** check equality */
|
||||
bool equals(const This& other, double tol = 1e-9) const;
|
||||
GTSAM_EXPORT bool equals(const This& other, double tol = 1e-9) const;
|
||||
|
||||
private:
|
||||
/** Serialization function */
|
||||
|
|
|
@ -44,6 +44,12 @@ foreach(subdir ${gtsam_unstable_subdirs})
|
|||
add_subdirectory(${subdir})
|
||||
endforeach(subdir)
|
||||
|
||||
# dllexport.h
|
||||
set(library_name GTSAM_UNSTABLE) # For substitution in dllexport.h.in
|
||||
configure_file("${GTSAM_SOURCE_DIR}/cmake/dllexport.h.in" "dllexport.h")
|
||||
list(APPEND gtsam_unstable_srcs "${PROJECT_BINARY_DIR}/dllexport.h")
|
||||
install(FILES "${PROJECT_BINARY_DIR}/dllexport.h" DESTINATION include/gtsam_unstable)
|
||||
|
||||
# assemble gtsam_unstable components
|
||||
set(gtsam_unstable_srcs
|
||||
${base_srcs}
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
*/
|
||||
|
||||
#include <gtsam/global_includes.h>
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <string>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -1,36 +0,0 @@
|
|||
/* ----------------------------------------------------------------------------
|
||||
|
||||
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
||||
* Atlanta, Georgia 30332-0415
|
||||
* All Rights Reserved
|
||||
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
||||
|
||||
* See LICENSE for the license information
|
||||
|
||||
* -------------------------------------------------------------------------- */
|
||||
|
||||
/**
|
||||
* @file dllexport.h
|
||||
* @brief Symbols for exporting classes and methods from DLLs
|
||||
* @author Richard Roberts
|
||||
* @date Mar 9, 2013
|
||||
*/
|
||||
|
||||
#ifdef _WIN32
|
||||
# ifdef GTSAM_UNSTABLE_EXPORTS
|
||||
# define GTSAM_UNSTABLE_EXPORT __declspec(dllexport)
|
||||
# define GTSAM_UNSTABLE_EXTERN_EXPORT __declspec(dllexport) extern
|
||||
# else
|
||||
# ifndef GTSAM_UNSTABLE_IMPORT_STATIC
|
||||
# define GTSAM_UNSTABLE_EXPORT __declspec(dllimport)
|
||||
# define GTSAM_UNSTABLE_EXTERN_EXPORT __declspec(dllimport)
|
||||
# else /* GTSAM_UNSTABLE_IMPORT_STATIC */
|
||||
# define GTSAM_UNSTABLE_EXPORT
|
||||
# define GTSAM_UNSTABLE_EXTERN_EXPORT extern
|
||||
# endif /* GTSAM_UNSTABLE_IMPORT_STATIC */
|
||||
# endif /* GTSAM_UNSTABLE_EXPORTS */
|
||||
#else /* _WIN32 */
|
||||
# define GTSAM_UNSTABLE_EXPORT
|
||||
# define GTSAM_UNSTABLE_EXTERN_EXPORT extern
|
||||
#endif
|
||||
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/discrete/DiscreteFactor.h>
|
||||
#include <boost/assign.hpp>
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/base/ProductLieGroup.h>
|
||||
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/geometry/Rot2.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <cmath>
|
||||
#include <iosfwd>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -60,10 +61,10 @@ public:
|
|||
}
|
||||
|
||||
/** print with optional string */
|
||||
void print(const std::string& s = "") const;
|
||||
GTSAM_UNSTABLE_EXPORT void print(const std::string& s = "") const;
|
||||
|
||||
/** equals with an tolerance */
|
||||
bool equals(const Event& other, double tol = 1e-9) const;
|
||||
GTSAM_UNSTABLE_EXPORT bool equals(const Event& other, double tol = 1e-9) const;
|
||||
|
||||
/// Updates a with tangent space delta
|
||||
inline Event retract(const Vector4& v) const {
|
||||
|
@ -94,6 +95,6 @@ public:
|
|||
|
||||
// Define GTSAM traits
|
||||
template<>
|
||||
struct GTSAM_EXPORT traits<Event> : internal::Manifold<Event> {};
|
||||
struct traits<Event> : internal::Manifold<Event> {};
|
||||
|
||||
} //\ namespace gtsam
|
||||
|
|
|
@ -11,7 +11,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
|
||||
|
|
|
@ -6,7 +6,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
#include <gtsam/linear/Sampler.h>
|
||||
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
#include <gtsam/geometry/Point3.h>
|
||||
#include <gtsam/base/Lie.h>
|
||||
#include <gtsam/base/Manifold.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
||||
|
@ -49,59 +50,59 @@ public:
|
|||
/// @{
|
||||
|
||||
/// Default constructor
|
||||
Similarity3();
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3();
|
||||
|
||||
/// Construct pure scaling
|
||||
Similarity3(double s);
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3(double s);
|
||||
|
||||
/// Construct from GTSAM types
|
||||
Similarity3(const Rot3& R, const Point3& t, double s);
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3(const Rot3& R, const Point3& t, double s);
|
||||
|
||||
/// Construct from Eigen types
|
||||
Similarity3(const Matrix3& R, const Vector3& t, double s);
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s);
|
||||
|
||||
/// Construct from matrix [R t; 0 s^-1]
|
||||
Similarity3(const Matrix4& T);
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3(const Matrix4& T);
|
||||
|
||||
/// @}
|
||||
/// @name Testable
|
||||
/// @{
|
||||
|
||||
/// Compare with tolerance
|
||||
bool equals(const Similarity3& sim, double tol) const;
|
||||
GTSAM_UNSTABLE_EXPORT bool equals(const Similarity3& sim, double tol) const;
|
||||
|
||||
/// Exact equality
|
||||
bool operator==(const Similarity3& other) const;
|
||||
GTSAM_UNSTABLE_EXPORT bool operator==(const Similarity3& other) const;
|
||||
|
||||
/// Print with optional string
|
||||
void print(const std::string& s) const;
|
||||
GTSAM_UNSTABLE_EXPORT void print(const std::string& s) const;
|
||||
|
||||
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p);
|
||||
GTSAM_UNSTABLE_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p);
|
||||
|
||||
/// @}
|
||||
/// @name Group
|
||||
/// @{
|
||||
|
||||
/// Return an identity transform
|
||||
static Similarity3 identity();
|
||||
GTSAM_UNSTABLE_EXPORT static Similarity3 identity();
|
||||
|
||||
/// Composition
|
||||
Similarity3 operator*(const Similarity3& T) const;
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3 operator*(const Similarity3& T) const;
|
||||
|
||||
/// Return the inverse
|
||||
Similarity3 inverse() const;
|
||||
GTSAM_UNSTABLE_EXPORT Similarity3 inverse() const;
|
||||
|
||||
/// @}
|
||||
/// @name Group action on Point3
|
||||
/// @{
|
||||
|
||||
/// Action on a point p is s*(R*p+t)
|
||||
Point3 transformFrom(const Point3& p, //
|
||||
GTSAM_UNSTABLE_EXPORT Point3 transformFrom(const Point3& p, //
|
||||
OptionalJacobian<3, 7> H1 = boost::none, //
|
||||
OptionalJacobian<3, 3> H2 = boost::none) const;
|
||||
|
||||
/** syntactic sugar for transformFrom */
|
||||
Point3 operator*(const Point3& p) const;
|
||||
GTSAM_UNSTABLE_EXPORT Point3 operator*(const Point3& p) const;
|
||||
|
||||
/// @}
|
||||
/// @name Lie Group
|
||||
|
@ -110,12 +111,12 @@ public:
|
|||
/** Log map at the identity
|
||||
* \f$ [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \f$
|
||||
*/
|
||||
static Vector7 Logmap(const Similarity3& s, //
|
||||
GTSAM_UNSTABLE_EXPORT static Vector7 Logmap(const Similarity3& s, //
|
||||
OptionalJacobian<7, 7> Hm = boost::none);
|
||||
|
||||
/** Exponential map at the identity
|
||||
*/
|
||||
static Similarity3 Expmap(const Vector7& v, //
|
||||
GTSAM_UNSTABLE_EXPORT static Similarity3 Expmap(const Vector7& v, //
|
||||
OptionalJacobian<7, 7> Hm = boost::none);
|
||||
|
||||
/// Chart at the origin
|
||||
|
@ -136,17 +137,17 @@ public:
|
|||
* @return 4*4 element of Lie algebra that can be exponentiated
|
||||
* TODO(frank): rename to Hat, make part of traits
|
||||
*/
|
||||
static Matrix4 wedge(const Vector7& xi);
|
||||
GTSAM_UNSTABLE_EXPORT static Matrix4 wedge(const Vector7& xi);
|
||||
|
||||
/// Project from one tangent space to another
|
||||
Matrix7 AdjointMap() const;
|
||||
GTSAM_UNSTABLE_EXPORT Matrix7 AdjointMap() const;
|
||||
|
||||
/// @}
|
||||
/// @name Standard interface
|
||||
/// @{
|
||||
|
||||
/// Calculate 4*4 matrix group equivalent
|
||||
const Matrix4 matrix() const;
|
||||
GTSAM_UNSTABLE_EXPORT const Matrix4 matrix() const;
|
||||
|
||||
/// Return a GTSAM rotation
|
||||
const Rot3& rotation() const {
|
||||
|
@ -165,7 +166,7 @@ public:
|
|||
|
||||
/// Convert to a rigid body pose (R, s*t)
|
||||
/// TODO(frank): why is this here? Red flag! Definitely don't have it as a cast.
|
||||
operator Pose3() const;
|
||||
GTSAM_UNSTABLE_EXPORT operator Pose3() const;
|
||||
|
||||
/// Dimensionality of tangent space = 7 DOF - used to autodetect sizes
|
||||
inline static size_t Dim() {
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
// \callgraph
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
#include <gtsam/linear/GaussianFactorGraph.h>
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
// \callgraph
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
|
||||
#include <gtsam/nonlinear/Values.h>
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/linear/JacobianFactor.h>
|
||||
#include <gtsam/linear/HessianFactor.h>
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
#define AHRS_H_
|
||||
|
||||
#include "Mechanization_bRn2.h"
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/linear/KalmanFilter.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
|
||||
#include <gtsam/geometry/Rot3.h>
|
||||
#include <gtsam/base/Vector.h>
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <list>
|
||||
|
||||
namespace gtsam {
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/geometry/Pose3.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <gtsam_unstable/base/dllexport.h>
|
||||
#include <gtsam_unstable/dllexport.h>
|
||||
#include <gtsam/nonlinear/NonlinearFactor.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/geometry/Pose2.h>
|
||||
|
|
|
@ -153,13 +153,13 @@ TEST(timeGaussianFactorGraph, linearTime)
|
|||
// Switch to 100*100 grid = 10K poses
|
||||
// 1879: 15.6498 15.3851 15.5279
|
||||
|
||||
int size = 100;
|
||||
int grid_size = 100;
|
||||
|
||||
/* ************************************************************************* */
|
||||
TEST(timeGaussianFactorGraph, planar_old)
|
||||
{
|
||||
cout << "Timing planar - original version" << endl;
|
||||
double time = timePlanarSmoother(size);
|
||||
double time = timePlanarSmoother(grid_size);
|
||||
cout << "timeGaussianFactorGraph : " << time << endl;
|
||||
//DOUBLES_EQUAL(5.97,time,0.1);
|
||||
}
|
||||
|
@ -168,7 +168,7 @@ TEST(timeGaussianFactorGraph, planar_old)
|
|||
TEST(timeGaussianFactorGraph, planar_new)
|
||||
{
|
||||
cout << "Timing planar - new version" << endl;
|
||||
double time = timePlanarSmoother(size, false);
|
||||
double time = timePlanarSmoother(grid_size, false);
|
||||
cout << "timeGaussianFactorGraph : " << time << endl;
|
||||
//DOUBLES_EQUAL(5.97,time,0.1);
|
||||
}
|
||||
|
@ -177,7 +177,7 @@ TEST(timeGaussianFactorGraph, planar_new)
|
|||
TEST(timeGaussianFactorGraph, planar_eliminate_old)
|
||||
{
|
||||
cout << "Timing planar Eliminate - original version" << endl;
|
||||
double time = timePlanarSmootherEliminate(size);
|
||||
double time = timePlanarSmootherEliminate(grid_size);
|
||||
cout << "timeGaussianFactorGraph : " << time << endl;
|
||||
//DOUBLES_EQUAL(5.97,time,0.1);
|
||||
}
|
||||
|
@ -186,7 +186,7 @@ TEST(timeGaussianFactorGraph, planar_eliminate_old)
|
|||
TEST(timeGaussianFactorGraph, planar_eliminate_new)
|
||||
{
|
||||
cout << "Timing planar Eliminate - new version" << endl;
|
||||
double time = timePlanarSmootherEliminate(size, false);
|
||||
double time = timePlanarSmootherEliminate(grid_size, false);
|
||||
cout << "timeGaussianFactorGraph : " << time << endl;
|
||||
//DOUBLES_EQUAL(5.97,time,0.1);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue