mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Plane: log ANG attitude message
This commit is contained in:
parent
505d05d5f8
commit
2e194383d2
@ -1772,6 +1772,10 @@ void QuadPlane::update(void)
|
|||||||
if (motors->armed()) {
|
if (motors->armed()) {
|
||||||
const bool motors_active = in_vtol_mode() || assisted_flight;
|
const bool motors_active = in_vtol_mode() || assisted_flight;
|
||||||
if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) {
|
if (motors_active && (motors->get_spool_state() != AP_Motors::SpoolState::SHUT_DOWN)) {
|
||||||
|
// log ANG at main loop rate
|
||||||
|
if (show_vtol_view()) {
|
||||||
|
attitude_control->Write_ANG();
|
||||||
|
}
|
||||||
// log RATE at main loop rate
|
// log RATE at main loop rate
|
||||||
attitude_control->Write_Rate(*pos_control);
|
attitude_control->Write_Rate(*pos_control);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user