mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: fix global-pos-int velocity direction to NED
This commit is contained in:
parent
e6ece4cf3d
commit
144dd82fe4
@ -120,7 +120,7 @@ void Tracker::send_location(mavlink_channel_t chan)
|
||||
0,
|
||||
vel.x * 100, // X speed cm/s (+ve North)
|
||||
vel.y * 100, // Y speed cm/s (+ve East)
|
||||
vel.z * -100, // Z speed cm/s (+ve up)
|
||||
vel.z * 100, // Z speed cm/s (+ve Down)
|
||||
ahrs.yaw_sensor);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user