Merge branch 'develop' of https://github.com/borglab/gtsam into borglab-develop
commit
711bc98d94
|
@ -68,6 +68,8 @@ function configure()
|
|||
-DGTSAM_USE_QUATERNIONS=${GTSAM_USE_QUATERNIONS:-OFF} \
|
||||
-DGTSAM_ROT3_EXPMAP=${GTSAM_ROT3_EXPMAP:-ON} \
|
||||
-DGTSAM_POSE3_EXPMAP=${GTSAM_POSE3_EXPMAP:-ON} \
|
||||
-DGTSAM_USE_SYSTEM_EIGEN=${GTSAM_USE_SYSTEM_EIGEN:-OFF} \
|
||||
-DGTSAM_USE_SYSTEM_METIS=${GTSAM_USE_SYSTEM_METIS:-OFF} \
|
||||
-DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \
|
||||
-DBOOST_ROOT=$BOOST_ROOT \
|
||||
-DBoost_NO_SYSTEM_PATHS=ON \
|
||||
|
|
|
@ -55,6 +55,12 @@ jobs:
|
|||
version: "9"
|
||||
flag: cayley
|
||||
|
||||
- name: ubuntu-system-libs
|
||||
os: ubuntu-18.04
|
||||
compiler: gcc
|
||||
version: "9"
|
||||
flag: system-libs
|
||||
|
||||
steps:
|
||||
- name: Checkout
|
||||
uses: actions/checkout@v2
|
||||
|
@ -126,6 +132,12 @@ jobs:
|
|||
echo "GTSAM_ROT3_EXPMAP=OFF" >> $GITHUB_ENV
|
||||
echo "GTSAM Uses Cayley map for Rot3"
|
||||
|
||||
- name: Use system versions of 3rd party libraries
|
||||
if: matrix.flag == 'system'
|
||||
run: |
|
||||
echo "GTSAM_USE_SYSTEM_EIGEN=ON" >> $GITHUB_ENV
|
||||
echo "GTSAM_USE_SYSTEM_METIS=ON" >> $GITHUB_ENV
|
||||
|
||||
- name: Build & Test
|
||||
run: |
|
||||
bash .github/scripts/unix.sh -t
|
||||
|
|
|
@ -38,11 +38,14 @@ if(${GTSAM_SOURCE_DIR} STREQUAL ${GTSAM_BINARY_DIR})
|
|||
message(FATAL_ERROR "In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. ")
|
||||
endif()
|
||||
|
||||
include(cmake/HandleGeneralOptions.cmake) # CMake build options
|
||||
|
||||
# Libraries:
|
||||
include(cmake/HandleBoost.cmake) # Boost
|
||||
include(cmake/HandleCCache.cmake) # ccache
|
||||
include(cmake/HandleCPack.cmake) # CPack
|
||||
include(cmake/HandleEigen.cmake) # Eigen3
|
||||
include(cmake/HandleGeneralOptions.cmake) # CMake build options
|
||||
include(cmake/HandleMetis.cmake) # metis
|
||||
include(cmake/HandleMKL.cmake) # MKL
|
||||
include(cmake/HandleOpenMP.cmake) # OpenMP
|
||||
include(cmake/HandlePerfTools.cmake) # Google perftools
|
||||
|
|
|
@ -0,0 +1,44 @@
|
|||
###############################################################################
|
||||
# Metis library
|
||||
|
||||
# For both system or bundle version, a cmake target "metis-gtsam-if" is defined (interface library)
|
||||
|
||||
# Dont try to use metis if GTSAM_SUPPORT_NESTED_DISSECTION is disabled:
|
||||
if (NOT GTSAM_SUPPORT_NESTED_DISSECTION)
|
||||
return()
|
||||
endif()
|
||||
|
||||
option(GTSAM_USE_SYSTEM_METIS "Find and use system-installed libmetis. If 'off', use the one bundled with GTSAM" OFF)
|
||||
|
||||
if(GTSAM_USE_SYSTEM_METIS)
|
||||
# Debian package: libmetis-dev
|
||||
|
||||
find_path(METIS_INCLUDE_DIR metis.h REQUIRED)
|
||||
find_library(METIS_LIBRARY metis REQUIRED)
|
||||
|
||||
if(METIS_INCLUDE_DIR AND METIS_LIBRARY)
|
||||
mark_as_advanced(METIS_INCLUDE_DIR)
|
||||
mark_as_advanced(METIS_LIBRARY)
|
||||
|
||||
add_library(metis-gtsam-if INTERFACE)
|
||||
target_include_directories(metis-gtsam-if BEFORE INTERFACE ${METIS_INCLUDE_DIR})
|
||||
target_link_libraries(metis-gtsam-if INTERFACE ${METIS_LIBRARY})
|
||||
endif()
|
||||
else()
|
||||
# Bundled version:
|
||||
option(GTSAM_BUILD_METIS_EXECUTABLES "Build metis library executables" OFF)
|
||||
add_subdirectory(${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis)
|
||||
|
||||
target_include_directories(metis-gtsam BEFORE PUBLIC
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/include>
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/libmetis>
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/GKlib>
|
||||
$<INSTALL_INTERFACE:include/gtsam/3rdparty/metis/>
|
||||
)
|
||||
|
||||
add_library(metis-gtsam-if INTERFACE)
|
||||
target_link_libraries(metis-gtsam-if INTERFACE metis-gtsam)
|
||||
endif()
|
||||
|
||||
list(APPEND GTSAM_EXPORTED_TARGETS metis-gtsam-if)
|
||||
install(TARGETS metis-gtsam-if EXPORT GTSAM-exports ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR})
|
|
@ -32,6 +32,7 @@ endif()
|
|||
print_build_options_for_target(gtsam)
|
||||
|
||||
print_config("Use System Eigen" "${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})")
|
||||
print_config("Use System Metis" "${GTSAM_USE_SYSTEM_METIS}")
|
||||
|
||||
if(GTSAM_USE_TBB)
|
||||
print_config("Use Intel TBB" "Yes (Version: ${TBB_VERSION})")
|
||||
|
|
|
@ -1,28 +1,32 @@
|
|||
###############################################################################
|
||||
# Find TBB
|
||||
find_package(TBB 4.4 COMPONENTS tbb tbbmalloc)
|
||||
if (GTSAM_WITH_TBB)
|
||||
# Find TBB
|
||||
find_package(TBB 4.4 COMPONENTS tbb tbbmalloc)
|
||||
|
||||
# Set up variables if we're using TBB
|
||||
if(TBB_FOUND AND GTSAM_WITH_TBB)
|
||||
set(GTSAM_USE_TBB 1) # This will go into config.h
|
||||
if ((${TBB_VERSION} VERSION_GREATER "2021.1") OR (${TBB_VERSION} VERSION_EQUAL "2021.1"))
|
||||
message(FATAL_ERROR "TBB version greater than 2021.1 (oneTBB API) is not yet supported. Use an older version instead.")
|
||||
endif()
|
||||
# Set up variables if we're using TBB
|
||||
if(TBB_FOUND)
|
||||
set(GTSAM_USE_TBB 1) # This will go into config.h
|
||||
|
||||
if ((${TBB_VERSION_MAJOR} GREATER 2020) OR (${TBB_VERSION_MAJOR} EQUAL 2020))
|
||||
set(TBB_GREATER_EQUAL_2020 1)
|
||||
if ((${TBB_VERSION} VERSION_GREATER "2021.1") OR (${TBB_VERSION} VERSION_EQUAL "2021.1"))
|
||||
message(FATAL_ERROR "TBB version greater than 2021.1 (oneTBB API) is not yet supported. Use an older version instead.")
|
||||
endif()
|
||||
|
||||
if ((${TBB_VERSION_MAJOR} GREATER 2020) OR (${TBB_VERSION_MAJOR} EQUAL 2020))
|
||||
set(TBB_GREATER_EQUAL_2020 1)
|
||||
else()
|
||||
set(TBB_GREATER_EQUAL_2020 0)
|
||||
endif()
|
||||
# all definitions and link requisites will go via imported targets:
|
||||
# tbb & tbbmalloc
|
||||
list(APPEND GTSAM_ADDITIONAL_LIBRARIES tbb tbbmalloc)
|
||||
else()
|
||||
set(TBB_GREATER_EQUAL_2020 0)
|
||||
set(GTSAM_USE_TBB 0) # This will go into config.h
|
||||
endif()
|
||||
|
||||
###############################################################################
|
||||
# Prohibit Timing build mode in combination with TBB
|
||||
if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing"))
|
||||
message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.")
|
||||
endif()
|
||||
# all definitions and link requisites will go via imported targets:
|
||||
# tbb & tbbmalloc
|
||||
list(APPEND GTSAM_ADDITIONAL_LIBRARIES tbb tbbmalloc)
|
||||
else()
|
||||
set(GTSAM_USE_TBB 0) # This will go into config.h
|
||||
endif()
|
||||
|
||||
###############################################################################
|
||||
# Prohibit Timing build mode in combination with TBB
|
||||
if(GTSAM_USE_TBB AND (CMAKE_BUILD_TYPE STREQUAL "Timing"))
|
||||
message(FATAL_ERROR "Timing build mode cannot be used together with TBB. Use a sampling profiler such as Instruments or Intel VTune Amplifier instead.")
|
||||
endif()
|
||||
|
|
|
@ -49,10 +49,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN)
|
|||
|
||||
endif()
|
||||
|
||||
option(GTSAM_BUILD_METIS_EXECUTABLES "Build metis library executables" OFF)
|
||||
if(GTSAM_SUPPORT_NESTED_DISSECTION)
|
||||
add_subdirectory(metis)
|
||||
endif()
|
||||
# metis: already handled in ROOT/cmake/HandleMetis.cmake
|
||||
|
||||
add_subdirectory(ceres)
|
||||
|
||||
|
|
|
@ -89,7 +89,8 @@ list(APPEND gtsam_srcs "${PROJECT_BINARY_DIR}/config.h" "${PROJECT_BINARY_DIR}/d
|
|||
install(FILES "${PROJECT_BINARY_DIR}/config.h" "${PROJECT_BINARY_DIR}/dllexport.h" DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/gtsam)
|
||||
|
||||
if(GTSAM_SUPPORT_NESTED_DISSECTION)
|
||||
list(APPEND GTSAM_ADDITIONAL_LIBRARIES metis-gtsam)
|
||||
# target metis-gtsam-if is defined in both cases: embedded metis or system version:
|
||||
list(APPEND GTSAM_ADDITIONAL_LIBRARIES metis-gtsam-if)
|
||||
endif()
|
||||
|
||||
# Versions
|
||||
|
@ -155,16 +156,6 @@ target_include_directories(gtsam SYSTEM BEFORE PUBLIC
|
|||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/3rdparty/CCOLAMD/Include>
|
||||
$<INSTALL_INTERFACE:include/gtsam/3rdparty/CCOLAMD>
|
||||
)
|
||||
if(GTSAM_SUPPORT_NESTED_DISSECTION)
|
||||
target_include_directories(gtsam BEFORE PUBLIC
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/include>
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/libmetis>
|
||||
$<BUILD_INTERFACE:${GTSAM_SOURCE_DIR}/gtsam/3rdparty/metis/GKlib>
|
||||
$<INSTALL_INTERFACE:include/gtsam/3rdparty/metis/>
|
||||
)
|
||||
endif()
|
||||
|
||||
|
||||
|
||||
if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library
|
||||
if (NOT BUILD_SHARED_LIBS)
|
||||
|
|
|
@ -77,3 +77,6 @@
|
|||
|
||||
// Support Metis-based nested dissection
|
||||
#cmakedefine GTSAM_TANGENT_PREINTEGRATION
|
||||
|
||||
// Whether to use the system installed Metis instead of the provided one
|
||||
#cmakedefine GTSAM_USE_SYSTEM_METIS
|
||||
|
|
|
@ -25,8 +25,12 @@
|
|||
#include <gtsam/3rdparty/CCOLAMD/Include/ccolamd.h>
|
||||
|
||||
#ifdef GTSAM_SUPPORT_NESTED_DISSECTION
|
||||
#ifdef GTSAM_USE_SYSTEM_METIS
|
||||
#include <metis.h>
|
||||
#else
|
||||
#include <gtsam/3rdparty/metis/include/metis.h>
|
||||
#endif
|
||||
#endif
|
||||
|
||||
using namespace std;
|
||||
|
||||
|
|
|
@ -530,7 +530,14 @@ template<PARAMS>
|
|||
virtual class GncParams {
|
||||
GncParams(const PARAMS& baseOptimizerParams);
|
||||
GncParams();
|
||||
void setVerbosityGNC(const This::Verbosity value);
|
||||
void print(const string& str) const;
|
||||
|
||||
enum Verbosity {
|
||||
SILENT,
|
||||
SUMMARY,
|
||||
VALUES
|
||||
};
|
||||
};
|
||||
|
||||
typedef gtsam::GncParams<gtsam::GaussNewtonParams> GncGaussNewtonParams;
|
||||
|
|
|
@ -20,6 +20,8 @@
|
|||
|
||||
#include "FindSeparator.h"
|
||||
|
||||
#ifndef GTSAM_USE_SYSTEM_METIS
|
||||
|
||||
extern "C" {
|
||||
#include <metis.h>
|
||||
#include "metislib.h"
|
||||
|
@ -564,3 +566,5 @@ namespace gtsam { namespace partition {
|
|||
}
|
||||
|
||||
}} //namespace
|
||||
|
||||
#endif
|
||||
|
|
|
@ -20,6 +20,8 @@ using namespace std;
|
|||
using namespace gtsam;
|
||||
using namespace gtsam::partition;
|
||||
|
||||
#ifndef GTSAM_USE_SYSTEM_METIS
|
||||
|
||||
/* ************************************************************************* */
|
||||
// x0 - x1 - x2
|
||||
// l3 l4
|
||||
|
@ -227,6 +229,8 @@ TEST ( Partition, findSeparator3_with_reduced_camera )
|
|||
LONGS_EQUAL(2, partitionTable[28]);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/* ************************************************************************* */
|
||||
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
|
||||
/* ************************************************************************* */
|
||||
|
|
|
@ -119,24 +119,27 @@ class Constructor:
|
|||
Can have 0 or more arguments.
|
||||
"""
|
||||
rule = (
|
||||
IDENT("name") #
|
||||
Optional(Template.rule("template")) #
|
||||
+ IDENT("name") #
|
||||
+ LPAREN #
|
||||
+ ArgumentList.rule("args_list") #
|
||||
+ RPAREN #
|
||||
+ SEMI_COLON # BR
|
||||
).setParseAction(lambda t: Constructor(t.name, t.args_list))
|
||||
).setParseAction(lambda t: Constructor(t.name, t.args_list, t.template))
|
||||
|
||||
def __init__(self,
|
||||
name: str,
|
||||
args: ArgumentList,
|
||||
template: Union[Template, Any],
|
||||
parent: Union["Class", Any] = ''):
|
||||
self.name = name
|
||||
self.args = args
|
||||
self.template = template
|
||||
|
||||
self.parent = parent
|
||||
|
||||
def __repr__(self) -> str:
|
||||
return "Constructor: {}".format(self.name)
|
||||
return "Constructor: {}{}".format(self.name, self.args)
|
||||
|
||||
|
||||
class Operator:
|
||||
|
@ -260,17 +263,9 @@ class Class:
|
|||
+ RBRACE #
|
||||
+ SEMI_COLON # BR
|
||||
).setParseAction(lambda t: Class(
|
||||
t.template,
|
||||
t.is_virtual,
|
||||
t.name,
|
||||
t.parent_class,
|
||||
t.members.ctors,
|
||||
t.members.methods,
|
||||
t.members.static_methods,
|
||||
t.members.properties,
|
||||
t.members.operators,
|
||||
t.members.enums
|
||||
))
|
||||
t.template, t.is_virtual, t.name, t.parent_class, t.members.ctors, t.
|
||||
members.methods, t.members.static_methods, t.members.properties, t.
|
||||
members.operators, t.members.enums))
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
|
|
|
@ -81,7 +81,7 @@ class ArgumentList:
|
|||
return ArgumentList([])
|
||||
|
||||
def __repr__(self) -> str:
|
||||
return self.args_list.__repr__()
|
||||
return repr(tuple(self.args_list))
|
||||
|
||||
def __len__(self) -> int:
|
||||
return len(self.args_list)
|
||||
|
|
|
@ -41,6 +41,8 @@ def instantiate_type(ctype: parser.Type,
|
|||
|
||||
str_arg_typename = str(ctype.typename)
|
||||
|
||||
# Instantiate templates which have enumerated instantiations in the template.
|
||||
# E.g. `template<T={double}>`.
|
||||
if str_arg_typename in template_typenames:
|
||||
idx = template_typenames.index(str_arg_typename)
|
||||
return parser.Type(
|
||||
|
@ -51,14 +53,15 @@ def instantiate_type(ctype: parser.Type,
|
|||
is_ref=ctype.is_ref,
|
||||
is_basic=ctype.is_basic,
|
||||
)
|
||||
|
||||
# If a method has the keyword `This`, we replace it with the (instantiated) class.
|
||||
elif str_arg_typename == 'This':
|
||||
# Check if the class is template instantiated
|
||||
# so we can replace it with the instantiated version.
|
||||
if instantiated_class:
|
||||
name = instantiated_class.original.name
|
||||
namespaces_name = instantiated_class.namespaces()
|
||||
namespaces_name.append(name)
|
||||
# print("INST: {}, {}, CPP: {}, CLS: {}".format(
|
||||
# ctype, instantiations, cpp_typename, instantiated_class.instantiations
|
||||
# ), file=sys.stderr)
|
||||
cpp_typename = parser.Typename(
|
||||
namespaces_name,
|
||||
instantiations=instantiated_class.instantiations)
|
||||
|
@ -71,6 +74,14 @@ def instantiate_type(ctype: parser.Type,
|
|||
is_ref=ctype.is_ref,
|
||||
is_basic=ctype.is_basic,
|
||||
)
|
||||
|
||||
# Case when 'This' is present in the type namespace, e.g `This::Subclass`.
|
||||
elif 'This' in str_arg_typename:
|
||||
# Simply get the index of `This` in the namespace and replace it with the instantiated name.
|
||||
namespace_idx = ctype.typename.namespaces.index('This')
|
||||
ctype.typename.namespaces[namespace_idx] = cpp_typename.name
|
||||
return ctype
|
||||
|
||||
else:
|
||||
return ctype
|
||||
|
||||
|
@ -368,19 +379,45 @@ class InstantiatedClass(parser.Class):
|
|||
"""
|
||||
instantiated_ctors = []
|
||||
|
||||
for ctor in self.original.ctors:
|
||||
def instantiate(instantiated_ctors, ctor, typenames, instantiations):
|
||||
instantiated_args = instantiate_args_list(
|
||||
ctor.args.list(),
|
||||
typenames,
|
||||
self.instantiations,
|
||||
instantiations,
|
||||
self.cpp_typename(),
|
||||
)
|
||||
instantiated_ctors.append(
|
||||
parser.Constructor(
|
||||
name=self.name,
|
||||
args=parser.ArgumentList(instantiated_args),
|
||||
template=self.original.template,
|
||||
parent=self,
|
||||
))
|
||||
return instantiated_ctors
|
||||
|
||||
for ctor in self.original.ctors:
|
||||
# Add constructor templates to the typenames and instantiations
|
||||
if isinstance(ctor.template, parser.template.Template):
|
||||
typenames.extend(ctor.template.typenames)
|
||||
|
||||
# Get all combinations of template args
|
||||
for instantiations in itertools.product(
|
||||
*ctor.template.instantiations):
|
||||
instantiations = self.instantiations + list(instantiations)
|
||||
|
||||
instantiated_ctors = instantiate(
|
||||
instantiated_ctors,
|
||||
ctor,
|
||||
typenames=typenames,
|
||||
instantiations=instantiations)
|
||||
|
||||
else:
|
||||
# If no constructor level templates, just use the class templates
|
||||
instantiated_ctors = instantiate(
|
||||
instantiated_ctors,
|
||||
ctor,
|
||||
typenames=typenames,
|
||||
instantiations=self.instantiations)
|
||||
return instantiated_ctors
|
||||
|
||||
def instantiate_static_methods(self, typenames):
|
||||
|
|
|
@ -15,9 +15,9 @@ classdef MyFactorPosePoint2 < handle
|
|||
function obj = MyFactorPosePoint2(varargin)
|
||||
if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)
|
||||
my_ptr = varargin{2};
|
||||
class_wrapper(56, my_ptr);
|
||||
class_wrapper(62, my_ptr);
|
||||
elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base')
|
||||
my_ptr = class_wrapper(57, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
||||
my_ptr = class_wrapper(63, varargin{1}, varargin{2}, varargin{3}, varargin{4});
|
||||
else
|
||||
error('Arguments do not match any overload of MyFactorPosePoint2 constructor');
|
||||
end
|
||||
|
@ -25,7 +25,7 @@ classdef MyFactorPosePoint2 < handle
|
|||
end
|
||||
|
||||
function delete(obj)
|
||||
class_wrapper(58, obj.ptr_MyFactorPosePoint2);
|
||||
class_wrapper(64, obj.ptr_MyFactorPosePoint2);
|
||||
end
|
||||
|
||||
function display(obj), obj.print(''); end
|
||||
|
@ -36,7 +36,7 @@ classdef MyFactorPosePoint2 < handle
|
|||
% PRINT usage: print(string s, KeyFormatter keyFormatter) : returns void
|
||||
% Doxygen can be found at https://gtsam.org/doxygen/
|
||||
if length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.KeyFormatter')
|
||||
class_wrapper(59, this, varargin{:});
|
||||
class_wrapper(65, this, varargin{:});
|
||||
return
|
||||
end
|
||||
error('Arguments do not match any overload of function MyFactorPosePoint2.print');
|
||||
|
|
|
@ -33,6 +33,8 @@ typedef std::set<boost::shared_ptr<MultipleTemplatesIntFloat>*> Collector_Multip
|
|||
static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat;
|
||||
typedef std::set<boost::shared_ptr<ForwardKinematics>*> Collector_ForwardKinematics;
|
||||
static Collector_ForwardKinematics collector_ForwardKinematics;
|
||||
typedef std::set<boost::shared_ptr<TemplatedConstructor>*> Collector_TemplatedConstructor;
|
||||
static Collector_TemplatedConstructor collector_TemplatedConstructor;
|
||||
typedef std::set<boost::shared_ptr<MyFactorPosePoint2>*> Collector_MyFactorPosePoint2;
|
||||
static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2;
|
||||
|
||||
|
@ -97,6 +99,12 @@ void _deleteAllObjects()
|
|||
collector_ForwardKinematics.erase(iter++);
|
||||
anyDeleted = true;
|
||||
} }
|
||||
{ for(Collector_TemplatedConstructor::iterator iter = collector_TemplatedConstructor.begin();
|
||||
iter != collector_TemplatedConstructor.end(); ) {
|
||||
delete *iter;
|
||||
collector_TemplatedConstructor.erase(iter++);
|
||||
anyDeleted = true;
|
||||
} }
|
||||
{ for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin();
|
||||
iter != collector_MyFactorPosePoint2.end(); ) {
|
||||
delete *iter;
|
||||
|
@ -682,7 +690,76 @@ void ForwardKinematics_deconstructor_55(int nargout, mxArray *out[], int nargin,
|
|||
}
|
||||
}
|
||||
|
||||
void MyFactorPosePoint2_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
void TemplatedConstructor_collectorInsertAndMakeBase_56(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
|
||||
Shared *self = *reinterpret_cast<Shared**> (mxGetData(in[0]));
|
||||
collector_TemplatedConstructor.insert(self);
|
||||
}
|
||||
|
||||
void TemplatedConstructor_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
|
||||
Shared *self = new Shared(new TemplatedConstructor());
|
||||
collector_TemplatedConstructor.insert(self);
|
||||
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||
}
|
||||
|
||||
void TemplatedConstructor_constructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
|
||||
string& arg = *unwrap_shared_ptr< string >(in[0], "ptr_string");
|
||||
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||
collector_TemplatedConstructor.insert(self);
|
||||
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||
}
|
||||
|
||||
void TemplatedConstructor_constructor_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
|
||||
int arg = unwrap< int >(in[0]);
|
||||
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||
collector_TemplatedConstructor.insert(self);
|
||||
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||
}
|
||||
|
||||
void TemplatedConstructor_constructor_60(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
|
||||
double arg = unwrap< double >(in[0]);
|
||||
Shared *self = new Shared(new TemplatedConstructor(arg));
|
||||
collector_TemplatedConstructor.insert(self);
|
||||
out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL);
|
||||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||
}
|
||||
|
||||
void TemplatedConstructor_deconstructor_61(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
typedef boost::shared_ptr<TemplatedConstructor> Shared;
|
||||
checkArguments("delete_TemplatedConstructor",nargout,nargin,1);
|
||||
Shared *self = *reinterpret_cast<Shared**>(mxGetData(in[0]));
|
||||
Collector_TemplatedConstructor::iterator item;
|
||||
item = collector_TemplatedConstructor.find(self);
|
||||
if(item != collector_TemplatedConstructor.end()) {
|
||||
delete self;
|
||||
collector_TemplatedConstructor.erase(item);
|
||||
}
|
||||
}
|
||||
|
||||
void MyFactorPosePoint2_collectorInsertAndMakeBase_62(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||
|
@ -691,7 +768,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_56(int nargout, mxArray *out[
|
|||
collector_MyFactorPosePoint2.insert(self);
|
||||
}
|
||||
|
||||
void MyFactorPosePoint2_constructor_57(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
void MyFactorPosePoint2_constructor_63(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
mexAtExit(&_deleteAllObjects);
|
||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||
|
@ -706,7 +783,7 @@ void MyFactorPosePoint2_constructor_57(int nargout, mxArray *out[], int nargin,
|
|||
*reinterpret_cast<Shared**> (mxGetData(out[0])) = self;
|
||||
}
|
||||
|
||||
void MyFactorPosePoint2_deconstructor_58(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
void MyFactorPosePoint2_deconstructor_64(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
typedef boost::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>> Shared;
|
||||
checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1);
|
||||
|
@ -719,7 +796,7 @@ void MyFactorPosePoint2_deconstructor_58(int nargout, mxArray *out[], int nargin
|
|||
}
|
||||
}
|
||||
|
||||
void MyFactorPosePoint2_print_59(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
void MyFactorPosePoint2_print_65(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
||||
{
|
||||
checkArguments("print",nargout,nargin-1,2);
|
||||
auto obj = unwrap_shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>(in[0], "ptr_MyFactorPosePoint2");
|
||||
|
@ -909,16 +986,34 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])
|
|||
ForwardKinematics_deconstructor_55(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 56:
|
||||
MyFactorPosePoint2_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1);
|
||||
TemplatedConstructor_collectorInsertAndMakeBase_56(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 57:
|
||||
MyFactorPosePoint2_constructor_57(nargout, out, nargin-1, in+1);
|
||||
TemplatedConstructor_constructor_57(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 58:
|
||||
MyFactorPosePoint2_deconstructor_58(nargout, out, nargin-1, in+1);
|
||||
TemplatedConstructor_constructor_58(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 59:
|
||||
MyFactorPosePoint2_print_59(nargout, out, nargin-1, in+1);
|
||||
TemplatedConstructor_constructor_59(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 60:
|
||||
TemplatedConstructor_constructor_60(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 61:
|
||||
TemplatedConstructor_deconstructor_61(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 62:
|
||||
MyFactorPosePoint2_collectorInsertAndMakeBase_62(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 63:
|
||||
MyFactorPosePoint2_constructor_63(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 64:
|
||||
MyFactorPosePoint2_deconstructor_64(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
case 65:
|
||||
MyFactorPosePoint2_print_65(nargout, out, nargin-1, in+1);
|
||||
break;
|
||||
}
|
||||
} catch(const std::exception& e) {
|
||||
|
|
|
@ -86,6 +86,12 @@ PYBIND11_MODULE(class_py, m_) {
|
|||
py::class_<ForwardKinematics, std::shared_ptr<ForwardKinematics>>(m_, "ForwardKinematics")
|
||||
.def(py::init<const gtdynamics::Robot&, const string&, const string&, const gtsam::Values&, const gtsam::Pose3&>(), py::arg("robot"), py::arg("start_link_name"), py::arg("end_link_name"), py::arg("joint_angles"), py::arg("l2Tp") = gtsam::Pose3());
|
||||
|
||||
py::class_<TemplatedConstructor, std::shared_ptr<TemplatedConstructor>>(m_, "TemplatedConstructor")
|
||||
.def(py::init<>())
|
||||
.def(py::init<const string&>(), py::arg("arg"))
|
||||
.def(py::init<const int&>(), py::arg("arg"))
|
||||
.def(py::init<const double&>(), py::arg("arg"));
|
||||
|
||||
py::class_<MyFactor<gtsam::Pose2, gtsam::Matrix>, std::shared_ptr<MyFactor<gtsam::Pose2, gtsam::Matrix>>>(m_, "MyFactorPosePoint2")
|
||||
.def(py::init<size_t, size_t, double, const std::shared_ptr<gtsam::noiseModel::Base>>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel"))
|
||||
.def("print",[](MyFactor<gtsam::Pose2, gtsam::Matrix>* self, const string& s, const gtsam::KeyFormatter& keyFormatter){ py::scoped_ostream_redirect output; self->print(s, keyFormatter);}, py::arg("s") = "factor: ", py::arg("keyFormatter") = gtsam::DefaultKeyFormatter)
|
||||
|
|
|
@ -69,6 +69,16 @@ PYBIND11_MODULE(enum_py, m_) {
|
|||
.value("Groot", gtsam::MCU::GotG::Groot);
|
||||
|
||||
|
||||
py::class_<gtsam::Optimizer<gtsam::GaussNewtonParams>, std::shared_ptr<gtsam::Optimizer<gtsam::GaussNewtonParams>>> optimizergaussnewtonparams(m_gtsam, "OptimizerGaussNewtonParams");
|
||||
optimizergaussnewtonparams
|
||||
.def("setVerbosity",[](gtsam::Optimizer<gtsam::GaussNewtonParams>* self, const Optimizer<gtsam::GaussNewtonParams>::Verbosity value){ self->setVerbosity(value);}, py::arg("value"));
|
||||
|
||||
py::enum_<gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity>(optimizergaussnewtonparams, "Verbosity", py::arithmetic())
|
||||
.value("SILENT", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::SILENT)
|
||||
.value("SUMMARY", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::SUMMARY)
|
||||
.value("VERBOSE", gtsam::Optimizer<gtsam::GaussNewtonParams>::Verbosity::VERBOSE);
|
||||
|
||||
|
||||
|
||||
#include "python/specializations.h"
|
||||
|
||||
|
|
|
@ -7,6 +7,7 @@ class FunRange {
|
|||
|
||||
template<M={double}>
|
||||
class Fun {
|
||||
|
||||
static This staticMethodWithThis();
|
||||
|
||||
template<T={string}>
|
||||
|
@ -118,5 +119,14 @@ class ForwardKinematics {
|
|||
const gtsam::Pose3& l2Tp = gtsam::Pose3());
|
||||
};
|
||||
|
||||
// Test for templated constructor
|
||||
class TemplatedConstructor {
|
||||
TemplatedConstructor();
|
||||
|
||||
template<T={string, int, double}>
|
||||
TemplatedConstructor(const T& arg);
|
||||
};
|
||||
|
||||
|
||||
class SuperCoolFactor;
|
||||
typedef SuperCoolFactor<gtsam::Pose3> SuperCoolFactorPose3;
|
||||
|
|
|
@ -42,4 +42,17 @@ class MCU {
|
|||
|
||||
};
|
||||
|
||||
template<PARAMS>
|
||||
class Optimizer {
|
||||
enum Verbosity {
|
||||
SILENT,
|
||||
SUMMARY,
|
||||
VERBOSE
|
||||
};
|
||||
|
||||
void setVerbosity(const This::Verbosity value);
|
||||
};
|
||||
|
||||
typedef gtsam::Optimizer<gtsam::GaussNewtonParams> OptimizerGaussNewtonParams;
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
@ -314,6 +314,25 @@ class TestInterfaceParser(unittest.TestCase):
|
|||
self.assertEqual(5, len(ret.args))
|
||||
self.assertEqual("gtsam::Pose3()", ret.args.list()[4].default)
|
||||
|
||||
def test_constructor_templated(self):
|
||||
"""Test for templated class constructor."""
|
||||
f = """
|
||||
template<T = {double, int}>
|
||||
Class();
|
||||
"""
|
||||
ret = Constructor.rule.parseString(f)[0]
|
||||
self.assertEqual("Class", ret.name)
|
||||
self.assertEqual(0, len(ret.args))
|
||||
|
||||
f = """
|
||||
template<T = {double, int}>
|
||||
Class(const T& name);
|
||||
"""
|
||||
ret = Constructor.rule.parseString(f)[0]
|
||||
self.assertEqual("Class", ret.name)
|
||||
self.assertEqual(1, len(ret.args))
|
||||
self.assertEqual("const T & name", ret.args.args_list[0].to_cpp())
|
||||
|
||||
def test_operator_overload(self):
|
||||
"""Test for operator overloading."""
|
||||
# Unary operator
|
||||
|
|
Loading…
Reference in New Issue