Go to the documentation of this file.
39 using namespace gtsam;
40 using namespace noiseModel;
43 int main(
int argc,
char* argv[]) {
45 Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
68 for (
size_t i = 0;
i < poses.size(); ++
i) {
71 for (
size_t j = 0;
j < points.size(); ++
j) {
88 for (
size_t i = 0;
i < poses.size(); ++
i)
90 for (
size_t j = 0;
j < points.size(); ++
j)
Expression< Point3 > Point3_
virtual const Values & optimize()
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)
double error(const Values &values) const
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Factor graph that supports adding ExpressionFactors directly.
int main(int argc, char *argv[])
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)
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
Common expressions for solving geometry/slam/sfm problems.
T compose(const T &t1, const T &t2)
std::shared_ptr< Diagonal > shared_ptr
The most common 5DOF 3D->2D calibration.
std::shared_ptr< Isotropic > shared_ptr
static const CalibratedCamera camera(kDefaultPose)
NonlinearFactorGraph graph
Simple example for the structure-from-motion problems.
static Point2 measurement(323.0, 240.0)
A non-templated config holding any types of Manifold-group elements.
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
void addExpressionFactor(const SharedNoiseModel &R, const T &z, const Expression< T > &h)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:11