Plane: fixes for AP_Mount API

This commit is contained in:
Andrew Tridgell 2013-10-12 17:59:00 +11:00 committed by Randy Mackay
parent f62c53502d
commit a3168bcbaa

View File

@ -678,13 +678,13 @@ static uint16_t mainLoop_count;
#if MOUNT == ENABLED #if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // 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? // mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
AP_Mount camera_mount(&current_loc, g_gps, &ahrs, 0); AP_Mount camera_mount(&current_loc, g_gps, ahrs, 0);
#endif #endif
#if MOUNT2 == ENABLED #if MOUNT2 == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only. // 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? // mabe one could use current_loc for lat/lon too and eliminate g_gps alltogether?
AP_Mount camera_mount2(&current_loc, g_gps, &ahrs, 1); AP_Mount camera_mount2(&current_loc, g_gps, ahrs, 1);
#endif #endif
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////