diff --git a/gtsam/geometry/GeneralCameraT.h b/gtsam/geometry/GeneralCameraT.h index 92c93365f..73bf28b32 100644 --- a/gtsam/geometry/GeneralCameraT.h +++ b/gtsam/geometry/GeneralCameraT.h @@ -61,8 +61,8 @@ class GeneralCameraT { std::pair projectSafe( const Point3& P, - boost::optional H1, - boost::optional H2) const { + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { Point3 cameraPoint = calibrated_.pose().transform_to(P); return std::pair(