ArduCopter: inertial nav - only initialise horizontal position when home is initialised

This commit is contained in:
rmackay9 2012-12-25 12:39:25 +09:00
parent e859549814
commit 3ff091efb6
1 changed files with 0 additions and 2 deletions

View File

@ -190,8 +190,6 @@ static void init_home()
#if INERTIAL_NAV_XY == ENABLED #if INERTIAL_NAV_XY == ENABLED
// set inertial nav's home position // set inertial nav's home position
inertial_nav.set_current_position(g_gps->longitude, g_gps->latitude); inertial_nav.set_current_position(g_gps->longitude, g_gps->latitude);
inertial_nav.set_altitude(home.alt);
inertial_nav.set_velocity_z(0);
#endif #endif
if (g.log_bitmask & MASK_LOG_CMD) if (g.log_bitmask & MASK_LOG_CMD)