mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: viewpro fix for swapped ahrs roll pitch
This commit is contained in:
parent
c17a11b3c8
commit
456c1bf39c
|
@ -702,8 +702,8 @@ bool AP_Mount_Viewpro::send_m_ahrs()
|
|||
frame_id: FrameId::M_AHRS,
|
||||
data_type: 0x07, // Bit0: Attitude, Bit1: GPS, Bit2 Gyro
|
||||
unused2to8 : {0, 0, 0, 0, 0, 0, 0},
|
||||
pitch_be: htobe16(-degrees(AP::ahrs().get_pitch()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle pitch angle. 1bit=360deg/65536
|
||||
roll_be: htobe16(degrees(AP::ahrs().get_roll()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle roll angle. 1bit=360deg/65536
|
||||
pitch_be: htobe16(-degrees(AP::ahrs().get_pitch()) * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle pitch angle. 1bit=360deg/65536
|
||||
yaw_be: htobe16(veh_yaw_deg * AP_MOUNT_VIEWPRO_DEG_TO_OUTPUT), // vehicle yaw angle. 1bit=360deg/65536
|
||||
date_be: htobe16(date), // bit0~6:year, bit7~10:month, bit11~15:day
|
||||
seconds_utc: {uint8_t((second_hundredths & 0xFF0000ULL) >> 16), // seconds * 100 MSB. 1bit = 0.01sec
|
||||
|
|
|
@ -291,8 +291,8 @@ private:
|
|||
FrameId frame_id; // always 0xB1
|
||||
uint8_t data_type; // should be 0x07. Bit0: Attitude, Bit1: GPS, Bit2 Gyro
|
||||
uint8_t unused2to8[7]; // unused
|
||||
be16_t pitch_be; // vehicle pitch angle. 1bit=360deg/65536
|
||||
be16_t roll_be; // vehicle roll angle. 1bit=360deg/65536
|
||||
be16_t pitch_be; // vehicle pitch angle. 1bit=360deg/65536
|
||||
be16_t yaw_be; // vehicle yaw angle. 1bit=360deg/65536
|
||||
be16_t date_be; // bit0~6:year, bit7~10:month, bit11~15:day
|
||||
uint8_t seconds_utc[3]; // seconds. 1bit = 0.01sec
|
||||
|
|
Loading…
Reference in New Issue