mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: fixed wrap of yaw in AHRS_View
This commit is contained in:
parent
7737c3445c
commit
6b6ad6ddf2
@ -62,6 +62,9 @@ void AP_AHRS_View::update(bool skip_ins_update)
|
||||
roll_sensor = degrees(roll) * 100;
|
||||
pitch_sensor = degrees(pitch) * 100;
|
||||
yaw_sensor = degrees(yaw) * 100;
|
||||
if (yaw_sensor < 0) {
|
||||
yaw_sensor += 36000;
|
||||
}
|
||||
|
||||
ahrs.calc_trig(rot_body_to_ned,
|
||||
trig.cos_roll, trig.cos_pitch, trig.cos_yaw,
|
||||
|
Loading…
Reference in New Issue
Block a user