Tracker: fix global-pos-int velocity direction to NED

This commit is contained in:
Randy Mackay 2018-02-08 08:05:45 +09:00
parent e6ece4cf3d
commit 144dd82fe4

View File

@ -120,7 +120,7 @@ void Tracker::send_location(mavlink_channel_t chan)
0, 0,
vel.x * 100, // X speed cm/s (+ve North) vel.x * 100, // X speed cm/s (+ve North)
vel.y * 100, // Y speed cm/s (+ve East) 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); ahrs.yaw_sensor);
} }