add missing header guards under timing/ and examples/
parent
2ba8683454
commit
1bf53fc414
|
@ -22,6 +22,8 @@
|
||||||
* Passing function argument allows to specificy an initial position, a pose increment and step count.
|
* 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
|
// 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.
|
// 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).
|
// Camera observations of landmarks (i.e. pixel coordinates) will be stored as Point2 (x, y).
|
||||||
|
|
|
@ -16,6 +16,8 @@
|
||||||
* @date July 5, 2015
|
* @date July 5, 2015
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
#include <gtsam/sfm/SfmData.h>
|
#include <gtsam/sfm/SfmData.h>
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
|
||||||
|
|
Loading…
Reference in New Issue