|
|
|
@ -435,13 +435,13 @@ void Copter::ModeGuided::pos_control_run()
@@ -435,13 +435,13 @@ void Copter::ModeGuided::pos_control_run()
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (copter.auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate); |
|
|
|
|
} else if (auto_yaw_mode == AUTO_YAW_RATE) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from mavlink command or mission item
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_yaw_rate_cds(), get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_yaw_rate_cds()); |
|
|
|
|
} else { |
|
|
|
|
// roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_heading(), true, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), get_auto_heading(), true); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -489,13 +489,13 @@ void Copter::ModeGuided::vel_control_run()
@@ -489,13 +489,13 @@ void Copter::ModeGuided::vel_control_run()
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (copter.auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate); |
|
|
|
|
} else if (auto_yaw_mode == AUTO_YAW_RATE) { |
|
|
|
|
// roll & pitch from velocity controller, yaw rate from mavlink command or mission item
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_yaw_rate_cds(), get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_yaw_rate_cds()); |
|
|
|
|
} else { |
|
|
|
|
// roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_heading(), true, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_heading(), true); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -561,13 +561,13 @@ void Copter::ModeGuided::posvel_control_run()
@@ -561,13 +561,13 @@ void Copter::ModeGuided::posvel_control_run()
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (copter.auto_yaw_mode == AUTO_YAW_HOLD) { |
|
|
|
|
// roll & pitch from waypoint controller, yaw rate from pilot
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), target_yaw_rate); |
|
|
|
|
} else if (auto_yaw_mode == AUTO_YAW_RATE) { |
|
|
|
|
// roll & pitch from position-velocity controller, yaw rate from mavlink command or mission item
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_yaw_rate_cds(), get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_yaw_rate_cds()); |
|
|
|
|
} else { |
|
|
|
|
// roll, pitch from waypoint controller, yaw heading from GCS or auto_heading()
|
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_heading(), true, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(pos_control->get_roll(), pos_control->get_pitch(), get_auto_heading(), true); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -620,9 +620,9 @@ void Copter::ModeGuided::angle_control_run()
@@ -620,9 +620,9 @@ void Copter::ModeGuided::angle_control_run()
|
|
|
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
|
if (guided_angle_state.use_yaw_rate) { |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(roll_in, pitch_in, yaw_rate_in, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(roll_in, pitch_in, yaw_rate_in); |
|
|
|
|
} else { |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true, get_smoothing_gain()); |
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_yaw(roll_in, pitch_in, yaw_in, true); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// call position controller
|
|
|
|
|