Merge branch 'feature/cython-examples' into fix/ImuFactor
commit
0219b39341
|
@ -52,7 +52,7 @@ function(pyx_to_cpp target pyx_file generated_cpp include_dirs)
|
||||||
add_custom_command(
|
add_custom_command(
|
||||||
OUTPUT ${generated_cpp}
|
OUTPUT ${generated_cpp}
|
||||||
COMMAND
|
COMMAND
|
||||||
${CYTHON_EXECUTABLE} -X boundscheck=False -a -v --fast-fail --cplus ${includes_for_cython} ${pyx_file} -o ${generated_cpp}
|
${CYTHON_EXECUTABLE} -X boundscheck=False -v --fast-fail --cplus ${includes_for_cython} ${pyx_file} -o ${generated_cpp}
|
||||||
VERBATIM)
|
VERBATIM)
|
||||||
add_custom_target(${target} ALL DEPENDS ${generated_cpp})
|
add_custom_target(${target} ALL DEPENDS ${generated_cpp})
|
||||||
endfunction()
|
endfunction()
|
||||||
|
@ -95,7 +95,7 @@ function(cythonize target pyx_file output_lib_we output_dir include_dirs libs in
|
||||||
|
|
||||||
# Late dependency injection, to make sure this gets called whenever the interface header is updated
|
# Late dependency injection, to make sure this gets called whenever the interface header is updated
|
||||||
# See: https://stackoverflow.com/questions/40032593/cmake-does-not-rebuild-dependent-after-prerequisite-changes
|
# See: https://stackoverflow.com/questions/40032593/cmake-does-not-rebuild-dependent-after-prerequisite-changes
|
||||||
add_custom_command(OUTPUT ${generated_cpp} DEPENDS ${interface_header} APPEND)
|
add_custom_command(OUTPUT ${generated_cpp} DEPENDS ${interface_header} ${pyx_file} APPEND)
|
||||||
if (NOT "${dependencies}" STREQUAL "")
|
if (NOT "${dependencies}" STREQUAL "")
|
||||||
add_dependencies(${target}_pyx2cpp "${dependencies}")
|
add_dependencies(${target}_pyx2cpp "${dependencies}")
|
||||||
endif()
|
endif()
|
||||||
|
|
|
@ -0,0 +1,52 @@
|
||||||
|
"""
|
||||||
|
GTSAM Copyright 2010-2018, 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
|
||||||
|
|
||||||
|
Simple robot motion example, with prior and two odometry measurements
|
||||||
|
Author: Frank Dellaert
|
||||||
|
"""
|
||||||
|
# pylint: disable=invalid-name, E1101
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
|
||||||
|
# Create noise models
|
||||||
|
ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1]))
|
||||||
|
PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1]))
|
||||||
|
|
||||||
|
# Create an empty nonlinear factor graph
|
||||||
|
graph = gtsam.NonlinearFactorGraph()
|
||||||
|
|
||||||
|
# Add a prior on the first pose, setting it to the origin
|
||||||
|
# A prior factor consists of a mean and a noise model (covariance matrix)
|
||||||
|
priorMean = gtsam.Pose2(0.0, 0.0, 0.0) # prior at origin
|
||||||
|
graph.add(gtsam.PriorFactorPose2(1, priorMean, PRIOR_NOISE))
|
||||||
|
|
||||||
|
# Add odometry factors
|
||||||
|
odometry = gtsam.Pose2(2.0, 0.0, 0.0)
|
||||||
|
# For simplicity, we will use the same noise model for each odometry factor
|
||||||
|
# Create odometry (Between) factors between consecutive poses
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(1, 2, odometry, ODOMETRY_NOISE))
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(2, 3, odometry, ODOMETRY_NOISE))
|
||||||
|
graph.print_("\nFactor Graph:\n")
|
||||||
|
|
||||||
|
# Create the data structure to hold the initialEstimate estimate to the solution
|
||||||
|
# For illustrative purposes, these have been deliberately set to incorrect values
|
||||||
|
initial = gtsam.Values()
|
||||||
|
initial.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))
|
||||||
|
initial.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))
|
||||||
|
initial.insert(3, gtsam.Pose2(4.1, 0.1, 0.1))
|
||||||
|
initial.print_("\nInitial Estimate:\n")
|
||||||
|
|
||||||
|
# optimize using Levenberg-Marquardt optimization
|
||||||
|
params = gtsam.LevenbergMarquardtParams()
|
||||||
|
optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)
|
||||||
|
result = optimizer.optimize()
|
||||||
|
result.print_("\nFinal Result:\n")
|
|
@ -0,0 +1,80 @@
|
||||||
|
"""
|
||||||
|
GTSAM Copyright 2010-2018, 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
|
||||||
|
|
||||||
|
Simple robotics example using odometry measurements and bearing-range (laser) measurements
|
||||||
|
Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python)
|
||||||
|
"""
|
||||||
|
# pylint: disable=invalid-name, E1101
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
|
||||||
|
# Create noise models
|
||||||
|
PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.3, 0.3, 0.1]))
|
||||||
|
ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.2, 0.2, 0.1]))
|
||||||
|
MEASUREMENT_NOISE = gtsam.noiseModel_Diagonal.Sigmas(np.array([0.1, 0.2]))
|
||||||
|
|
||||||
|
# Create an empty nonlinear factor graph
|
||||||
|
graph = gtsam.NonlinearFactorGraph()
|
||||||
|
|
||||||
|
# Create the keys corresponding to unknown variables in the factor graph
|
||||||
|
X1 = gtsam.symbol(ord('x'), 1)
|
||||||
|
X2 = gtsam.symbol(ord('x'), 2)
|
||||||
|
X3 = gtsam.symbol(ord('x'), 3)
|
||||||
|
L1 = gtsam.symbol(ord('l'), 4)
|
||||||
|
L2 = gtsam.symbol(ord('l'), 5)
|
||||||
|
|
||||||
|
# Add a prior on pose X1 at the origin. A prior factor consists of a mean and a noise model
|
||||||
|
graph.add(gtsam.PriorFactorPose2(X1, gtsam.Pose2(0.0, 0.0, 0.0), PRIOR_NOISE))
|
||||||
|
|
||||||
|
# Add odometry factors between X1,X2 and X2,X3, respectively
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
X1, X2, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE))
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
X2, X3, gtsam.Pose2(2.0, 0.0, 0.0), ODOMETRY_NOISE))
|
||||||
|
|
||||||
|
# Add Range-Bearing measurements to two different landmarks L1 and L2
|
||||||
|
graph.add(gtsam.BearingRangeFactor2D(
|
||||||
|
X1, L1, gtsam.Rot2.fromDegrees(45), np.sqrt(4.0+4.0), MEASUREMENT_NOISE))
|
||||||
|
graph.add(gtsam.BearingRangeFactor2D(
|
||||||
|
X2, L1, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE))
|
||||||
|
graph.add(gtsam.BearingRangeFactor2D(
|
||||||
|
X3, L2, gtsam.Rot2.fromDegrees(90), 2.0, MEASUREMENT_NOISE))
|
||||||
|
|
||||||
|
# Print graph
|
||||||
|
graph.print_("Factor Graph:\n")
|
||||||
|
|
||||||
|
# Create (deliberately inaccurate) initial estimate
|
||||||
|
initial_estimate = gtsam.Values()
|
||||||
|
initial_estimate.insert(X1, gtsam.Pose2(-0.25, 0.20, 0.15))
|
||||||
|
initial_estimate.insert(X2, gtsam.Pose2(2.30, 0.10, -0.20))
|
||||||
|
initial_estimate.insert(X3, gtsam.Pose2(4.10, 0.10, 0.10))
|
||||||
|
initial_estimate.insert(L1, gtsam.Point2(1.80, 2.10))
|
||||||
|
initial_estimate.insert(L2, gtsam.Point2(4.10, 1.80))
|
||||||
|
|
||||||
|
# Print
|
||||||
|
initial_estimate.print_("Initial Estimate:\n")
|
||||||
|
|
||||||
|
# Optimize using Levenberg-Marquardt optimization. The optimizer
|
||||||
|
# accepts an optional set of configuration parameters, controlling
|
||||||
|
# things like convergence criteria, the type of linear system solver
|
||||||
|
# to use, and the amount of information displayed during optimization.
|
||||||
|
# Here we will use the default set of parameters. See the
|
||||||
|
# documentation for the full set of parameters.
|
||||||
|
params = gtsam.LevenbergMarquardtParams()
|
||||||
|
optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial_estimate, params)
|
||||||
|
result = optimizer.optimize()
|
||||||
|
result.print_("\nFinal Result:\n")
|
||||||
|
|
||||||
|
# Calculate and print marginal covariances for all variables
|
||||||
|
marginals = gtsam.Marginals(graph, result)
|
||||||
|
for (key, str) in [(X1, "X1"), (X2, "X2"), (X3, "X3"), (L1, "L1"), (L2, "L2")]:
|
||||||
|
print("{} covariance:\n{}\n".format(str, marginals.marginalCovariance(key)))
|
|
@ -0,0 +1,87 @@
|
||||||
|
"""
|
||||||
|
GTSAM Copyright 2010-2018, 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
|
||||||
|
|
||||||
|
Simple robotics example using odometry measurements and bearing-range (laser) measurements
|
||||||
|
Author: Alex Cunningham (C++), Kevin Deng & Frank Dellaert (Python)
|
||||||
|
"""
|
||||||
|
# pylint: disable=invalid-name, E1101
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
|
import math
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
|
||||||
|
|
||||||
|
def vector3(x, y, z):
|
||||||
|
"""Create 3d double numpy array."""
|
||||||
|
return np.array([x, y, z], dtype=np.float)
|
||||||
|
|
||||||
|
|
||||||
|
# Create noise models
|
||||||
|
PRIOR_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.3, 0.3, 0.1))
|
||||||
|
ODOMETRY_NOISE = gtsam.noiseModel_Diagonal.Sigmas(vector3(0.2, 0.2, 0.1))
|
||||||
|
|
||||||
|
# 1. Create a factor graph container and add factors to it
|
||||||
|
graph = gtsam.NonlinearFactorGraph()
|
||||||
|
|
||||||
|
# 2a. Add a prior on the first pose, setting it to the origin
|
||||||
|
# A prior factor consists of a mean and a noise ODOMETRY_NOISE (covariance matrix)
|
||||||
|
graph.add(gtsam.PriorFactorPose2(1, gtsam.Pose2(0, 0, 0), PRIOR_NOISE))
|
||||||
|
|
||||||
|
# 2b. Add odometry factors
|
||||||
|
# Create odometry (Between) factors between consecutive poses
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(1, 2, gtsam.Pose2(2, 0, 0), ODOMETRY_NOISE))
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
2, 3, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
3, 4, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
4, 5, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
|
||||||
|
|
||||||
|
# 2c. Add the loop closure constraint
|
||||||
|
# This factor encodes the fact that we have returned to the same pose. In real
|
||||||
|
# systems, these constraints may be identified in many ways, such as appearance-based
|
||||||
|
# techniques with camera images. We will use another Between Factor to enforce this constraint:
|
||||||
|
graph.add(gtsam.BetweenFactorPose2(
|
||||||
|
5, 2, gtsam.Pose2(2, 0, math.pi / 2), ODOMETRY_NOISE))
|
||||||
|
graph.print_("\nFactor Graph:\n") # print
|
||||||
|
|
||||||
|
# 3. Create the data structure to hold the initial_estimate estimate to the
|
||||||
|
# solution. For illustrative purposes, these have been deliberately set to incorrect values
|
||||||
|
initial_estimate = gtsam.Values()
|
||||||
|
initial_estimate.insert(1, gtsam.Pose2(0.5, 0.0, 0.2))
|
||||||
|
initial_estimate.insert(2, gtsam.Pose2(2.3, 0.1, -0.2))
|
||||||
|
initial_estimate.insert(3, gtsam.Pose2(4.1, 0.1, math.pi / 2))
|
||||||
|
initial_estimate.insert(4, gtsam.Pose2(4.0, 2.0, math.pi))
|
||||||
|
initial_estimate.insert(5, gtsam.Pose2(2.1, 2.1, -math.pi / 2))
|
||||||
|
initial_estimate.print_("\nInitial Estimate:\n") # print
|
||||||
|
|
||||||
|
# 4. Optimize the initial values using a Gauss-Newton nonlinear optimizer
|
||||||
|
# The optimizer accepts an optional set of configuration parameters,
|
||||||
|
# controlling things like convergence criteria, the type of linear
|
||||||
|
# system solver to use, and the amount of information displayed during
|
||||||
|
# optimization. We will set a few parameters as a demonstration.
|
||||||
|
parameters = gtsam.GaussNewtonParams()
|
||||||
|
|
||||||
|
# Stop iterating once the change in error between steps is less than this value
|
||||||
|
parameters.setRelativeErrorTol(1e-5)
|
||||||
|
# Do not perform more than N iteration steps
|
||||||
|
parameters.setMaxIterations(100)
|
||||||
|
# Create the optimizer ...
|
||||||
|
optimizer = gtsam.GaussNewtonOptimizer(graph, initial_estimate, parameters)
|
||||||
|
# ... and optimize
|
||||||
|
result = optimizer.optimize()
|
||||||
|
result.print_("Final Result:\n")
|
||||||
|
|
||||||
|
# 5. Calculate and print marginal covariances for all variables
|
||||||
|
marginals = gtsam.Marginals(graph, result)
|
||||||
|
for i in range(1, 6):
|
||||||
|
print("X{} covariance:\n{}\n".format(i, marginals.marginalCovariance(i)))
|
|
@ -0,0 +1,4 @@
|
||||||
|
These examples are almost identical to the old handwritten python wrapper
|
||||||
|
examples. However, there are just some slight name changes, for example .print
|
||||||
|
becomes .print_, and noiseModel.Diagonal becomes noiseModel_Diagonal etc...
|
||||||
|
Also, annoyingly, instead of gtsam.Symbol('b',0) we now need to say gtsam.symbol(ord('b'), 0))
|
|
@ -0,0 +1,38 @@
|
||||||
|
"""
|
||||||
|
A structure-from-motion example with landmarks
|
||||||
|
- The landmarks form a 10 meter cube
|
||||||
|
- The robot rotates around the landmarks, always facing towards the cube
|
||||||
|
"""
|
||||||
|
# pylint: disable=invalid-name, E1101
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
|
||||||
|
|
||||||
|
def createPoints():
|
||||||
|
# Create the set of ground-truth landmarks
|
||||||
|
points = [gtsam.Point3(10.0, 10.0, 10.0),
|
||||||
|
gtsam.Point3(-10.0, 10.0, 10.0),
|
||||||
|
gtsam.Point3(-10.0, -10.0, 10.0),
|
||||||
|
gtsam.Point3(10.0, -10.0, 10.0),
|
||||||
|
gtsam.Point3(10.0, 10.0, -10.0),
|
||||||
|
gtsam.Point3(-10.0, 10.0, -10.0),
|
||||||
|
gtsam.Point3(-10.0, -10.0, -10.0),
|
||||||
|
gtsam.Point3(10.0, -10.0, -10.0)]
|
||||||
|
return points
|
||||||
|
|
||||||
|
|
||||||
|
def createPoses(K):
|
||||||
|
# Create the set of ground-truth poses
|
||||||
|
radius = 30.0
|
||||||
|
angles = np.linspace(0, 2*np.pi, 8, endpoint=False)
|
||||||
|
up = gtsam.Point3(0, 0, 1)
|
||||||
|
target = gtsam.Point3(0, 0, 0)
|
||||||
|
poses = []
|
||||||
|
for theta in angles:
|
||||||
|
position = gtsam.Point3(radius*np.cos(theta),
|
||||||
|
radius*np.sin(theta), 0.0)
|
||||||
|
camera = gtsam.PinholeCameraCal3_S2.Lookat(position, target, up, K)
|
||||||
|
poses.append(camera.pose())
|
||||||
|
return poses
|
|
@ -0,0 +1,163 @@
|
||||||
|
"""
|
||||||
|
GTSAM Copyright 2010-2018, 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
|
||||||
|
|
||||||
|
An example of running visual SLAM using iSAM2.
|
||||||
|
Author: Duy-Nguyen Ta (C++), Frank Dellaert (Python)
|
||||||
|
"""
|
||||||
|
# pylint: disable=invalid-name, E1101
|
||||||
|
|
||||||
|
from __future__ import print_function
|
||||||
|
|
||||||
|
import matplotlib.pyplot as plt
|
||||||
|
import numpy as np
|
||||||
|
from mpl_toolkits.mplot3d import Axes3D # pylint: disable=W0611
|
||||||
|
|
||||||
|
import gtsam
|
||||||
|
import gtsam.utils.plot as gtsam_plot
|
||||||
|
from gtsam.examples import SFMdata
|
||||||
|
|
||||||
|
|
||||||
|
def X(i):
|
||||||
|
"""Create key for pose i."""
|
||||||
|
return int(gtsam.symbol(ord('x'), i))
|
||||||
|
|
||||||
|
|
||||||
|
def L(j):
|
||||||
|
"""Create key for landmark j."""
|
||||||
|
return int(gtsam.symbol(ord('l'), j))
|
||||||
|
|
||||||
|
|
||||||
|
def visual_ISAM2_plot(result):
|
||||||
|
"""
|
||||||
|
VisualISAMPlot plots current state of ISAM2 object
|
||||||
|
Author: Ellon Paiva
|
||||||
|
Based on MATLAB version by: Duy Nguyen Ta and Frank Dellaert
|
||||||
|
"""
|
||||||
|
|
||||||
|
# Declare an id for the figure
|
||||||
|
fignum = 0
|
||||||
|
|
||||||
|
fig = plt.figure(fignum)
|
||||||
|
axes = fig.gca(projection='3d')
|
||||||
|
plt.cla()
|
||||||
|
|
||||||
|
# Plot points
|
||||||
|
# Can't use data because current frame might not see all points
|
||||||
|
# marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate())
|
||||||
|
# gtsam.plot_3d_points(result, [], marginals)
|
||||||
|
gtsam_plot.plot_3d_points(fignum, result, 'rx')
|
||||||
|
|
||||||
|
# Plot cameras
|
||||||
|
i = 0
|
||||||
|
while result.exists(X(i)):
|
||||||
|
pose_i = result.atPose3(X(i))
|
||||||
|
gtsam_plot.plot_pose3(fignum, pose_i, 10)
|
||||||
|
i += 1
|
||||||
|
|
||||||
|
# draw
|
||||||
|
axes.set_xlim3d(-40, 40)
|
||||||
|
axes.set_ylim3d(-40, 40)
|
||||||
|
axes.set_zlim3d(-40, 40)
|
||||||
|
plt.pause(1)
|
||||||
|
|
||||||
|
|
||||||
|
def visual_ISAM2_example():
|
||||||
|
plt.ion()
|
||||||
|
|
||||||
|
# Define the camera calibration parameters
|
||||||
|
K = gtsam.Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)
|
||||||
|
|
||||||
|
# Define the camera observation noise model
|
||||||
|
measurement_noise = gtsam.noiseModel_Isotropic.Sigma(
|
||||||
|
2, 1.0) # one pixel in u and v
|
||||||
|
|
||||||
|
# Create the set of ground-truth landmarks
|
||||||
|
points = SFMdata.createPoints()
|
||||||
|
|
||||||
|
# Create the set of ground-truth poses
|
||||||
|
poses = SFMdata.createPoses(K)
|
||||||
|
|
||||||
|
# Create an iSAM2 object. Unlike iSAM1, which performs periodic batch steps
|
||||||
|
# to maintain proper linearization and efficient variable ordering, iSAM2
|
||||||
|
# performs partial relinearization/reordering at each step. A parameter
|
||||||
|
# structure is available that allows the user to set various properties, such
|
||||||
|
# as the relinearization threshold and type of linear solver. For this
|
||||||
|
# example, we we set the relinearization threshold small so the iSAM2 result
|
||||||
|
# will approach the batch result.
|
||||||
|
parameters = gtsam.ISAM2Params()
|
||||||
|
parameters.setRelinearizeThreshold(0.01)
|
||||||
|
parameters.setRelinearizeSkip(1)
|
||||||
|
isam = gtsam.ISAM2(parameters)
|
||||||
|
|
||||||
|
# Create a Factor Graph and Values to hold the new data
|
||||||
|
graph = gtsam.NonlinearFactorGraph()
|
||||||
|
initial_estimate = gtsam.Values()
|
||||||
|
|
||||||
|
# Loop over the different poses, adding the observations to iSAM incrementally
|
||||||
|
for i, pose in enumerate(poses):
|
||||||
|
|
||||||
|
# Add factors for each landmark observation
|
||||||
|
for j, point in enumerate(points):
|
||||||
|
camera = gtsam.PinholeCameraCal3_S2(pose, K)
|
||||||
|
measurement = camera.project(point)
|
||||||
|
graph.push_back(gtsam.GenericProjectionFactorCal3_S2(
|
||||||
|
measurement, measurement_noise, X(i), L(j), K))
|
||||||
|
|
||||||
|
# Add an initial guess for the current pose
|
||||||
|
# Intentionally initialize the variables off from the ground truth
|
||||||
|
initial_estimate.insert(X(i), pose.compose(gtsam.Pose3(
|
||||||
|
gtsam.Rot3.Rodrigues(-0.1, 0.2, 0.25), gtsam.Point3(0.05, -0.10, 0.20))))
|
||||||
|
|
||||||
|
# If this is the first iteration, add a prior on the first pose to set the
|
||||||
|
# coordinate frame and a prior on the first landmark to set the scale.
|
||||||
|
# Also, as iSAM solves incrementally, we must wait until each is observed
|
||||||
|
# at least twice before adding it to iSAM.
|
||||||
|
if i == 0:
|
||||||
|
# Add a prior on pose x0
|
||||||
|
pose_noise = gtsam.noiseModel_Diagonal.Sigmas(np.array(
|
||||||
|
[0.3, 0.3, 0.3, 0.1, 0.1, 0.1])) # 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
|
||||||
|
graph.push_back(gtsam.PriorFactorPose3(X(0), poses[0], pose_noise))
|
||||||
|
|
||||||
|
# Add a prior on landmark l0
|
||||||
|
point_noise = gtsam.noiseModel_Isotropic.Sigma(3, 0.1)
|
||||||
|
graph.push_back(gtsam.PriorFactorPoint3(
|
||||||
|
L(0), points[0], point_noise)) # add directly to graph
|
||||||
|
|
||||||
|
# Add initial guesses to all observed landmarks
|
||||||
|
# Intentionally initialize the variables off from the ground truth
|
||||||
|
for j, point in enumerate(points):
|
||||||
|
initial_estimate.insert(L(j), gtsam.Point3(
|
||||||
|
point.x()-0.25, point.y()+0.20, point.z()+0.15))
|
||||||
|
else:
|
||||||
|
# Update iSAM with the new factors
|
||||||
|
isam.update(graph, initial_estimate)
|
||||||
|
# Each call to iSAM2 update(*) performs one iteration of the iterative nonlinear solver.
|
||||||
|
# If accuracy is desired at the expense of time, update(*) can be called additional
|
||||||
|
# times to perform multiple optimizer iterations every step.
|
||||||
|
isam.update()
|
||||||
|
current_estimate = isam.calculateEstimate()
|
||||||
|
print("****************************************************")
|
||||||
|
print("Frame", i, ":")
|
||||||
|
for j in range(i + 1):
|
||||||
|
print(X(j), ":", current_estimate.atPose3(X(j)))
|
||||||
|
|
||||||
|
for j in range(len(points)):
|
||||||
|
print(L(j), ":", current_estimate.atPoint3(L(j)))
|
||||||
|
|
||||||
|
visual_ISAM2_plot(current_estimate)
|
||||||
|
|
||||||
|
# Clear the factor graph and values for the next iteration
|
||||||
|
graph.resize(0)
|
||||||
|
initial_estimate.clear()
|
||||||
|
|
||||||
|
plt.ioff()
|
||||||
|
plt.show()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
visual_ISAM2_example()
|
|
@ -0,0 +1 @@
|
||||||
|
from . import SFMdata
|
|
@ -0,0 +1,76 @@
|
||||||
|
"""Various plotting utlities."""
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
import matplotlib.pyplot as plt
|
||||||
|
|
||||||
|
|
||||||
|
def plot_point3_on_axes(axes, point, linespec):
|
||||||
|
"""Plot a 3D point on given axis 'axes' with given 'linespec'."""
|
||||||
|
axes.plot([point.x()], [point.y()], [point.z()], linespec)
|
||||||
|
|
||||||
|
|
||||||
|
def plot_point3(fignum, point, linespec):
|
||||||
|
"""Plot a 3D point on given figure with given 'linespec'."""
|
||||||
|
fig = plt.figure(fignum)
|
||||||
|
axes = fig.gca(projection='3d')
|
||||||
|
plot_point3_on_axes(axes, point, linespec)
|
||||||
|
|
||||||
|
|
||||||
|
def plot_3d_points(fignum, values, linespec, marginals=None):
|
||||||
|
"""
|
||||||
|
Plots the Point3s in 'values', with optional covariances.
|
||||||
|
Finds all the Point3 objects in the given Values object and plots them.
|
||||||
|
If a Marginals object is given, this function will also plot marginal
|
||||||
|
covariance ellipses for each point.
|
||||||
|
"""
|
||||||
|
|
||||||
|
keys = values.keys()
|
||||||
|
|
||||||
|
# Plot points and covariance matrices
|
||||||
|
for i in range(keys.size()):
|
||||||
|
try:
|
||||||
|
p = values.atPoint3(keys.at(i))
|
||||||
|
# if haveMarginals
|
||||||
|
# P = marginals.marginalCovariance(key);
|
||||||
|
# gtsam.plot_point3(p, linespec, P);
|
||||||
|
# else
|
||||||
|
plot_point3(fignum, p, linespec)
|
||||||
|
except RuntimeError:
|
||||||
|
continue
|
||||||
|
# I guess it's not a Point3
|
||||||
|
|
||||||
|
|
||||||
|
def plot_pose3_on_axes(axes, pose, axis_length=0.1):
|
||||||
|
"""Plot a 3D pose on given axis 'axes' with given 'axis_length'."""
|
||||||
|
# get rotation and translation (center)
|
||||||
|
gRp = pose.rotation().matrix() # rotation from pose to global
|
||||||
|
t = pose.translation()
|
||||||
|
origin = np.array([t.x(), t.y(), t.z()])
|
||||||
|
|
||||||
|
# draw the camera axes
|
||||||
|
x_axis = origin + gRp[:, 0] * axis_length
|
||||||
|
line = np.append(origin[np.newaxis], x_axis[np.newaxis], axis=0)
|
||||||
|
axes.plot(line[:, 0], line[:, 1], line[:, 2], 'r-')
|
||||||
|
|
||||||
|
y_axis = origin + gRp[:, 1] * axis_length
|
||||||
|
line = np.append(origin[np.newaxis], y_axis[np.newaxis], axis=0)
|
||||||
|
axes.plot(line[:, 0], line[:, 1], line[:, 2], 'g-')
|
||||||
|
|
||||||
|
z_axis = origin + gRp[:, 2] * axis_length
|
||||||
|
line = np.append(origin[np.newaxis], z_axis[np.newaxis], axis=0)
|
||||||
|
axes.plot(line[:, 0], line[:, 1], line[:, 2], 'b-')
|
||||||
|
|
||||||
|
# # plot the covariance
|
||||||
|
# if (nargin>2) && (~isempty(P))
|
||||||
|
# pPp = P(4:6,4:6); % covariance matrix in pose coordinate frame
|
||||||
|
# gPp = gRp*pPp*gRp'; % convert the covariance matrix to global coordinate frame
|
||||||
|
# gtsam.covarianceEllipse3D(origin,gPp);
|
||||||
|
# end
|
||||||
|
|
||||||
|
|
||||||
|
def plot_pose3(fignum, pose, axis_length=0.1):
|
||||||
|
"""Plot a 3D pose on given figure with given 'axis_length'."""
|
||||||
|
# get figure object
|
||||||
|
fig = plt.figure(fignum)
|
||||||
|
axes = fig.gca(projection='3d')
|
||||||
|
plot_pose3_on_axes(axes, pose, axis_length)
|
|
@ -306,10 +306,17 @@ public:
|
||||||
: cols),
|
: cols),
|
||||||
stride
|
stride
|
||||||
) {}
|
) {}
|
||||||
|
|
||||||
|
MapBase &operator=(const MatrixType &other) {
|
||||||
|
Base::operator=(other);
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~MapBase() { }
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
template <template<class,int,int,int,int,int> class DenseBase,
|
template <template<class,int,int,int,int,int> class EigencyDenseBase,
|
||||||
typename Scalar,
|
typename Scalar,
|
||||||
int _Rows, int _Cols,
|
int _Rows, int _Cols,
|
||||||
int _Options = Eigen::AutoAlign |
|
int _Options = Eigen::AutoAlign |
|
||||||
|
@ -341,16 +348,18 @@ template <template<class,int,int,int,int,int> class DenseBase,
|
||||||
int _StrideOuter=0, int _StrideInner=0,
|
int _StrideOuter=0, int _StrideInner=0,
|
||||||
int _MaxRows = _Rows,
|
int _MaxRows = _Rows,
|
||||||
int _MaxCols = _Cols>
|
int _MaxCols = _Cols>
|
||||||
class FlattenedMap: public MapBase<DenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>, _MapOptions, Eigen::Stride<_StrideOuter, _StrideInner> > {
|
class FlattenedMap: public MapBase<EigencyDenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>, _MapOptions, Eigen::Stride<_StrideOuter, _StrideInner> > {
|
||||||
public:
|
public:
|
||||||
typedef MapBase<DenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>, _MapOptions, Eigen::Stride<_StrideOuter, _StrideInner> > Base;
|
typedef MapBase<EigencyDenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>, _MapOptions, Eigen::Stride<_StrideOuter, _StrideInner> > Base;
|
||||||
|
|
||||||
FlattenedMap()
|
FlattenedMap()
|
||||||
: Base(NULL, 0, 0) {}
|
: Base(NULL, 0, 0),
|
||||||
|
object_(NULL) {}
|
||||||
|
|
||||||
FlattenedMap(Scalar *data, long rows, long cols, long outer_stride=0, long inner_stride=0)
|
FlattenedMap(Scalar *data, long rows, long cols, long outer_stride=0, long inner_stride=0)
|
||||||
: Base(data, rows, cols,
|
: Base(data, rows, cols,
|
||||||
Eigen::Stride<_StrideOuter, _StrideInner>(outer_stride, inner_stride)) {
|
Eigen::Stride<_StrideOuter, _StrideInner>(outer_stride, inner_stride)),
|
||||||
|
object_(NULL) {
|
||||||
}
|
}
|
||||||
|
|
||||||
FlattenedMap(PyArrayObject *object)
|
FlattenedMap(PyArrayObject *object)
|
||||||
|
@ -359,18 +368,26 @@ public:
|
||||||
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1,
|
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1,
|
||||||
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0],
|
(((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0],
|
||||||
Eigen::Stride<_StrideOuter, _StrideInner>(_StrideOuter != Eigen::Dynamic ? _StrideOuter : (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1,
|
Eigen::Stride<_StrideOuter, _StrideInner>(_StrideOuter != Eigen::Dynamic ? _StrideOuter : (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[0] : 1,
|
||||||
_StrideInner != Eigen::Dynamic ? _StrideInner : (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0])) {
|
_StrideInner != Eigen::Dynamic ? _StrideInner : (((PyArrayObject*)object)->nd == 2) ? ((PyArrayObject*)object)->dimensions[1] : ((PyArrayObject*)object)->dimensions[0])),
|
||||||
|
object_(object) {
|
||||||
|
|
||||||
if (((PyObject*)object != Py_None) && !PyArray_ISONESEGMENT(object))
|
if (((PyObject*)object != Py_None) && !PyArray_ISONESEGMENT(object))
|
||||||
throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map.");
|
throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map.");
|
||||||
|
|
||||||
|
Py_XINCREF(object_);
|
||||||
}
|
}
|
||||||
FlattenedMap &operator=(const FlattenedMap &other) {
|
FlattenedMap &operator=(const FlattenedMap &other) {
|
||||||
|
if (other.object_) {
|
||||||
|
new (this) FlattenedMap(other.object_);
|
||||||
|
} else {
|
||||||
// Replace the memory that we point to (not a memory allocation)
|
// Replace the memory that we point to (not a memory allocation)
|
||||||
new (this) FlattenedMap(const_cast<Scalar*>(other.data()),
|
new (this) FlattenedMap(const_cast<Scalar*>(other.data()),
|
||||||
other.rows(),
|
other.rows(),
|
||||||
other.cols(),
|
other.cols(),
|
||||||
other.outerStride(),
|
other.outerStride(),
|
||||||
other.innerStride());
|
other.innerStride());
|
||||||
|
}
|
||||||
|
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -382,9 +399,16 @@ public:
|
||||||
return static_cast<Base&>(*this);
|
return static_cast<Base&>(*this);
|
||||||
}
|
}
|
||||||
|
|
||||||
operator DenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>() const {
|
operator EigencyDenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>() const {
|
||||||
return DenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>(static_cast<Base>(*this));
|
return EigencyDenseBase<Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols>(static_cast<Base>(*this));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual ~FlattenedMap() {
|
||||||
|
Py_XDECREF(object_);
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
PyArrayObject * const object_;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@ -394,39 +418,60 @@ public:
|
||||||
typedef MapBase<MatrixType> Base;
|
typedef MapBase<MatrixType> Base;
|
||||||
typedef typename MatrixType::Scalar Scalar;
|
typedef typename MatrixType::Scalar Scalar;
|
||||||
|
|
||||||
|
enum {
|
||||||
|
RowsAtCompileTime = Base::Base::RowsAtCompileTime,
|
||||||
|
ColsAtCompileTime = Base::Base::ColsAtCompileTime
|
||||||
|
};
|
||||||
|
|
||||||
Map()
|
Map()
|
||||||
: Base(NULL, 0, 0) {
|
: Base(NULL,
|
||||||
|
(RowsAtCompileTime == Eigen::Dynamic) ? 0 : RowsAtCompileTime,
|
||||||
|
(ColsAtCompileTime == Eigen::Dynamic) ? 0 : ColsAtCompileTime),
|
||||||
|
object_(NULL) {
|
||||||
}
|
}
|
||||||
|
|
||||||
Map(Scalar *data, long rows, long cols)
|
Map(Scalar *data, long rows, long cols)
|
||||||
: Base(data, rows, cols) {}
|
: Base(data, rows, cols),
|
||||||
|
object_(NULL) {}
|
||||||
|
|
||||||
Map(PyArrayObject *object)
|
Map(PyArrayObject *object)
|
||||||
: Base((PyObject*)object == Py_None? NULL: (Scalar *)object->data,
|
: Base((PyObject*)object == Py_None? NULL: (Scalar *)object->data,
|
||||||
// ROW: If array is in row-major order, transpose (see README)
|
// ROW: If array is in row-major order, transpose (see README)
|
||||||
(PyObject*)object == Py_None? 0 :
|
(PyObject*)object == Py_None? 0 :
|
||||||
(PyArray_IS_C_CONTIGUOUS(object)
|
(!PyArray_IS_F_CONTIGUOUS(object)
|
||||||
? ((object->nd == 1)
|
? ((object->nd == 1)
|
||||||
? 1 // ROW: If 1D row-major numpy array, set to 1 (row vector)
|
? 1 // ROW: If 1D row-major numpy array, set to 1 (row vector)
|
||||||
: object->dimensions[1])
|
: object->dimensions[1])
|
||||||
: object->dimensions[0]),
|
: object->dimensions[0]),
|
||||||
// COLUMN: If array is in row-major order: transpose (see README)
|
// COLUMN: If array is in row-major order: transpose (see README)
|
||||||
(PyObject*)object == Py_None? 0 :
|
(PyObject*)object == Py_None? 0 :
|
||||||
(PyArray_IS_C_CONTIGUOUS(object)
|
(!PyArray_IS_F_CONTIGUOUS(object)
|
||||||
? object->dimensions[0]
|
? object->dimensions[0]
|
||||||
: ((object->nd == 1)
|
: ((object->nd == 1)
|
||||||
? 1 // COLUMN: If 1D col-major numpy array, set to length (column vector)
|
? 1 // COLUMN: If 1D col-major numpy array, set to length (column vector)
|
||||||
: object->dimensions[1]))) {
|
: object->dimensions[1]))),
|
||||||
|
object_(object) {
|
||||||
|
|
||||||
if (((PyObject*)object != Py_None) && !PyArray_ISONESEGMENT(object))
|
if (((PyObject*)object != Py_None) && !PyArray_ISONESEGMENT(object))
|
||||||
throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map.");
|
throw std::invalid_argument("Numpy array must be a in one contiguous segment to be able to be transferred to a Eigen Map.");
|
||||||
|
Py_XINCREF(object_);
|
||||||
}
|
}
|
||||||
|
|
||||||
Map &operator=(const Map &other) {
|
Map &operator=(const Map &other) {
|
||||||
|
if (other.object_) {
|
||||||
|
new (this) Map(other.object_);
|
||||||
|
} else {
|
||||||
// Replace the memory that we point to (not a memory allocation)
|
// Replace the memory that we point to (not a memory allocation)
|
||||||
new (this) Map(const_cast<Scalar*>(other.data()),
|
new (this) Map(const_cast<Scalar*>(other.data()),
|
||||||
other.rows(),
|
other.rows(),
|
||||||
other.cols());
|
other.cols());
|
||||||
|
}
|
||||||
|
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
Map &operator=(const MatrixType &other) {
|
||||||
|
MapBase<MatrixType>::operator=(other);
|
||||||
return *this;
|
return *this;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -441,6 +486,13 @@ public:
|
||||||
operator MatrixType() const {
|
operator MatrixType() const {
|
||||||
return MatrixType(static_cast<Base>(*this));
|
return MatrixType(static_cast<Base>(*this));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual ~Map() {
|
||||||
|
Py_XDECREF(object_);
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
PyArrayObject * const object_;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
41
gtsam.h
41
gtsam.h
|
@ -938,6 +938,8 @@ virtual class SimpleCamera {
|
||||||
static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height);
|
static gtsam::SimpleCamera Level(const gtsam::Pose2& pose, double height);
|
||||||
static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
||||||
const gtsam::Point3& upVector, const gtsam::Cal3_S2& K);
|
const gtsam::Point3& upVector, const gtsam::Cal3_S2& K);
|
||||||
|
static gtsam::SimpleCamera Lookat(const gtsam::Point3& eye, const gtsam::Point3& target,
|
||||||
|
const gtsam::Point3& upVector);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
void print(string s) const;
|
void print(string s) const;
|
||||||
|
@ -2502,6 +2504,11 @@ class NavState {
|
||||||
#include <gtsam/navigation/PreintegratedRotation.h>
|
#include <gtsam/navigation/PreintegratedRotation.h>
|
||||||
virtual class PreintegratedRotationParams {
|
virtual class PreintegratedRotationParams {
|
||||||
PreintegratedRotationParams();
|
PreintegratedRotationParams();
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::PreintegratedRotationParams& expected, double tol);
|
||||||
|
|
||||||
void setGyroscopeCovariance(Matrix cov);
|
void setGyroscopeCovariance(Matrix cov);
|
||||||
void setOmegaCoriolis(Vector omega);
|
void setOmegaCoriolis(Vector omega);
|
||||||
void setBodyPSensor(const gtsam::Pose3& pose);
|
void setBodyPSensor(const gtsam::Pose3& pose);
|
||||||
|
@ -2509,13 +2516,23 @@ virtual class PreintegratedRotationParams {
|
||||||
Matrix getGyroscopeCovariance() const;
|
Matrix getGyroscopeCovariance() const;
|
||||||
|
|
||||||
// TODO(frank): allow optional
|
// TODO(frank): allow optional
|
||||||
// boost::optional<Vector3> getOmegaCoriolis() const;
|
// boost::optional<Vector> getOmegaCoriolis() const;
|
||||||
// boost::optional<Pose3> getBodyPSensor() const;
|
// boost::optional<Pose3> getBodyPSensor() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/navigation/PreintegrationParams.h>
|
#include <gtsam/navigation/PreintegrationParams.h>
|
||||||
virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
|
virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
|
||||||
PreintegrationParams(Vector n_gravity);
|
PreintegrationParams(Vector n_gravity);
|
||||||
|
|
||||||
|
static gtsam::PreintegrationParams* MakeSharedD(double g);
|
||||||
|
static gtsam::PreintegrationParams* MakeSharedU(double g);
|
||||||
|
static gtsam::PreintegrationParams* MakeSharedD(); // default g = 9.81
|
||||||
|
static gtsam::PreintegrationParams* MakeSharedU(); // default g = 9.81
|
||||||
|
|
||||||
|
// Testable
|
||||||
|
void print(string s) const;
|
||||||
|
bool equals(const gtsam::PreintegrationParams& expected, double tol);
|
||||||
|
|
||||||
void setAccelerometerCovariance(Matrix cov);
|
void setAccelerometerCovariance(Matrix cov);
|
||||||
void setIntegrationCovariance(Matrix cov);
|
void setIntegrationCovariance(Matrix cov);
|
||||||
void setUse2ndOrderCoriolis(bool flag);
|
void setUse2ndOrderCoriolis(bool flag);
|
||||||
|
@ -2523,7 +2540,6 @@ virtual class PreintegrationParams : gtsam::PreintegratedRotationParams {
|
||||||
Matrix getAccelerometerCovariance() const;
|
Matrix getAccelerometerCovariance() const;
|
||||||
Matrix getIntegrationCovariance() const;
|
Matrix getIntegrationCovariance() const;
|
||||||
bool getUse2ndOrderCoriolis() const;
|
bool getUse2ndOrderCoriolis() const;
|
||||||
void print(string s) const;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#include <gtsam/navigation/ImuFactor.h>
|
#include <gtsam/navigation/ImuFactor.h>
|
||||||
|
@ -2660,6 +2676,27 @@ virtual class Pose3AttitudeFactor : gtsam::NonlinearFactor{
|
||||||
gtsam::Unit3 bRef() const;
|
gtsam::Unit3 bRef() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#include <gtsam/navigation/Scenario.h>
|
||||||
|
virtual class Scenario {};
|
||||||
|
|
||||||
|
virtual class ConstantTwistScenario : gtsam::Scenario {
|
||||||
|
ConstantTwistScenario(const Vector& w, const Vector& v);
|
||||||
|
gtsam::Pose3 pose(double t) const;
|
||||||
|
Vector omega_b(double t) const;
|
||||||
|
Vector velocity_n(double t) const;
|
||||||
|
Vector acceleration_n(double t) const;
|
||||||
|
};
|
||||||
|
|
||||||
|
virtual class AcceleratingScenario : gtsam::Scenario {
|
||||||
|
AcceleratingScenario(const gtsam::Rot3& nRb, const gtsam::Point3& p0,
|
||||||
|
const Vector& v0, const Vector& a_n,
|
||||||
|
const Vector& omega_b);
|
||||||
|
gtsam::Pose3 pose(double t) const;
|
||||||
|
Vector omega_b(double t) const;
|
||||||
|
Vector velocity_n(double t) const;
|
||||||
|
Vector acceleration_n(double t) const;
|
||||||
|
};
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
// Utilities
|
// Utilities
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
Loading…
Reference in New Issue