Plane: fix global-pos-int velocity direction to NED
This commit is contained in:
parent
f47e65822f
commit
dd6755f486
@ -186,7 +186,7 @@ void Plane::send_location(mavlink_channel_t chan)
|
||||
relative_altitude * 1.0e3f, // millimeters above ground
|
||||
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