Browse Source

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

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
dd6755f486
  1. 2
      ArduPlane/GCS_Mavlink.cpp

2
ArduPlane/GCS_Mavlink.cpp

@ -186,7 +186,7 @@ void Plane::send_location(mavlink_channel_t chan)
relative_altitude * 1.0e3f, // millimeters above ground relative_altitude * 1.0e3f, // millimeters above ground
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);
} }

Loading…
Cancel
Save