add missing header guards under timing/ and examples/

release/4.3a0
acxz 2022-02-21 11:59:01 -05:00
parent 2ba8683454
commit 1bf53fc414
2 changed files with 4 additions and 0 deletions

View File

@ -22,6 +22,8 @@
* Passing function argument allows to specificy an initial position, a pose increment and step count.
*/
#pragma once
// As this is a full 3D problem, we will use Pose3 variables to represent the camera
// positions and Point3 variables (x, y, z) to represent the landmark coordinates.
// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).

View File

@ -16,6 +16,8 @@
* @date July 5, 2015
*/
#pragma once
#include <gtsam/sfm/SfmData.h>
#include <gtsam/slam/dataset.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>