diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 4cda4bddef..e1c27dea29 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -678,13 +678,13 @@ static uint16_t mainLoop_count; #if MOUNT == ENABLED // current_loc uses the baro/gps soloution for altitude rather than gps only. // mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether? -AP_Mount camera_mount(¤t_loc, g_gps, &ahrs, 0); +AP_Mount camera_mount(¤t_loc, g_gps, ahrs, 0); #endif #if MOUNT2 == ENABLED // current_loc uses the baro/gps soloution for altitude rather than gps only. // mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether? -AP_Mount camera_mount2(¤t_loc, g_gps, &ahrs, 1); +AP_Mount camera_mount2(¤t_loc, g_gps, ahrs, 1); #endif ////////////////////////////////////////////////////////////////////////////////