Building timing scripts using new timing script support in GtsamTesting.cmake. Fixed compile errors in timing scripts but disabled a couple.
parent
2591f7dca2
commit
fe235b1209
|
@ -303,6 +303,9 @@ add_subdirectory(tests)
|
||||||
# Build examples
|
# Build examples
|
||||||
add_subdirectory(examples)
|
add_subdirectory(examples)
|
||||||
|
|
||||||
|
# Build timing
|
||||||
|
add_subdirectory(timing)
|
||||||
|
|
||||||
# Matlab toolbox
|
# Matlab toolbox
|
||||||
if (GTSAM_INSTALL_MATLAB_TOOLBOX)
|
if (GTSAM_INSTALL_MATLAB_TOOLBOX)
|
||||||
add_subdirectory(matlab)
|
add_subdirectory(matlab)
|
||||||
|
|
|
@ -7,9 +7,3 @@ install(FILES ${base_headers_tree} DESTINATION include/gtsam/base/treeTraversal)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(base "gtsam" "gtsam" "${base_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -6,9 +6,3 @@ install(FILES ${discrete_headers} DESTINATION include/gtsam/discrete)
|
||||||
|
|
||||||
# Add all tests
|
# Add all tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
#if (GTSAM_BUILD_TIMING)
|
|
||||||
# gtsam_add_timing(discrete "${discrete_local_libs}")
|
|
||||||
#endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -4,9 +4,3 @@ install(FILES ${geometry_headers} DESTINATION include/gtsam/geometry)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(geometry "gtsam" "gtsam" "${geometry_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -4,9 +4,3 @@ install(FILES ${inference_headers} DESTINATION include/gtsam/inference)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(inference "gtsam" "gtsam" "${inference_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -4,8 +4,3 @@ install(FILES ${linear_headers} DESTINATION include/gtsam/linear)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(linear "gtsam" "gtsam" "${linear_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
|
@ -4,8 +4,3 @@ install(FILES ${navigation_headers} DESTINATION include/gtsam/navigation)
|
||||||
|
|
||||||
# Add all tests
|
# Add all tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(navigation "gtsam" "gtsam" "${navigation_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
|
@ -4,9 +4,3 @@ install(FILES ${nonlinear_headers} DESTINATION include/gtsam/nonlinear)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(nonlinear "gtsam" "gtsam" "${nonlinear_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -8,8 +8,3 @@ install(FILES ${slam_headers} DESTINATION include/gtsam/slam)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(slam "gtsam" "gtsam" "${slam_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
|
@ -4,9 +4,3 @@ install(FILES ${symbolic_headers} DESTINATION include/gtsam/symbolic)
|
||||||
|
|
||||||
# Build tests
|
# Build tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(symbolic "gtsam" "gtsam" "${symbolic_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
||||||
|
|
|
@ -118,6 +118,7 @@ endif(GTSAM_INSTALL_MATLAB_TOOLBOX)
|
||||||
|
|
||||||
|
|
||||||
# Build examples
|
# Build examples
|
||||||
if (GTSAM_BUILD_EXAMPLES)
|
add_subdirectory(examples)
|
||||||
add_subdirectory(examples)
|
|
||||||
endif(GTSAM_BUILD_EXAMPLES)
|
# Build timing
|
||||||
|
add_subdirectory(timing)
|
||||||
|
|
|
@ -4,8 +4,3 @@ install(FILES ${base_headers} DESTINATION include/gtsam_unstable/base)
|
||||||
|
|
||||||
# Add all tests
|
# Add all tests
|
||||||
add_subdirectory(tests)
|
add_subdirectory(tests)
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
gtsam_add_subdir_timing(base_unstable "${base_full_libs}" "${base_full_libs}" "${base_excluded_files}")
|
|
||||||
endif(GTSAM_BUILD_TIMING)
|
|
||||||
|
|
|
@ -0,0 +1 @@
|
||||||
|
gtsamAddTimingGlob("*.cpp" "" "gtsam_unstable")
|
|
@ -20,9 +20,9 @@
|
||||||
#include <gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h>
|
#include <gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h>
|
||||||
#include <gtsam/geometry/Pose3.h>
|
#include <gtsam/geometry/Pose3.h>
|
||||||
#include <gtsam/nonlinear/Values.h>
|
#include <gtsam/nonlinear/Values.h>
|
||||||
#include <gtsam/nonlinear/Key.h>
|
|
||||||
#include <gtsam/base/numericalDerivative.h>
|
#include <gtsam/base/numericalDerivative.h>
|
||||||
#include <gtsam/base/LieVector.h>
|
#include <gtsam/base/LieVector.h>
|
||||||
|
#include <gtsam/inference/Key.h>
|
||||||
|
|
||||||
using namespace std;
|
using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
|
@ -32,7 +32,7 @@ gtsam::Rot3 world_R_ECEF(
|
||||||
0.85173, -0.52399, 0,
|
0.85173, -0.52399, 0,
|
||||||
0.41733, 0.67835, -0.60471);
|
0.41733, 0.67835, -0.60471);
|
||||||
|
|
||||||
gtsam::Vector ECEF_omega_earth((Vec(3) << 0.0, 0.0, 7.292115e-5));
|
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5));
|
||||||
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
@ -54,16 +54,16 @@ int main() {
|
||||||
gtsam::Key BiasKey1(31);
|
gtsam::Key BiasKey1(31);
|
||||||
|
|
||||||
double measurement_dt(0.1);
|
double measurement_dt(0.1);
|
||||||
Vector world_g((Vec(3) << 0.0, 0.0, 9.81));
|
Vector world_g((Vector(3) << 0.0, 0.0, 9.81));
|
||||||
Vector world_rho((Vec(3) << 0.0, -1.5724e-05, 0.0)); // NED system
|
Vector world_rho((Vector(3) << 0.0, -1.5724e-05, 0.0)); // NED system
|
||||||
gtsam::Vector ECEF_omega_earth((Vec(3) << 0.0, 0.0, 7.292115e-5));
|
gtsam::Vector ECEF_omega_earth((Vector(3) << 0.0, 0.0, 7.292115e-5));
|
||||||
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
gtsam::Vector world_omega_earth(world_R_ECEF.matrix() * ECEF_omega_earth);
|
||||||
|
|
||||||
SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
SharedGaussian model(noiseModel::Isotropic::Sigma(9, 0.1));
|
||||||
|
|
||||||
// Second test: zero angular motion, some acceleration - generated in matlab
|
// Second test: zero angular motion, some acceleration - generated in matlab
|
||||||
Vector measurement_acc((Vec(3) << 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
Vector measurement_acc((Vector(3) << 6.501390843381716, -6.763926150509185, -2.300389940090343));
|
||||||
Vector measurement_gyro((Vec(3) << 0.1, 0.2, 0.3));
|
Vector measurement_gyro((Vector(3) << 0.1, 0.2, 0.3));
|
||||||
|
|
||||||
InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
InertialNavFactor_GlobalVelocity<Pose3, LieVector, imuBias::ConstantBias> f(PoseKey1, VelKey1, BiasKey1, PoseKey2, VelKey2, measurement_acc, measurement_gyro, measurement_dt, world_g, world_rho, world_omega_earth, model);
|
||||||
|
|
||||||
|
@ -72,7 +72,7 @@ int main() {
|
||||||
-0.652537293, 0.709880342, 0.265075427);
|
-0.652537293, 0.709880342, 0.265075427);
|
||||||
Point3 t1(2.0,1.0,3.0);
|
Point3 t1(2.0,1.0,3.0);
|
||||||
Pose3 Pose1(R1, t1);
|
Pose3 Pose1(R1, t1);
|
||||||
LieVector Vel1(3,0.5,-0.5,0.4);
|
LieVector Vel1 = Vector((Vector(3) << 0.5,-0.5,0.4));
|
||||||
Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
Rot3 R2(0.473618898, 0.119523052, 0.872582019,
|
||||||
0.609241153, 0.67099888, -0.422594037,
|
0.609241153, 0.67099888, -0.422594037,
|
||||||
-0.636011287, 0.731761397, 0.244979388);
|
-0.636011287, 0.731761397, 0.244979388);
|
||||||
|
@ -99,7 +99,7 @@ int main() {
|
||||||
GaussianFactorGraph graph;
|
GaussianFactorGraph graph;
|
||||||
gttic_(LinearizeTiming);
|
gttic_(LinearizeTiming);
|
||||||
for(size_t i = 0; i < 100000; ++i) {
|
for(size_t i = 0; i < 100000; ++i) {
|
||||||
GaussianFactor::shared_ptr g = f.linearize(values, ordering);
|
GaussianFactor::shared_ptr g = f.linearize(values);
|
||||||
graph.push_back(g);
|
graph.push_back(g);
|
||||||
}
|
}
|
||||||
gttoc_(LinearizeTiming);
|
gttoc_(LinearizeTiming);
|
|
@ -14,16 +14,3 @@ if(MSVC)
|
||||||
set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSLAM.cpp"
|
set_property(SOURCE "${CMAKE_CURRENT_SOURCE_DIR}/testSerializationSLAM.cpp"
|
||||||
APPEND PROPERTY COMPILE_FLAGS "/bigobj")
|
APPEND PROPERTY COMPILE_FLAGS "/bigobj")
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
# Build timing scripts
|
|
||||||
if (GTSAM_BUILD_TIMING)
|
|
||||||
# Subdirectory target for timing - does not actually execute the scripts
|
|
||||||
add_custom_target(timing.tests)
|
|
||||||
set(is_test FALSE)
|
|
||||||
|
|
||||||
# Build grouped benchmarks
|
|
||||||
gtsam_add_grouped_scripts("tests" # Use subdirectory as group label
|
|
||||||
"time*.cpp" timing "Timing Benchmark" # Standard for all timing scripts
|
|
||||||
"${tests_full_libs}" "${tests_full_libs}" "${tests_exclude}" # Pass in linking and exclusion lists
|
|
||||||
${is_test})
|
|
||||||
endif (GTSAM_BUILD_TIMING)
|
|
||||||
|
|
|
@ -0,0 +1,6 @@
|
||||||
|
list(APPEND to_exclude
|
||||||
|
timeFactorOverhead.cpp
|
||||||
|
timeSLAMlike.cpp)
|
||||||
|
gtsamAddTimingGlob("*.cpp" "${to_exclude}" "gtsam")
|
||||||
|
|
||||||
|
target_link_libraries(timeGaussianFactorGraph CppUnitLite)
|
|
@ -27,11 +27,11 @@ int main()
|
||||||
{
|
{
|
||||||
int n = 100000;
|
int n = 100000;
|
||||||
|
|
||||||
const Pose3 pose1((Matrix)(Mat(3,3) <<
|
const Pose3 pose1(Matrix3((Matrix(3,3) <<
|
||||||
1., 0., 0.,
|
1., 0., 0.,
|
||||||
0.,-1., 0.,
|
0.,-1., 0.,
|
||||||
0., 0.,-1.
|
0., 0.,-1.
|
||||||
),
|
)),
|
||||||
Point3(0,0,0.5));
|
Point3(0,0,0.5));
|
||||||
|
|
||||||
const CalibratedCamera camera(pose1);
|
const CalibratedCamera camera(pose1);
|
|
@ -22,7 +22,7 @@
|
||||||
using namespace std;
|
using namespace std;
|
||||||
|
|
||||||
#include <boost/tuple/tuple.hpp>
|
#include <boost/tuple/tuple.hpp>
|
||||||
#include <boost/assign/std/list.hpp> // for operator += in Ordering
|
#include <boost/assign/list_of.hpp>
|
||||||
|
|
||||||
#include <gtsam/base/Matrix.h>
|
#include <gtsam/base/Matrix.h>
|
||||||
#include <gtsam/linear/JacobianFactor.h>
|
#include <gtsam/linear/JacobianFactor.h>
|
||||||
|
@ -33,7 +33,7 @@ using namespace std;
|
||||||
using namespace gtsam;
|
using namespace gtsam;
|
||||||
using namespace boost::assign;
|
using namespace boost::assign;
|
||||||
|
|
||||||
static const Index _x1_=1, _x2_=2, _l1_=3;
|
static const Key _x1_=1, _x2_=2, _l1_=3;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Alex's Machine
|
* Alex's Machine
|
||||||
|
@ -53,7 +53,7 @@ static const Index _x1_=1, _x2_=2, _l1_=3;
|
||||||
int main()
|
int main()
|
||||||
{
|
{
|
||||||
// create a linear factor
|
// create a linear factor
|
||||||
Matrix Ax2 = (Mat(8, 2) <<
|
Matrix Ax2 = (Matrix(8, 2) <<
|
||||||
// x2
|
// x2
|
||||||
-5., 0.,
|
-5., 0.,
|
||||||
+0.,-5.,
|
+0.,-5.,
|
||||||
|
@ -65,7 +65,7 @@ int main()
|
||||||
+0.,10.
|
+0.,10.
|
||||||
);
|
);
|
||||||
|
|
||||||
Matrix Al1 = (Mat(8, 10) <<
|
Matrix Al1 = (Matrix(8, 10) <<
|
||||||
// l1
|
// l1
|
||||||
5., 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
5., 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||||
0., 5.,1.,2.,3.,4.,5.,6.,7.,8.,
|
0., 5.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||||
|
@ -77,7 +77,7 @@ int main()
|
||||||
0., 0.,1.,2.,3.,4.,5.,6.,7.,8.
|
0., 0.,1.,2.,3.,4.,5.,6.,7.,8.
|
||||||
);
|
);
|
||||||
|
|
||||||
Matrix Ax1 = (Mat(8, 2) <<
|
Matrix Ax1 = (Matrix(8, 2) <<
|
||||||
// x1
|
// x1
|
||||||
0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||||
0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
0.00, 0.,1.,2.,3.,4.,5.,6.,7.,8.,
|
||||||
|
@ -108,7 +108,8 @@ int main()
|
||||||
JacobianFactor::shared_ptr factor;
|
JacobianFactor::shared_ptr factor;
|
||||||
|
|
||||||
for(int i = 0; i < n; i++)
|
for(int i = 0; i < n; i++)
|
||||||
conditional = JacobianFactor(combined).eliminateFirst();
|
boost::tie(conditional, factor) =
|
||||||
|
JacobianFactor(combined).eliminate(Ordering(boost::assign::list_of(_x2_)));
|
||||||
|
|
||||||
long timeLog2 = clock();
|
long timeLog2 = clock();
|
||||||
double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC;
|
double seconds = (double)(timeLog2-timeLog)/CLOCKS_PER_SEC;
|
|
@ -29,10 +29,10 @@ using namespace boost::assign;
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Create a Kalman smoother for t=1:T and optimize
|
// Create a Kalman smoother for t=1:T and optimize
|
||||||
double timeKalmanSmoother(int T) {
|
double timeKalmanSmoother(int T) {
|
||||||
pair<GaussianFactorGraph,Ordering> smoother_ordering = createSmoother(T);
|
GaussianFactorGraph smoother = createSmoother(T);
|
||||||
GaussianFactorGraph& smoother(smoother_ordering.first);
|
|
||||||
clock_t start = clock();
|
clock_t start = clock();
|
||||||
GaussianSequentialSolver(smoother).optimize();
|
// Keys will come out sorted since keys() returns a set
|
||||||
|
smoother.optimize(Ordering(smoother.keys()));
|
||||||
clock_t end = clock ();
|
clock_t end = clock ();
|
||||||
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
||||||
return dif;
|
return dif;
|
||||||
|
@ -40,12 +40,10 @@ double timeKalmanSmoother(int T) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Create a planar factor graph and optimize
|
// Create a planar factor graph and optimize
|
||||||
// todo: use COLAMD ordering again (removed when linear baked-in ordering added)
|
|
||||||
double timePlanarSmoother(int N, bool old = true) {
|
double timePlanarSmoother(int N, bool old = true) {
|
||||||
boost::tuple<GaussianFactorGraph, VectorValues> pg = planarGraph(N);
|
GaussianFactorGraph fg = planarGraph(N).get<0>();
|
||||||
GaussianFactorGraph& fg(pg.get<0>());
|
|
||||||
clock_t start = clock();
|
clock_t start = clock();
|
||||||
GaussianSequentialSolver(fg).optimize();
|
fg.optimize();
|
||||||
clock_t end = clock ();
|
clock_t end = clock ();
|
||||||
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
||||||
return dif;
|
return dif;
|
||||||
|
@ -53,12 +51,10 @@ double timePlanarSmoother(int N, bool old = true) {
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
// Create a planar factor graph and eliminate
|
// Create a planar factor graph and eliminate
|
||||||
// todo: use COLAMD ordering again (removed when linear baked-in ordering added)
|
|
||||||
double timePlanarSmootherEliminate(int N, bool old = true) {
|
double timePlanarSmootherEliminate(int N, bool old = true) {
|
||||||
boost::tuple<GaussianFactorGraph, VectorValues> pg = planarGraph(N);
|
GaussianFactorGraph fg = planarGraph(N).get<0>();
|
||||||
GaussianFactorGraph& fg(pg.get<0>());
|
|
||||||
clock_t start = clock();
|
clock_t start = clock();
|
||||||
GaussianSequentialSolver(fg).eliminate();
|
fg.eliminateMultifrontal();
|
||||||
clock_t end = clock ();
|
clock_t end = clock ();
|
||||||
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
double dif = (double)(end - start) / CLOCKS_PER_SEC;
|
||||||
return dif;
|
return dif;
|
|
@ -189,7 +189,7 @@ double timeColumn(size_t reps) {
|
||||||
*/
|
*/
|
||||||
double timeHouseholder(size_t reps) {
|
double timeHouseholder(size_t reps) {
|
||||||
// create a matrix
|
// create a matrix
|
||||||
Matrix Abase = Mat(4, 7) <<
|
Matrix Abase = (Matrix(4, 7) <<
|
||||||
-5, 0, 5, 0, 0, 0, -1,
|
-5, 0, 5, 0, 0, 0, -1,
|
||||||
00, -5, 0, 5, 0, 0, 1.5,
|
00, -5, 0, 5, 0, 0, 1.5,
|
||||||
10, 0, 0, 0,-10, 0, 2,
|
10, 0, 0, 0,-10, 0, 2,
|
|
@ -28,7 +28,7 @@ int main()
|
||||||
{
|
{
|
||||||
int n = 1000000;
|
int n = 1000000;
|
||||||
|
|
||||||
const Pose3 pose1((Matrix)(Mat(3,3) <<
|
const Pose3 pose1((Matrix)(Matrix(3,3) <<
|
||||||
1., 0., 0.,
|
1., 0., 0.,
|
||||||
0.,-1., 0.,
|
0.,-1., 0.,
|
||||||
0., 0.,-1.
|
0., 0.,-1.
|
|
@ -58,7 +58,7 @@ Pose2 Pose2betweenOptimized(const Pose2& r1, const Pose2& r2,
|
||||||
if (H1) {
|
if (H1) {
|
||||||
double dt1 = -s2 * x + c2 * y;
|
double dt1 = -s2 * x + c2 * y;
|
||||||
double dt2 = -c2 * x - s2 * y;
|
double dt2 = -c2 * x - s2 * y;
|
||||||
*H1 = (Mat(3,3) <<
|
*H1 = (Matrix(3,3) <<
|
||||||
-c, -s, dt1,
|
-c, -s, dt1,
|
||||||
s, -c, dt2,
|
s, -c, dt2,
|
||||||
0.0, 0.0,-1.0);
|
0.0, 0.0,-1.0);
|
|
@ -37,8 +37,8 @@ int main()
|
||||||
|
|
||||||
double norm=sqrt(1.0+16.0+4.0);
|
double norm=sqrt(1.0+16.0+4.0);
|
||||||
double x=1.0/norm, y=4.0/norm, z=2.0/norm;
|
double x=1.0/norm, y=4.0/norm, z=2.0/norm;
|
||||||
Vector v = (Vec(6) << x, y, z, 0.1, 0.2, -0.1);
|
Vector v = (Vector(6) << x, y, z, 0.1, 0.2, -0.1);
|
||||||
Pose3 T = Pose3::Expmap((Vec(6) << 0.1, 0.1, 0.2, 0.1, 0.4, 0.2)), T2 = T.retract(v);
|
Pose3 T = Pose3::Expmap((Vector(6) << 0.1, 0.1, 0.2, 0.1, 0.4, 0.2)), T2 = T.retract(v);
|
||||||
Matrix H1,H2;
|
Matrix H1,H2;
|
||||||
|
|
||||||
TEST(retract, T.retract(v))
|
TEST(retract, T.retract(v))
|
|
@ -27,7 +27,7 @@ int main()
|
||||||
{
|
{
|
||||||
int n = 100000;
|
int n = 100000;
|
||||||
|
|
||||||
const Pose3 pose1((Matrix)(Mat(3,3) <<
|
const Pose3 pose1((Matrix)(Matrix(3,3) <<
|
||||||
1., 0., 0.,
|
1., 0., 0.,
|
||||||
0.,-1., 0.,
|
0.,-1., 0.,
|
||||||
0., 0.,-1.
|
0., 0.,-1.
|
Loading…
Reference in New Issue