InertialNav: rename set_current_position to set_home_position

This commit is contained in:
Randy Mackay 2013-09-19 15:57:22 +09:00
parent 2f5b32bada
commit 262fcb301a
3 changed files with 5 additions and 5 deletions

View File

@ -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);

View File

@ -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;

View File

@ -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;