mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_LTM_Telem: Change from division to multiplication
This commit is contained in:
parent
7897807a78
commit
ae896ff8c2
@ -168,9 +168,9 @@ void AP_LTM_Telem::send_Aframe(void)
|
|||||||
{
|
{
|
||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
WITH_SEMAPHORE(ahrs.get_semaphore());
|
WITH_SEMAPHORE(ahrs.get_semaphore());
|
||||||
pitch = roundf(ahrs.pitch_sensor / 100.0); // attitude pitch in degrees
|
pitch = roundf(ahrs.pitch_sensor * 0.01); // attitude pitch in degrees
|
||||||
roll = roundf(ahrs.roll_sensor / 100.0); // attitude roll in degrees
|
roll = roundf(ahrs.roll_sensor * 0.01); // attitude roll in degrees
|
||||||
heading = roundf(ahrs.yaw_sensor / 100.0); // heading in degrees
|
heading = roundf(ahrs.yaw_sensor * 0.01); // heading in degrees
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t lt_buff[LTM_AFRAME_SIZE];
|
uint8_t lt_buff[LTM_AFRAME_SIZE];
|
||||||
|
Loading…
Reference in New Issue
Block a user