ardupilot/ArduCopter/commands.pde

38 lines
1008 B
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static int32_t get_RTL_alt()
{
if(g.rtl_altitude <= 0) {
return min(current_loc.alt, RTL_ALT_MAX);
}else if (g.rtl_altitude < current_loc.alt) {
return min(current_loc.alt, RTL_ALT_MAX);
2012-08-16 21:50:03 -03:00
}else{
return g.rtl_altitude;
2012-08-16 21:50:03 -03:00
}
}
// run this at setup on the ground
// -------------------------------
static void init_home()
{
2012-11-10 01:55:51 -04:00
set_home_is_set(true);
2014-01-03 07:33:57 -04:00
ahrs.set_home(g_gps->latitude, g_gps->longitude, 0);
2012-08-16 21:50:03 -03:00
inertial_nav.setup_home_position();
2014-02-27 22:16:33 -04:00
// log new home position which mission library will pull from ahrs
if (g.log_bitmask & MASK_LOG_CMD) {
AP_Mission::Mission_Command temp_cmd;
if (mission.read_cmd_from_storage(0, temp_cmd)) {
Log_Write_Cmd(temp_cmd);
}
2014-02-27 22:16:33 -04:00
}
2012-08-16 21:50:03 -03:00
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
scaleLongDown = longitude_scale(home);
scaleLongUp = 1.0f/scaleLongDown;
}