mirror of https://github.com/ArduPilot/ardupilot
TradHeli: Change behavior of Acro and Stabilize modes when disarmed. Servos should move realistically for testing when disarmed.
This commit is contained in:
parent
5b13b2b3da
commit
4b5167e529
|
@ -16,14 +16,25 @@ static bool heli_acro_init(bool ignore_checks)
|
|||
static void heli_acro_run()
|
||||
{
|
||||
float target_roll, target_pitch, target_yaw;
|
||||
|
||||
// if not armed or main rotor not up to full speed clear stabilized rate errors
|
||||
// unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
||||
if(!motors.armed() || !motors.motor_runup_complete()) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
static bool init_targets_on_arming;
|
||||
|
||||
// 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()) {
|
||||
init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
if(motors.armed() && init_targets_on_arming) {
|
||||
init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
|
||||
}
|
||||
|
||||
// To-Do: add support for flybarred helis
|
||||
|
||||
// convert the input to the desired body frame rate
|
||||
|
|
|
@ -20,9 +20,24 @@ static void heli_stabilize_run()
|
|||
int16_t target_roll, target_pitch;
|
||||
float target_yaw_rate;
|
||||
int16_t pilot_throttle_scaled;
|
||||
static bool init_targets_on_arming;
|
||||
|
||||
// To-Do: should tradheli reset roll, pitch, yaw targets when motors are not runup?
|
||||
|
||||
// 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()) {
|
||||
init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
if(motors.armed() && init_targets_on_arming) {
|
||||
init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
}
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
|
|
Loading…
Reference in New Issue