mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: Align received data to AP frame for Storm32 Serial
(Note: reversed pitch and yaw) to match NED. Update AP_Mount_SToRM32_serial.cpp
This commit is contained in:
parent
5f238f9296
commit
5b9403527b
|
@ -269,9 +269,10 @@ void AP_Mount_SToRM32_serial::parse_reply() {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Parse angles (Note: reversed pitch and yaw) to match ardupilot coordinate system
|
||||||
_current_angle.x = _buffer.data.imu1_roll;
|
_current_angle.x = _buffer.data.imu1_roll;
|
||||||
_current_angle.y = _buffer.data.imu1_pitch;
|
_current_angle.y = -_buffer.data.imu1_pitch;
|
||||||
_current_angle.z = _buffer.data.imu1_yaw;
|
_current_angle.z = -_buffer.data.imu1_yaw;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
|
|
Loading…
Reference in New Issue