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

This commit is contained in:
Randy Mackay 2018-02-08 08:06:08 +09:00
parent 144dd82fe4
commit f47e65822f

View File

@ -123,7 +123,7 @@ void Rover::send_location(mavlink_channel_t chan)
(current_loc.alt - home.alt) * 10, // millimeters above home
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);
}