diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index f9edafc46d..584619d441 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -129,7 +129,7 @@ static void init_home() set_cmd_with_index(home, 0); // set inertial nav's home position - inertial_nav.set_current_position(g_gps->longitude, g_gps->latitude); + inertial_nav.set_home_position(g_gps->longitude, g_gps->latitude); if (g.log_bitmask & MASK_LOG_CMD) Log_Write_Cmd(0, &home); diff --git a/libraries/AP_InertialNav/AP_InertialNav.cpp b/libraries/AP_InertialNav/AP_InertialNav.cpp index d3c15c632f..d1ed648aa6 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav.cpp @@ -218,8 +218,8 @@ int32_t AP_InertialNav::get_longitude() const return _base_lon + (int32_t)((_position_base.y+_position_correction.y) / _lon_to_m_scaling); } -// set_current_position - all internal calculations are recorded as the distances from this point -void AP_InertialNav::set_current_position(int32_t lon, int32_t lat) +// set_home_position - all internal calculations are recorded as the distances from this point +void AP_InertialNav::set_home_position(int32_t lon, int32_t lat) { // set base location _base_lon = lon; diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index d292da6afb..4dbb4fdff6 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -69,8 +69,8 @@ public: int32_t get_latitude() const; int32_t get_longitude() const; - // set_current_position - all internal calculations are recorded as the distances from this point - void set_current_position(int32_t lon, int32_t lat); + // set_home_position - all internal calculations are recorded as the distances from this point + void set_home_position(int32_t lon, int32_t lat); // get latitude & longitude positions from base location (in cm) float get_latitude_diff() const;