Go to the documentation of this file.
16 using namespace gtsam;
21 int main(
int argc,
char* argv[]) {
30 auto poses =
createPoses(init_pose, delta_pose1, steps);
31 auto poses2 =
createPoses(init_pose, delta_pose2, steps);
32 auto poses3 =
createPoses(init_pose, delta_pose3, steps);
35 poses.insert( poses.end(), poses2.begin(), poses2.end() );
36 poses.insert( poses.end(), poses3.begin(), poses3.end() );
53 Pose3_ body_T_sensor_(
'T', 0);
59 for (
size_t i = 0;
i < poses.size(); ++
i) {
60 auto world_T_sensor = poses[
i].compose(body_T_sensor_gt);
61 for (
size_t j = 0;
j < points.size(); ++
j) {
84 for (
size_t i = 0;
i < poses.size(); ++
i)
86 for (
size_t j = 0;
j < points.size(); ++
j)
98 body_T_sensor_gt.
print(
"\nGround truth body_T_sensor\n");
virtual const Values & optimize()
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
void print(const std::string &s="") const
print with optional string
double error(const Values &values) const
const ValueType at(Key j) const
void print(const Matrix &A, const string &s, ostream &stream)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Rot3 Rodrigues(const Vector3 &w)
Factor graph that supports adding ExpressionFactors directly.
std::vector< Pose3 > createPoses(const Pose3 &init=Pose3(Rot3::Ypr(M_PI_2, 0, -M_PI_2), {30, 0, 0}), const Pose3 &delta=Pose3(Rot3::Ypr(0, -M_PI_4, 0), {sin(M_PI_4) *30, 0, 30 *(1 - sin(M_PI_4))}), int steps=8)
Expression< Point3 > Point3_
Common expressions for solving geometry/slam/sfm problems.
Expression< Pose3 > Pose3_
NonlinearFactorGraph graph
Simple example for the structure-from-motion problems.
static Rot3 RzRyRx(double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix,...
static Point2 measurement(323.0, 240.0)
A non-templated config holding any types of Manifold-group elements.
void addExpressionFactor(const SharedNoiseModel &R, const T &z, const Expression< T > &h)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:36