diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index 7abf5547b..c42ed222a 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -47,9 +47,9 @@ public: /// evaluateError Vector evaluateError( const Pose3& pose, const OrientedPlane3& plane, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { - auto predicted_plane = OrientedPlane3::Transform(plane, pose, H1, H2); + boost::optional Hpose = boost::none, + boost::optional Hplane = boost::none) const override { + auto predicted_plane = plane.transform(pose, Hplane, Hpose); return predicted_plane.error(measured_p_); } };