ArduCopter: remove unused functions do_target_yaw, do_loiter_at_location, get_altitude_error and clear_new_altitude

This commit is contained in:
rmackay9 2012-12-10 17:30:50 +09:00
parent 047f848cc7
commit f522ef078e
2 changed files with 0 additions and 41 deletions

View File

@ -693,28 +693,6 @@ static void do_change_speed()
g.waypoint_speed_max = command_cond_queue.p1 * 100;
}
// do_target_yaw - initialise yaw mode based on requested yaw target
static void do_target_yaw()
{
switch( command_cond_queue.p1 ) {
case MAV_ROI_NONE:
set_yaw_mode(YAW_HOLD);
break;
case MAV_ROI_WPNEXT:
set_yaw_mode(YAW_LOOK_AT_NEXT_WP);
break;
case MAV_ROI_LOCATION:
yaw_look_at_WP = command_cond_queue;
set_yaw_mode(YAW_LOOK_AT_LOCATION);
break;
}
}
static void do_loiter_at_location()
{
next_WP = current_loc;
}
static void do_jump()
{
// Used to track the state of the jump command in Mission scripting

View File

@ -533,25 +533,6 @@ static void update_crosstrack(void)
}
}
static int32_t get_altitude_error()
{
// Next_WP alt is our target alt
// It changes based on climb rate
// until it reaches the target_altitude
#if INERTIAL_NAV_Z == ENABLED
// use inertial nav for altitude error
return next_WP.alt - inertial_nav.get_altitude();
#else
return next_WP.alt - current_loc.alt;
#endif
}
static void clear_new_altitude()
{
set_alt_change(REACHED_ALT);
}
static void force_new_altitude(int32_t new_alt)
{
next_WP.alt = new_alt;