mirror of https://github.com/ArduPilot/ardupilot
Plane: Write_Rate() moved to AC_AttitudeControl
This commit is contained in:
parent
ff72e163d9
commit
8596466d5a
|
@ -1764,7 +1764,7 @@ void QuadPlane::update(void)
|
|||
const bool motors_active = in_vtol_mode() || assisted_flight;
|
||||
if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) {
|
||||
// log RATE at main loop rate
|
||||
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
|
||||
attitude_control->Write_Rate(*pos_control);
|
||||
|
||||
// log CTRL and MOTB at 10 Hz
|
||||
if (now - last_ctrl_log_ms > 100) {
|
||||
|
|
Loading…
Reference in New Issue