diff --git a/fuse_variables/include/fuse_variables/pinhole_camera_simple.h b/fuse_variables/include/fuse_variables/pinhole_camera_simple.h index 03862e89e..33557e39b 100644 --- a/fuse_variables/include/fuse_variables/pinhole_camera_simple.h +++ b/fuse_variables/include/fuse_variables/pinhole_camera_simple.h @@ -34,8 +34,8 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef FUSE_VARIABLES_PINHOLE_CAMERA_H -#define FUSE_VARIABLES_PINHOLE_CAMERA_H +#ifndef FUSE_VARIABLES_PINHOLE_CAMERA_SIMPLE_H +#define FUSE_VARIABLES_PINHOLE_CAMERA_SIMPLE_H #include #include @@ -164,4 +164,4 @@ class PinholeCameraSimple : public BaseCamera<3> BOOST_CLASS_EXPORT_KEY(fuse_variables::PinholeCameraSimple); -#endif // FUSE_VARIABLES_PINHOLE_CAMERA_H +#endif // FUSE_VARIABLES_PINHOLE_CAMERA_SIMPLE_H diff --git a/fuse_variables/test/test_pinhole_camera_simple.cpp b/fuse_variables/test/test_pinhole_camera_simple.cpp index 93c3510f3..530516b01 100644 --- a/fuse_variables/test/test_pinhole_camera_simple.cpp +++ b/fuse_variables/test/test_pinhole_camera_simple.cpp @@ -98,7 +98,7 @@ TEST(PinholeCameraSimple, Optimization) K.r2() = 5; // Create a simple a constraint - ceres::CostFunction* cost_function = new ceres::AutoDiffCostFunction(new CostFunctor()); + ceres::CostFunction* cost_function = new ceres::AutoDiffCostFunction(new CostFunctor()); // Build the problem. ceres::Problem problem;