move LPSolver and QPSolver to unstable. Add script to compile lpsolve on Mac when doing cmake if it's not found.
parent
06e3f36f22
commit
ee52ca15dd
|
@ -178,14 +178,6 @@ if(GTSAM_WITH_EIGEN_MKL AND GTSAM_USE_EIGEN_MKL_OPENMP AND GTSAM_USE_EIGEN_MKL)
|
|||
endif()
|
||||
endif()
|
||||
|
||||
###############################################################################
|
||||
# Find lp_solve
|
||||
include(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/lp_solve_5.5/cmake/Findlpsolve.cmake)
|
||||
message("lpsolve_INCLUDE_DIRS: " ${lpsolve_INCLUDE_DIRS})
|
||||
include_directories(${lpsolve_INCLUDE_DIRS})
|
||||
list(APPEND GTSAM_ADDITIONAL_LIBRARIES ${lpsolve_LIBRARY})
|
||||
|
||||
|
||||
###############################################################################
|
||||
# Option for using system Eigen or GTSAM-bundled Eigen
|
||||
### Disabled until our patches are included in Eigen ###
|
||||
|
|
|
@ -386,7 +386,7 @@ namespace gtsam {
|
|||
|
||||
/**
|
||||
* eta for Hessian
|
||||
* Ignore duals parameters. It's only valid for constraints, which need to be JacobianFactor
|
||||
* Ignore duals parameters. It's only valid for constraints, which need to be a JacobianFactor
|
||||
*/
|
||||
VectorValues gradientAtZero(const boost::optional<const VectorValues&> negDuals = boost::none) const;
|
||||
|
||||
|
|
|
@ -446,12 +446,6 @@ TEST(HessianFactor, gradientAtZero)
|
|||
EXPECT(assert_equal(-A.transpose()*b, expectedG.vector(keys)));
|
||||
VectorValues actualG = factor.gradientAtZero();
|
||||
EXPECT(assert_equal(expectedG, actualG));
|
||||
|
||||
// test gradient at zero scaled with a dual variable
|
||||
Vector dual = (Vector(1) << 5.0);
|
||||
VectorValues actualGscaled = factor.gradientAtZero(dual);
|
||||
VectorValues expectedGscaled = pair_list_of<Key, Vector>(0, -g1*dual[0]) (1, -g2*dual[0]);
|
||||
EXPECT(assert_equal(expectedGscaled, actualGscaled));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -326,14 +326,6 @@ TEST(JacobianFactor, operators )
|
|||
EXPECT(assert_equal(-A.transpose()*b2, expectedG.vector(keys)));
|
||||
VectorValues actualG = lf.gradientAtZero();
|
||||
EXPECT(assert_equal(expectedG, actualG));
|
||||
|
||||
// test gradient at zero scaled by a dual vector
|
||||
Vector dual = (Vector(2) << 3.0, 5.0);
|
||||
VectorValues actualGscaled = lf.gradientAtZero(dual);
|
||||
VectorValues expectedGscaled;
|
||||
expectedGscaled.insert(1, (Vector(2) << 60,-50));
|
||||
expectedGscaled.insert(2, (Vector(2) << -60, 50));
|
||||
EXPECT(assert_equal(expectedGscaled, actualGscaled));
|
||||
}
|
||||
|
||||
/* ************************************************************************* */
|
||||
|
@ -584,7 +576,7 @@ TEST ( JacobianFactor, constraint_eliminate2 )
|
|||
Matrix m(1,2);
|
||||
Matrix Aempty = m.topRows(0);
|
||||
Vector bempty = m.block(0,0,0,1);
|
||||
JacobianFactor expectedLF(2, Aempty, bempty, noiseModel::Constrained::All(0));
|
||||
JacobianFactor expectedLF(2, Aempty, bempty, noiseModel::Diagonal::Sigmas(Vector()));
|
||||
EXPECT(assert_equal(expectedLF, *actual.second));
|
||||
|
||||
// verify CG
|
||||
|
|
|
@ -3,6 +3,7 @@
|
|||
set (gtsam_unstable_subdirs
|
||||
base
|
||||
geometry
|
||||
linear
|
||||
discrete
|
||||
dynamics
|
||||
nonlinear
|
||||
|
@ -28,6 +29,33 @@ set (excluded_headers # "")
|
|||
"${CMAKE_CURRENT_SOURCE_DIR}/slam/serialization.h"
|
||||
)
|
||||
|
||||
|
||||
#####################
|
||||
# Find lp_solve
|
||||
unset(lpsolve_LIBRARY CACHE)
|
||||
unset(lpsolve_INCLUDE_DIRS CACHE)
|
||||
include(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/lp_solve_5.5/cmake/Findlpsolve.cmake)
|
||||
# If lpsolve_LIBRARY is not found, recompile the library
|
||||
message("lpsolve_LIBRARY: " ${lpsolve_LIBRARY} " ...")
|
||||
if(NOT lpsolve_LIBRARY)
|
||||
message("Building lpsolve. Please wait...")
|
||||
# TODO: customize for other platforms
|
||||
execute_process(COMMAND sh ccc.osx
|
||||
WORKING_DIRECTORY ${lpsolve_BUILD_PATH}
|
||||
OUTPUT_QUIET
|
||||
ERROR_QUIET)
|
||||
#set(lpsolve_INCLUDE_DIRS ${lpsolve_BUILD_PATH}/../)
|
||||
#set(lpsolve_LIBRARY ${lpsolve_BUILD_PATH}/liblpsolve55.a)
|
||||
include(${CMAKE_SOURCE_DIR}/gtsam/3rdparty/lp_solve_5.5/cmake/Findlpsolve.cmake)
|
||||
message("Done!")
|
||||
endif()
|
||||
message("lpsolve_INCLUDE_DIRS: " ${lpsolve_INCLUDE_DIRS})
|
||||
message("lpsolve_LIBRARY: " ${lpsolve_LIBRARY})
|
||||
|
||||
include_directories(${lpsolve_INCLUDE_DIRS})
|
||||
list(APPEND GTSAM_UNSTABLE_ADDITIONAL_LIBRARIES ${lpsolve_LIBRARY})
|
||||
#####################
|
||||
|
||||
# assemble core libraries
|
||||
foreach(subdir ${gtsam_unstable_subdirs})
|
||||
# Build convenience libraries
|
||||
|
@ -47,6 +75,7 @@ endforeach(subdir)
|
|||
set(gtsam_unstable_srcs
|
||||
${base_srcs}
|
||||
${geometry_srcs}
|
||||
${linear_srcs}
|
||||
${discrete_srcs}
|
||||
${dynamics_srcs}
|
||||
${nonlinear_srcs}
|
||||
|
@ -77,7 +106,7 @@ if (GTSAM_BUILD_STATIC_LIBRARY)
|
|||
PREFIX "lib"
|
||||
COMPILE_DEFINITIONS GTSAM_UNSTABLE_IMPORT_STATIC)
|
||||
endif()
|
||||
target_link_libraries(gtsam_unstable gtsam ${GTSAM_UNSTABLE_BOOST_LIBRARIES})
|
||||
target_link_libraries(gtsam_unstable gtsam ${GTSAM_UNSTABLE_BOOST_LIBRARIES} ${GTSAM_UNSTABLE_ADDITIONAL_LIBRARIES})
|
||||
install(TARGETS gtsam_unstable EXPORT GTSAM-exports ARCHIVE DESTINATION lib)
|
||||
list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable)
|
||||
set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE)
|
||||
|
@ -95,7 +124,7 @@ else()
|
|||
DEFINE_SYMBOL GTSAM_UNSTABLE_EXPORTS
|
||||
RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/bin")
|
||||
endif()
|
||||
target_link_libraries(gtsam_unstable gtsam ${GTSAM_UNSTABLE_BOOST_LIBRARIES})
|
||||
target_link_libraries(gtsam_unstable gtsam ${GTSAM_UNSTABLE_BOOST_LIBRARIES} ${GTSAM_UNSTABLE_ADDITIONAL_LIBRARIES})
|
||||
install(TARGETS gtsam_unstable EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin)
|
||||
list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable)
|
||||
set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE)
|
||||
|
|
|
@ -0,0 +1,6 @@
|
|||
# Install headers
|
||||
file(GLOB linear_headers "*.h")
|
||||
install(FILES ${linear_headers} DESTINATION include/gtsam_unstable/linear)
|
||||
|
||||
# Add all tests
|
||||
add_subdirectory(tests)
|
|
@ -8,7 +8,7 @@
|
|||
#include <boost/foreach.hpp>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/linear/LPSolver.h>
|
||||
#include <gtsam_unstable/linear/LPSolver.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
|
@ -8,8 +8,8 @@
|
|||
#include <boost/foreach.hpp>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/linear/QPSolver.h>
|
||||
#include <gtsam/linear/LPSolver.h>
|
||||
#include <gtsam_unstable/linear/QPSolver.h>
|
||||
#include <gtsam_unstable/linear/LPSolver.h>
|
||||
|
||||
using namespace std;
|
||||
|
|
@ -0,0 +1 @@
|
|||
gtsamAddTestsGlob(linear_unstable "test*.cpp" "" "gtsam_unstable")
|
|
@ -9,7 +9,7 @@
|
|||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <boost/range/adaptor/map.hpp>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/linear/LPSolver.h>
|
||||
#include <gtsam_unstable/linear/LPSolver.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
|
@ -19,7 +19,7 @@
|
|||
#include <CppUnitLite/TestHarness.h>
|
||||
#include <gtsam/base/Testable.h>
|
||||
#include <gtsam/inference/Symbol.h>
|
||||
#include <gtsam/linear/QPSolver.h>
|
||||
#include <gtsam_unstable/linear/QPSolver.h>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
Loading…
Reference in New Issue