Copter: Write_Rate() moved to AC_AttitudeControl
This commit is contained in:
parent
c7b0dfc915
commit
ff72e163d9
@ -76,8 +76,8 @@ void Copter::Log_Write_Control_Tuning()
|
|||||||
void Copter::Log_Write_Attitude()
|
void Copter::Log_Write_Attitude()
|
||||||
{
|
{
|
||||||
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
|
ahrs.Write_Attitude(attitude_control->get_att_target_euler_rad() * RAD_TO_DEG);
|
||||||
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
|
attitude_control->Write_Rate(*pos_control);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write PIDS packets
|
// Write PIDS packets
|
||||||
void Copter::Log_Write_PIDS()
|
void Copter::Log_Write_PIDS()
|
||||||
|
Loading…
Reference in New Issue
Block a user