mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: make SET_ATTITUDE_TARGET changes persistent
In the sense that it no longer "times out"
This commit is contained in:
parent
9faf1ef273
commit
9a6fb5232e
@ -54,6 +54,9 @@ void Sub::handle_attitude()
|
|||||||
target_roll = 100 * degrees(target_roll);
|
target_roll = 100 * degrees(target_roll);
|
||||||
target_pitch = 100 * degrees(target_pitch);
|
target_pitch = 100 * degrees(target_pitch);
|
||||||
target_yaw = 100 * degrees(target_yaw);
|
target_yaw = 100 * degrees(target_yaw);
|
||||||
|
last_roll = target_roll;
|
||||||
|
last_pitch = target_pitch;
|
||||||
|
last_pilot_heading = target_yaw;
|
||||||
attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
|
attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
|
||||||
} else {
|
} else {
|
||||||
// If we don't have a mavlink attitude target, we use the pilot's input instead
|
// If we don't have a mavlink attitude target, we use the pilot's input instead
|
||||||
|
Loading…
Reference in New Issue
Block a user