Copter: rename tkoff_ to takeoff_

This commit is contained in:
Randy Mackay 2015-04-30 14:03:59 +09:00
parent 73d961cebc
commit 6f5b5c24f2
6 changed files with 18 additions and 20 deletions

View File

@ -44,12 +44,12 @@ static void althold_run()
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in); target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-tkoff_get_speed(), g.pilot_velocity_z_max-tkoff_get_speed()); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-takeoff_get_speed(), g.pilot_velocity_z_max-takeoff_get_speed());
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) { if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
tkoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
// indicate we are taking off // indicate we are taking off
@ -75,7 +75,7 @@ static void althold_run()
// call position controller // call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt); pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
tkoff_increment_alt_target(G_Dt); takeoff_increment_alt_target(G_Dt);
pos_control.update_z_controller(); pos_control.update_z_controller();
} }
} }

View File

@ -53,12 +53,12 @@ static void loiter_run()
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in); target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-tkoff_get_speed(), g.pilot_velocity_z_max-tkoff_get_speed()); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-takeoff_get_speed(), g.pilot_velocity_z_max-takeoff_get_speed());
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) { if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
tkoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
// indicate we are taking off // indicate we are taking off
@ -99,7 +99,7 @@ static void loiter_run()
// update altitude target and call position controller // update altitude target and call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt); pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
tkoff_increment_alt_target(G_Dt); takeoff_increment_alt_target(G_Dt);
pos_control.update_z_controller(); pos_control.update_z_controller();
} }
} }

View File

@ -171,12 +171,12 @@ static void poshold_run()
// get pilot desired climb rate (for alt-hold mode and take-off) // get pilot desired climb rate (for alt-hold mode and take-off)
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in); target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-tkoff_get_speed(), g.pilot_velocity_z_max-tkoff_get_speed()); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-takeoff_get_speed(), g.pilot_velocity_z_max-takeoff_get_speed());
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) { if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
tkoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
// indicate we are taking off // indicate we are taking off
@ -526,7 +526,7 @@ static void poshold_run()
} }
// update altitude target and call position controller // update altitude target and call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt); pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
tkoff_increment_alt_target(G_Dt); takeoff_increment_alt_target(G_Dt);
pos_control.update_z_controller(); pos_control.update_z_controller();
} }
} }

View File

@ -64,12 +64,12 @@ static void sport_run()
// get pilot desired climb rate // get pilot desired climb rate
target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in); target_climb_rate = get_pilot_desired_climb_rate(g.rc_3.control_in);
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-tkoff_get_speed(), g.pilot_velocity_z_max-tkoff_get_speed()); target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max-takeoff_get_speed(), g.pilot_velocity_z_max-takeoff_get_speed());
// check for take-off // check for take-off
if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) { if (ap.land_complete && (takeoff_state.running || g.rc_3.control_in > get_takeoff_trigger_throttle())) {
if (!takeoff_state.running) { if (!takeoff_state.running) {
tkoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); takeoff_timer_start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f));
} }
// indicate we are taking off // indicate we are taking off
@ -96,7 +96,7 @@ static void sport_run()
// call position controller // call position controller
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt); pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
tkoff_increment_alt_target(G_Dt); takeoff_increment_alt_target(G_Dt);
pos_control.update_z_controller(); pos_control.update_z_controller();
} }
} }

View File

@ -129,7 +129,7 @@ static bool set_mode(uint8_t mode)
// called at 100hz or more // called at 100hz or more
static void update_flight_mode() static void update_flight_mode()
{ {
tkoff_timer_update(); takeoff_timer_update();
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
// Update EKF speed limit - used to limit speed when we are using optical flow // Update EKF speed limit - used to limit speed when we are using optical flow

View File

@ -29,16 +29,14 @@ static bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
case ALT_HOLD: case ALT_HOLD:
case SPORT: case SPORT:
set_auto_armed(true); set_auto_armed(true);
tkoff_timer_start(pv_alt_above_origin(takeoff_alt_cm)-pos_control.get_pos_target().z); takeoff_timer_start(pv_alt_above_origin(takeoff_alt_cm)-pos_control.get_pos_target().z);
return true; return true;
} }
} }
return false; return false;
} }
static void takeoff_timer_start(float alt)
static void tkoff_timer_start(float alt)
{ {
float speed = min(wp_nav.get_speed_up(), max(g.pilot_velocity_z_max*2.0f/3.0f, g.pilot_velocity_z_max-50.0f)); float speed = min(wp_nav.get_speed_up(), max(g.pilot_velocity_z_max*2.0f/3.0f, g.pilot_velocity_z_max-50.0f));
@ -52,14 +50,14 @@ static void tkoff_timer_start(float alt)
takeoff_state.time_ms = (alt/takeoff_state.speed) * 1.0e3f; takeoff_state.time_ms = (alt/takeoff_state.speed) * 1.0e3f;
} }
static void tkoff_timer_update() static void takeoff_timer_update()
{ {
if (millis()-takeoff_state.start_ms >= takeoff_state.time_ms) { if (millis()-takeoff_state.start_ms >= takeoff_state.time_ms) {
takeoff_state.running = false; takeoff_state.running = false;
} }
} }
static void tkoff_increment_alt_target(float dt) static void takeoff_increment_alt_target(float dt)
{ {
if (takeoff_state.running) { if (takeoff_state.running) {
Vector3f pos_target = pos_control.get_pos_target(); Vector3f pos_target = pos_control.get_pos_target();
@ -68,7 +66,7 @@ static void tkoff_increment_alt_target(float dt)
} }
} }
static float tkoff_get_speed() static float takeoff_get_speed()
{ {
return takeoff_state.running?takeoff_state.speed:0.0f; return takeoff_state.running?takeoff_state.speed:0.0f;
} }