Copter: Tradheli moves init_targets_on_arming flag to motors

This commit is contained in:
bnsgeyer 2019-01-02 23:57:03 -05:00 committed by Randy Mackay
parent 2ddb3f6697
commit 12f4d8518e
5 changed files with 4 additions and 38 deletions

View File

@ -23,9 +23,6 @@ Copter::Mode::Mode(void) :
channel_throttle(copter.channel_throttle),
channel_yaw(copter.channel_yaw),
G_Dt(copter.G_Dt),
#if FRAME_CONFIG == HELI_FRAME
heli_flags(copter.heli_flags),
#endif
ap(copter.ap)
{ };

View File

@ -177,10 +177,6 @@ protected:
// altitude below which we do no navigation in auto takeoff
static float auto_takeoff_no_nav_alt_cm;
#if FRAME_CONFIG == HELI_FRAME
heli_flags_t &heli_flags;
#endif
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the Mode base
// class.

View File

@ -35,19 +35,10 @@ void Copter::ModeAcro_Heli::run()
// that the servos move in a realistic fashion while disarmed for operational checks.
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
if(!motors->armed()) {
copter.heli_flags.init_targets_on_arming=true;
attitude_control->set_attitude_target_to_current_attitude();
if (motors->init_targets_on_arming()) {
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_attitude_target_to_current_attitude();
}
if(motors->armed() && copter.heli_flags.init_targets_on_arming) {
attitude_control->set_attitude_target_to_current_attitude();
attitude_control->reset_rate_controller_I_terms();
if (motors->get_interlock()) {
copter.heli_flags.init_targets_on_arming=false;
}
}
// clear landing flag above zero throttle
if (motors->armed() && motors->get_interlock() && motors->rotor_runup_complete() && !ap.throttle_zero) {

View File

@ -65,7 +65,6 @@ void Copter::ModeAltHold::run()
#if FRAME_CONFIG == HELI_FRAME
// force descent rate and call position controller
pos_control->set_alt_target_from_climb_rate(-abs(g.land_speed), G_Dt, false);
heli_flags.init_targets_on_arming=true;
if (ap.land_complete_maybe) {
pos_control->relax_alt_hold_controllers(0.0f);
}
@ -76,11 +75,6 @@ void Copter::ModeAltHold::run()
break;
case AltHold_Takeoff:
#if FRAME_CONFIG == HELI_FRAME
if (heli_flags.init_targets_on_arming) {
heli_flags.init_targets_on_arming=false;
}
#endif
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
@ -117,12 +111,9 @@ void Copter::ModeAltHold::run()
}
#if FRAME_CONFIG == HELI_FRAME
if (heli_flags.init_targets_on_arming) {
if (motors->init_targets_on_arming()) {
attitude_control->reset_rate_controller_I_terms();
attitude_control->set_yaw_target_to_current_heading();
if (motors->get_interlock()) {
heli_flags.init_targets_on_arming=false;
}
}
#else
attitude_control->reset_rate_controller_I_terms();

View File

@ -28,18 +28,9 @@ void Copter::ModeStabilize_Heli::run()
// that the servos move in a realistic fashion while disarmed for operational checks.
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
if(!motors->armed()) {
copter.heli_flags.init_targets_on_arming = true;
attitude_control->set_yaw_target_to_current_heading();
if (motors->init_targets_on_arming()) {
attitude_control->reset_rate_controller_I_terms();
}
if(motors->armed() && copter.heli_flags.init_targets_on_arming) {
attitude_control->set_yaw_target_to_current_heading();
attitude_control->reset_rate_controller_I_terms();
if (motors->get_interlock()) {
copter.heli_flags.init_targets_on_arming=false;
}
}
// clear landing flag above zero throttle