Moved the subdirectories that compile into libgtsam.la into a 'gtsam' subdirectory. Hopefully a good fix for the problem we had trying to make a gtsam distribution, that the source directory may not be called 'gtsam'.
parent
b3bcf0d236
commit
2c90e3d836
|
@ -8,6 +8,5 @@ sources = Failure.cpp SimpleString.cpp Test.cpp TestRegistry.cpp TestResult.cpp
|
||||||
headers += $(sources:.cpp=.h)
|
headers += $(sources:.cpp=.h)
|
||||||
|
|
||||||
CppUnitLitedir = $(pkgincludedir)/CppUnitLite
|
CppUnitLitedir = $(pkgincludedir)/CppUnitLite
|
||||||
CppUnitLite_HEADERS = $(headers)
|
|
||||||
noinst_LIBRARIES = libCppUnitLite.a
|
noinst_LIBRARIES = libCppUnitLite.a
|
||||||
libCppUnitLite_a_SOURCES = $(sources)
|
libCppUnitLite_a_SOURCES = $(sources)
|
||||||
|
|
31
Makefile.am
31
Makefile.am
|
@ -11,37 +11,8 @@ ACLOCAL_AMFLAGS = -I m4
|
||||||
AUTOMAKE_OPTIONS = foreign nostdinc
|
AUTOMAKE_OPTIONS = foreign nostdinc
|
||||||
|
|
||||||
# All the sub-directories that need to be built
|
# All the sub-directories that need to be built
|
||||||
SUBDIRS = CppUnitLite base geometry inference linear nonlinear slam . tests wrap examples
|
SUBDIRS = CppUnitLite gtsam tests examples
|
||||||
|
|
||||||
# And the corresponding libraries produced
|
|
||||||
SUBLIBS = base/libbase.la geometry/libgeometry.la inference/libinference.la \
|
|
||||||
linear/liblinear.la nonlinear/libnonlinear.la slam/libslam.la
|
|
||||||
|
|
||||||
# TODO: UFconfig, CCOLAMD, and LDL automake magic without adding or touching any file
|
|
||||||
# in those directories as to not invalidate the LGPL license
|
|
||||||
# See some possibilities in
|
|
||||||
# http://www.gnu.org/software/hello/manual/automake/Third_002dParty-Makefiles.html
|
|
||||||
|
|
||||||
# The following lines specify the actual shared library to be built with libtool
|
|
||||||
lib_LTLIBRARIES = libgtsam.la
|
|
||||||
libgtsam_la_SOURCES =
|
|
||||||
nodist_EXTRA_libgtsam_la_SOURCES = dummy.cxx
|
|
||||||
libgtsam_la_LIBADD = $(SUBLIBS) -L$(CCOLAMDLib) $(BOOST_LDFLAGS) -lccolamd
|
|
||||||
libgtsam_la_LDFLAGS = -no-undefined -version-info 0:0:0
|
|
||||||
|
|
||||||
if USE_ACCELERATE_MACOS
|
|
||||||
libgtsam_la_LDFLAGS += -Wl,/System/Library/Frameworks/Accelerate.framework/Accelerate
|
|
||||||
endif
|
|
||||||
|
|
||||||
# Add these files to make sure they're in the distribution
|
# Add these files to make sure they're in the distribution
|
||||||
noinst_HEADERS = gtsam.h
|
|
||||||
EXTRA_DIST = autogen.sh configure.ac THANKS
|
EXTRA_DIST = autogen.sh configure.ac THANKS
|
||||||
|
|
||||||
# Todo: Also do CppUnitLite with automake
|
|
||||||
dist-hook:
|
|
||||||
mkdir $(distdir)/config
|
|
||||||
mkdir $(distdir)/matlab
|
|
||||||
cp -p $(srcdir)/matlab/*.m $(distdir)/matlab
|
|
||||||
cp -r $(srcdir)/wrap/expected $(distdir)/wrap
|
|
||||||
|
|
||||||
|
|
||||||
|
|
23
configure.ac
23
configure.ac
|
@ -4,18 +4,16 @@
|
||||||
AC_PREREQ(2.59)
|
AC_PREREQ(2.59)
|
||||||
AC_INIT(gtsam, 0.9.0, dellaert@cc.gatech.edu)
|
AC_INIT(gtsam, 0.9.0, dellaert@cc.gatech.edu)
|
||||||
AM_INIT_AUTOMAKE(gtsam, 0.9.0)
|
AM_INIT_AUTOMAKE(gtsam, 0.9.0)
|
||||||
AC_OUTPUT(Makefile CppUnitLite/Makefile base/Makefile inference/Makefile linear/Makefile geometry/Makefile nonlinear/Makefile slam/Makefile tests/Makefile wrap/Makefile examples/Makefile examples/vSLAMexample/Makefile)
|
|
||||||
AC_CONFIG_MACRO_DIR([m4])
|
AC_CONFIG_MACRO_DIR([m4])
|
||||||
AC_CONFIG_HEADER([config.h])
|
AC_CONFIG_HEADER([config.h])
|
||||||
AC_CONFIG_SRCDIR([CppUnitLite/Test.cpp])
|
AC_CONFIG_SRCDIR([CppUnitLite/Test.cpp])
|
||||||
AC_CONFIG_SRCDIR([base/DSFVector.cpp])
|
AC_CONFIG_SRCDIR([gtsam/base/DSFVector.cpp])
|
||||||
AC_CONFIG_SRCDIR([geometry/Cal3_S2.cpp])
|
AC_CONFIG_SRCDIR([gtsam/geometry/Cal3_S2.cpp])
|
||||||
AC_CONFIG_SRCDIR([inference/SymbolicFactorGraph.cpp])
|
AC_CONFIG_SRCDIR([gtsam/inference/SymbolicFactorGraph.cpp])
|
||||||
AC_CONFIG_SRCDIR([linear/GaussianFactor.cpp])
|
AC_CONFIG_SRCDIR([gtsam/linear/GaussianFactor.cpp])
|
||||||
AC_CONFIG_SRCDIR([nonlinear/NonlinearOptimizer.cpp])
|
AC_CONFIG_SRCDIR([gtsam/nonlinear/NonlinearOptimizer.cpp])
|
||||||
AC_CONFIG_SRCDIR([slam/pose2SLAM.cpp])
|
AC_CONFIG_SRCDIR([gtsam/slam/pose2SLAM.cpp])
|
||||||
AC_CONFIG_SRCDIR([tests/testSQP.cpp])
|
AC_CONFIG_SRCDIR([tests/testSQP.cpp])
|
||||||
AC_CONFIG_SRCDIR([wrap/wrap.cpp])
|
|
||||||
AC_CONFIG_SRCDIR([examples/SimpleRotation.cpp])
|
AC_CONFIG_SRCDIR([examples/SimpleRotation.cpp])
|
||||||
|
|
||||||
# Check for OS
|
# Check for OS
|
||||||
|
@ -169,4 +167,13 @@ AC_ARG_WITH([ccolamd-lib],
|
||||||
[CCOLAMDLib=${HOME}/lib])
|
[CCOLAMDLib=${HOME}/lib])
|
||||||
AC_SUBST([CCOLAMDLib])
|
AC_SUBST([CCOLAMDLib])
|
||||||
|
|
||||||
|
# For now we require blas, atlas, and lapack
|
||||||
|
#AM_COND_IF([test x$ISMAC = xtrue],
|
||||||
|
# [LINALG_CPPFLAGS="-I/System/Library/Frameworks/vecLib.framework/Headers ${CCOLAMDInc} -DGT_USE_LAPACK"],
|
||||||
|
# [LINALG_CPPFLAGS="${CCOLAMDInc} -DGT_USE_LAPACK"])
|
||||||
|
#AM_COND_IF([test x$ISMAC = xtrue],
|
||||||
|
# [LINALG_LDFLAGS="-Wl,/System/Library/Frameworks/Accelerate.framework/Accelerate ${CCOLAMDLib}"],
|
||||||
|
# [LINALG_LDFLAGS="-lcblas -latlas -llapack ${CCOLAMDLib}"])
|
||||||
|
|
||||||
|
AC_CONFIG_FILES([CppUnitLite/Makefile gtsam/base/Makefile gtsam/geometry/Makefile gtsam/inference/Makefile gtsam/linear/Makefile gtsam/nonlinear/Makefile gtsam/slam/Makefile gtsam/Makefile tests/Makefile examples/Makefile Makefile])
|
||||||
AC_OUTPUT
|
AC_OUTPUT
|
||||||
|
|
|
@ -22,9 +22,9 @@ noinst_PROGRAMS += Pose2SLAMwSPCG_advanced # Solves a simple Pose2 SLAM examp
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
# rules to build local programs
|
# rules to build local programs
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)/..
|
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)
|
||||||
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||||
LDADD = ../libgtsam.la
|
LDADD = ../gtsam/libgtsam.la
|
||||||
AM_DEFAULT_SOURCE_EXT = .cpp
|
AM_DEFAULT_SOURCE_EXT = .cpp
|
||||||
|
|
||||||
# rule to run an executable
|
# rule to run an executable
|
||||||
|
|
|
@ -23,7 +23,7 @@ vISAMexample_SOURCES = vISAMexample.cpp Feature2D.cpp vSLAMutils.cpp
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)/..
|
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)/..
|
||||||
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||||
LDADD = ../../libgtsam.la
|
LDADD = ../../gtsam/libgtsam.la
|
||||||
AM_DEFAULT_SOURCE_EXT = .cpp
|
AM_DEFAULT_SOURCE_EXT = .cpp
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -50,7 +50,7 @@ base_HEADERS = $(headers)
|
||||||
noinst_LTLIBRARIES = libbase.la
|
noinst_LTLIBRARIES = libbase.la
|
||||||
libbase_la_SOURCES = $(sources)
|
libbase_la_SOURCES = $(sources)
|
||||||
|
|
||||||
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)/..
|
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(CCOLAMDInc) -I$(top_srcdir)
|
||||||
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||||
|
|
||||||
if USE_BLAS
|
if USE_BLAS
|
||||||
|
@ -68,7 +68,7 @@ endif
|
||||||
TESTS = $(check_PROGRAMS)
|
TESTS = $(check_PROGRAMS)
|
||||||
AM_DEFAULT_SOURCE_EXT = .cpp
|
AM_DEFAULT_SOURCE_EXT = .cpp
|
||||||
AM_LDFLAGS += $(boost_serialization) -L$(CCOLAMDLib) -lccolamd
|
AM_LDFLAGS += $(boost_serialization) -L$(CCOLAMDLib) -lccolamd
|
||||||
LDADD = libbase.la ../CppUnitLite/libCppUnitLite.a
|
LDADD = libbase.la ../../CppUnitLite/libCppUnitLite.a
|
||||||
|
|
||||||
if USE_BLAS_LINUX
|
if USE_BLAS_LINUX
|
||||||
AM_LDFLAGS += -lcblas -latlas
|
AM_LDFLAGS += -lcblas -latlas
|
|
@ -22,7 +22,7 @@
|
||||||
#include <boost/assign/std/list.hpp> // for +=
|
#include <boost/assign/std/list.hpp> // for +=
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/BTree.h>
|
#include <gtsam/base/BTree.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
|
@ -21,7 +21,7 @@
|
||||||
#include <boost/assign/std/list.hpp>
|
#include <boost/assign/std/list.hpp>
|
||||||
#include <boost/assign/std/set.hpp>
|
#include <boost/assign/std/set.hpp>
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/DSF.h>
|
#include <gtsam/base/DSF.h>
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include <boost/assign/std/list.hpp>
|
#include <boost/assign/std/list.hpp>
|
||||||
#include <boost/assign/std/set.hpp>
|
#include <boost/assign/std/set.hpp>
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/DSFVector.h>
|
#include <gtsam/base/DSFVector.h>
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/DenseQRUtil.h>
|
#include <gtsam/base/DenseQRUtil.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
|
@ -14,7 +14,7 @@
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/FixedVector.h>
|
#include <gtsam/base/FixedVector.h>
|
||||||
|
|
|
@ -14,7 +14,7 @@
|
||||||
* @author Kai Ni
|
* @author Kai Ni
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/LieScalar.h>
|
#include <gtsam/base/LieScalar.h>
|
||||||
|
|
|
@ -14,7 +14,7 @@
|
||||||
* @author Alex Cunningham
|
* @author Alex Cunningham
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/LieVector.h>
|
#include <gtsam/base/LieVector.h>
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <boost/tuple/tuple.hpp>
|
#include <boost/tuple/tuple.hpp>
|
||||||
#include <boost/foreach.hpp>
|
#include <boost/foreach.hpp>
|
||||||
#include <boost/numeric/ublas/matrix_proxy.hpp>
|
#include <boost/numeric/ublas/matrix_proxy.hpp>
|
|
@ -16,7 +16,7 @@
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <boost/tuple/tuple.hpp>
|
#include <boost/tuple/tuple.hpp>
|
||||||
#include <gtsam/base/Vector.h>
|
#include <gtsam/base/Vector.h>
|
||||||
|
|
|
@ -41,7 +41,7 @@ geometrydir = $(pkgincludedir)/geometry
|
||||||
geometry_HEADERS = $(headers)
|
geometry_HEADERS = $(headers)
|
||||||
noinst_LTLIBRARIES = libgeometry.la
|
noinst_LTLIBRARIES = libgeometry.la
|
||||||
libgeometry_la_SOURCES = $(sources)
|
libgeometry_la_SOURCES = $(sources)
|
||||||
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(top_srcdir)/..
|
AM_CPPFLAGS = $(BOOST_CPPFLAGS) -I$(top_srcdir)
|
||||||
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||||
|
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
|
@ -49,7 +49,7 @@ AM_LDFLAGS = $(BOOST_LDFLAGS)
|
||||||
#----------------------------------------------------------------------------------------------------
|
#----------------------------------------------------------------------------------------------------
|
||||||
TESTS = $(check_PROGRAMS)
|
TESTS = $(check_PROGRAMS)
|
||||||
AM_LDFLAGS += $(boost_serialization)
|
AM_LDFLAGS += $(boost_serialization)
|
||||||
LDADD = libgeometry.la ../base/libbase.la ../CppUnitLite/libCppUnitLite.a
|
LDADD = libgeometry.la ../base/libbase.la ../../CppUnitLite/libCppUnitLite.a
|
||||||
AM_DEFAULT_SOURCE_EXT = .cpp
|
AM_DEFAULT_SOURCE_EXT = .cpp
|
||||||
|
|
||||||
if USE_ACCELERATE_MACOS
|
if USE_ACCELERATE_MACOS
|
|
@ -14,7 +14,7 @@
|
||||||
* @brief Unit tests for transform derivatives
|
* @brief Unit tests for transform derivatives
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/geometry/Cal3_S2.h>
|
#include <gtsam/geometry/Cal3_S2.h>
|
||||||
|
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/geometry/CalibratedCamera.h>
|
#include <gtsam/geometry/CalibratedCamera.h>
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include <boost/assign/std/list.hpp> // for operator +=
|
#include <boost/assign/std/list.hpp> // for operator +=
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/geometry/tensors.h>
|
#include <gtsam/geometry/tensors.h>
|
||||||
#include <gtsam/geometry/tensorInterface.h>
|
#include <gtsam/geometry/tensorInterface.h>
|
|
@ -21,7 +21,7 @@
|
||||||
#include <boost/assign/std/list.hpp> // for operator +=
|
#include <boost/assign/std/list.hpp> // for operator +=
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/base/Testable.h>
|
#include <gtsam/base/Testable.h>
|
||||||
#include <gtsam/geometry/tensors.h>
|
#include <gtsam/geometry/tensors.h>
|
|
@ -15,7 +15,7 @@
|
||||||
* @author Frank Dellaert
|
* @author Frank Dellaert
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/geometry/Point2.h>
|
#include <gtsam/geometry/Point2.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
|
@ -14,7 +14,7 @@
|
||||||
* @brief Unit tests for Point3 class
|
* @brief Unit tests for Point3 class
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/geometry/Point3.h>
|
#include <gtsam/geometry/Point3.h>
|
||||||
|
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
|
@ -22,7 +22,7 @@
|
||||||
#include <boost/assign/std/vector.hpp> // for operator +=
|
#include <boost/assign/std/vector.hpp> // for operator +=
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/base/lieProxies.h>
|
#include <gtsam/base/lieProxies.h>
|
||||||
#include <gtsam/geometry/Pose2.h>
|
#include <gtsam/geometry/Pose2.h>
|
|
@ -15,7 +15,7 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/base/lieProxies.h>
|
#include <gtsam/base/lieProxies.h>
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
|
@ -15,7 +15,7 @@
|
||||||
* @author Frank Dellaert
|
* @author Frank Dellaert
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/geometry/Rot2.h>
|
#include <gtsam/geometry/Rot2.h>
|
||||||
|
|
|
@ -15,7 +15,7 @@
|
||||||
* @author Alireza Fathi
|
* @author Alireza Fathi
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <boost/math/constants/constants.hpp>
|
#include <boost/math/constants/constants.hpp>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/base/lieProxies.h>
|
#include <gtsam/base/lieProxies.h>
|
|
@ -18,7 +18,7 @@
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <iostream>
|
#include <iostream>
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/geometry/SimpleCamera.h>
|
#include <gtsam/geometry/SimpleCamera.h>
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
* @author Chris Beall
|
* @author Chris Beall
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/geometry/StereoCamera.h>
|
#include <gtsam/geometry/StereoCamera.h>
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
#include <boost/assign/std/list.hpp> // for operator +=
|
#include <boost/assign/std/list.hpp> // for operator +=
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
#include <gtsam/CppUnitLite/TestHarness.h>
|
#include <CppUnitLite/TestHarness.h>
|
||||||
|
|
||||||
#include <gtsam/geometry/tensors.h>
|
#include <gtsam/geometry/tensors.h>
|
||||||
#include <gtsam/geometry/tensorInterface.h>
|
#include <gtsam/geometry/tensorInterface.h>
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue