|
|
@ -6,21 +6,21 @@ |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
|
|
// stabilize_init - initialise stabilize controller
|
|
|
|
// stabilize_init - initialise stabilize controller
|
|
|
|
bool Copter::heli_stabilize_init(bool ignore_checks) |
|
|
|
bool Copter::FlightMode_STABILIZE_Heli::init(bool ignore_checks) |
|
|
|
{ |
|
|
|
{ |
|
|
|
// set target altitude to zero for reporting
|
|
|
|
// 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?
|
|
|
|
// 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); |
|
|
|
pos_control->set_alt_target(0); |
|
|
|
|
|
|
|
|
|
|
|
// set stab collective true to use stabilize scaled collective pitch range
|
|
|
|
// set stab collective true to use stabilize scaled collective pitch range
|
|
|
|
input_manager.set_use_stab_col(true); |
|
|
|
_copter.input_manager.set_use_stab_col(true); |
|
|
|
|
|
|
|
|
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// stabilize_run - runs the main stabilize controller
|
|
|
|
// stabilize_run - runs the main stabilize controller
|
|
|
|
// should be called at 100hz or more
|
|
|
|
// should be called at 100hz or more
|
|
|
|
void Copter::heli_stabilize_run() |
|
|
|
void Copter::FlightMode_STABILIZE_Heli::run() |
|
|
|
{ |
|
|
|
{ |
|
|
|
float target_roll, target_pitch; |
|
|
|
float target_roll, target_pitch; |
|
|
|
float target_yaw_rate; |
|
|
|
float target_yaw_rate; |
|
|
@ -33,16 +33,16 @@ void Copter::heli_stabilize_run() |
|
|
|
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
|
|
|
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
|
|
|
|
|
|
|
|
|
|
|
if(!motors->armed()) { |
|
|
|
if(!motors->armed()) { |
|
|
|
heli_flags.init_targets_on_arming=true; |
|
|
|
_copter.heli_flags.init_targets_on_arming = true; |
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
if(motors->armed() && heli_flags.init_targets_on_arming) { |
|
|
|
if(motors->armed() && _copter.heli_flags.init_targets_on_arming) { |
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
attitude_control->set_yaw_target_to_current_heading(); |
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
attitude_control->reset_rate_controller_I_terms(); |
|
|
|
if (motors->get_interlock()) { |
|
|
|
if (motors->get_interlock()) { |
|
|
|
heli_flags.init_targets_on_arming=false; |
|
|
|
_copter.heli_flags.init_targets_on_arming=false; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -56,13 +56,13 @@ void Copter::heli_stabilize_run() |
|
|
|
|
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
|
|
|
// To-Do: convert get_pilot_desired_lean_angles to return angles as floats
|
|
|
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max); |
|
|
|
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, _copter.aparm.angle_max); |
|
|
|
|
|
|
|
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); |
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); |
|
|
|
|
|
|
|
|
|
|
|
// get pilot's desired throttle
|
|
|
|
// get pilot's desired throttle
|
|
|
|
pilot_throttle_scaled = input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); |
|
|
|
pilot_throttle_scaled = _copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in()); |
|
|
|
|
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
// call attitude controller
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); |
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate, get_smoothing_gain()); |
|
|
|