Browse Source

Copter: Employ heli_radio_passthrough() for servo setup

master
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
8f275ca2c4
  1. 3
      ArduCopter/flight_mode.pde
  2. 6
      ArduCopter/heli.pde
  3. 3
      ArduCopter/heli_control_acro.pde
  4. 5
      ArduCopter/heli_control_stabilize.pde

3
ArduCopter/flight_mode.pde

@ -241,6 +241,9 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode) @@ -241,6 +241,9 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
if (old_control_mode == ACRO) {
attitude_control.use_flybar_passthrough(false);
}
// reset RC Passthrough to motors
motors.reset_radio_passthrough();
#endif //HELI_FRAME
}

6
ArduCopter/heli.pde

@ -157,4 +157,10 @@ static void heli_update_rotor_speed_targets() @@ -157,4 +157,10 @@ static void heli_update_rotor_speed_targets()
}
}
// heli_radio_passthrough send RC inputs direct into motors library for use during manual passthrough for helicopter setup
static void heli_radio_passthrough()
{
motors.set_radio_passthrough(channel_roll->control_in, channel_pitch->control_in, channel_throttle->control_in, channel_yaw->control_in);
}
#endif // FRAME_CONFIG == HELI_FRAME

3
ArduCopter/heli_control_acro.pde

@ -36,6 +36,9 @@ static void heli_acro_run() @@ -36,6 +36,9 @@ static void heli_acro_run()
attitude_control.relax_bf_rate_controller();
}
// 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);

5
ArduCopter/heli_control_stabilize.pde

@ -36,7 +36,10 @@ static void heli_stabilize_run() @@ -36,7 +36,10 @@ static void heli_stabilize_run()
heli_flags.init_targets_on_arming=false;
attitude_control.relax_bf_rate_controller();
}
// send RC inputs direct into motors library for use during manual passthrough for helicopter setup
heli_radio_passthrough();
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();

Loading…
Cancel
Save