Browse Source

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

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
144dd82fe4
  1. 2
      AntennaTracker/GCS_Mavlink.cpp

2
AntennaTracker/GCS_Mavlink.cpp

@ -120,7 +120,7 @@ void Tracker::send_location(mavlink_channel_t chan) @@ -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…
Cancel
Save