AC_AttitudeControl: reset target attitude

added method to reset current vehicle attitude to support swash
behaviors in Trad Heli
This commit is contained in:
bnsgeyer 2017-04-15 20:34:13 -04:00 committed by Randy Mackay
parent 2e11bef518
commit aec4045f91

View File

@ -107,6 +107,9 @@ public:
// reset rate controller I terms
void reset_rate_controller_I_terms();
// Sets attitude target to vehicle attitude
void set_attitude_target_to_current_attitude() { _attitude_target_quat.from_rotation_matrix(_ahrs.get_rotation_body_to_ned()); }
// Sets yaw target to vehicle heading
void set_yaw_target_to_current_heading() { shift_ef_yaw_target(degrees(_ahrs.yaw - _attitude_target_euler_angle.z)*100.0f); }