ardupilot/ArduCopter/heli_control_stabilize.pde

61 lines
2.4 KiB
Plaintext
Raw Normal View History

2014-01-30 04:40:43 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#if FRAME_CONFIG == HELI_FRAME
/*
* heli_control_stabilize.pde - init and run calls for stabilize flight mode for trad heli
*/
// stabilize_init - initialise stabilize controller
static bool heli_stabilize_init(bool ignore_checks)
{
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control.set_alt_target(0);
return true;
}
// stabilize_run - runs the main stabilize controller
// should be called at 100hz or more
static void heli_stabilize_run()
{
int16_t target_roll, target_pitch;
float target_yaw_rate;
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) {
heli_flags.init_targets_on_arming=false;
attitude_control.relax_bf_rate_controller();
}
2014-01-30 04:40:43 -04:00
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// convert pilot input to lean angles
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
// get pilot's desired yaw rate
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_collective(g.rc_3.control_in);
2014-01-30 04:40:43 -04:00
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain());
2014-01-30 04:40:43 -04:00
// output pilot's throttle - note that TradHeli does not used angle-boost
attitude_control.set_throttle_out(pilot_throttle_scaled, false);
}
#endif //HELI_FRAME