// acro_run - runs the acro controller // should be called at 100hz or more void Sub::acro_run() { float target_roll, target_pitch, target_yaw; int16_t pilot_throttle_scaled; // if motors not running reset angle targets if(!motors.armed()) { attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); // slow start if landed if (ap.land_complete) { motors.slow_start(true); } return; } // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); // get pilot's desired throttle pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->control_in); // run attitude controller attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); // output pilot's throttle without angle boost attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); //control_in is range 0-1000 //radio_in is raw pwm value motors.set_forward(channel_forward->radio_in); motors.set_strafe(channel_strafe->radio_in); }
void Copter::ModeAcro::run() { float target_roll, target_pitch, target_yaw; float pilot_throttle_scaled; // if not armed set throttle to zero and exit immediately if (!motors->armed() || ap.throttle_zero || !motors->get_interlock()) { motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); attitude_control->set_throttle_out_unstabilized(0,true,g.throttle_filt); return; } // clear landing flag set_land_complete(false); motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw); // get pilot's desired throttle pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in(), g2.acro_thr_mid); // run attitude controller attitude_control->input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); // output pilot's throttle without angle boost attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); }
// heli_acro_run - runs the acro controller // should be called at 100hz or more void Copter::heli_acro_run() { float target_roll, target_pitch, target_yaw; // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because // we may be in autorotation flight. These should be reset only when transitioning from disarmed // to armed, because the pilot will have placed the helicopter down on the landing pad. This is so // 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()) { heli_flags.init_targets_on_arming=true; attitude_control.set_yaw_target_to_current_heading(); } if(motors.armed() && heli_flags.init_targets_on_arming) { attitude_control.relax_bf_rate_controller(); attitude_control.set_yaw_target_to_current_heading(); if (motors.rotor_speed_above_critical()) { heli_flags.init_targets_on_arming=false; } } // send RC inputs direct into motors library for use during manual passthrough for helicopter setup heli_radio_passthrough(); if (!motors.has_flybar()){ // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); // run attitude controller attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); }else{ /* for fly-bar passthrough use control_in values with no deadzone. This gives true pass-through. */ float roll_in = channel_roll->pwm_to_angle_dz(0); float pitch_in = channel_pitch->pwm_to_angle_dz(0); float yaw_in; if (motors.supports_yaw_passthrough()) { // if the tail on a flybar heli has an external gyro then // also use no deadzone for the yaw control and // pass-through the input direct to output. yaw_in = channel_yaw->pwm_to_angle_dz(0); } else { // if there is no external gyro then run the usual // ACRO_YAW_P gain on the input control, including // deadzone yaw_in = get_pilot_desired_yaw_rate(channel_yaw->control_in); } // run attitude controller attitude_control.passthrough_bf_roll_pitch_rate_yaw(roll_in, pitch_in, yaw_in); } // output pilot's throttle without angle boost attitude_control.set_throttle_out(channel_throttle->control_in, false, g.throttle_filt); }
// heli_acro_run - runs the acro controller // should be called at 100hz or more void Copter::heli_acro_run() { float target_roll, target_pitch, target_yaw; int16_t pilot_throttle_scaled; // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because // we may be in autorotation flight. These should be reset only when transitioning from disarmed // to armed, because the pilot will have placed the helicopter down on the landing pad. This is so // 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()) { heli_flags.init_targets_on_arming=true; attitude_control.set_yaw_target_to_current_heading(); } if(motors.armed() && heli_flags.init_targets_on_arming) { attitude_control.set_yaw_target_to_current_heading(); if (motors.rotor_speed_above_critical()) { heli_flags.init_targets_on_arming=false; } } // send RC inputs direct into motors library for use during manual passthrough for helicopter setup heli_radio_passthrough(); if (!motors.has_flybar()){ // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->control_in, channel_pitch->control_in, channel_yaw->control_in, target_roll, target_pitch, target_yaw); // run attitude controller attitude_control.rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); }else{ // flybar helis only need yaw rate control get_pilot_desired_yaw_rate(channel_yaw->control_in, target_yaw); // run attitude controller attitude_control.passthrough_bf_roll_pitch_rate_yaw(channel_roll->control_in, channel_pitch->control_in, target_yaw); } // get pilot's desired throttle pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->control_in); // output pilot's throttle without angle boost attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); }
// heli_acro_run - runs the acro controller // should be called at 100hz or more void Copter::ModeAcro_Heli::run() { float target_roll, target_pitch, target_yaw; float pilot_throttle_scaled; // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because // we may be in autorotation flight. These should be reset only when transitioning from disarmed // to armed, because the pilot will have placed the helicopter down on the landing pad. This is so // 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(); attitude_control->reset_rate_controller_I_terms(); } 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) { set_land_complete(false); } if (!motors->has_flybar()){ // convert the input to the desired body frame rate get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw); if (motors->supports_yaw_passthrough()) { // if the tail on a flybar heli has an external gyro then // also use no deadzone for the yaw control and // pass-through the input direct to output. target_yaw = channel_yaw->get_control_in_zero_dz(); } // run attitude controller attitude_control->input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw); }else{ /* for fly-bar passthrough use control_in values with no deadzone. This gives true pass-through. */ float roll_in = channel_roll->get_control_in_zero_dz(); float pitch_in = channel_pitch->get_control_in_zero_dz(); float yaw_in; if (motors->supports_yaw_passthrough()) { // if the tail on a flybar heli has an external gyro then // also use no deadzone for the yaw control and // pass-through the input direct to output. yaw_in = channel_yaw->get_control_in_zero_dz(); } else { // if there is no external gyro then run the usual // ACRO_YAW_P gain on the input control, including // deadzone yaw_in = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); } // run attitude controller attitude_control->passthrough_bf_roll_pitch_rate_yaw(roll_in, pitch_in, yaw_in); } // get pilot's desired throttle pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); // output pilot's throttle without angle boost attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt); }