diff --git a/cpp/CalibratedCamera.cpp b/cpp/CalibratedCamera.cpp index f714c499e..baaeab1cd 100644 --- a/cpp/CalibratedCamera.cpp +++ b/cpp/CalibratedCamera.cpp @@ -5,6 +5,7 @@ * Author: dellaert */ +#include "Point2.h" #include "CalibratedCamera.h" namespace gtsam { diff --git a/cpp/CalibratedCamera.h b/cpp/CalibratedCamera.h index 36f17ba8a..0f67f1d4d 100644 --- a/cpp/CalibratedCamera.h +++ b/cpp/CalibratedCamera.h @@ -8,12 +8,13 @@ #ifndef CalibratedCAMERA_H_ #define CalibratedCAMERA_H_ -#include "Point2.h" #include "Pose2.h" #include "Pose3.h" namespace gtsam { + class Point2; + /** * projects a 3-dimensional point in camera coordinates into the * camera and returns a 2-dimensional point, no calibration applied @@ -44,6 +45,8 @@ namespace gtsam { /** * Create a level camera at the given 2D pose and height + * @param pose2 specifies the location and viewing direction + * (theta 0 = looking in direction of positive X axis) */ static CalibratedCamera level(const Pose2& pose2, double height);