AP_GPS: set have_vertical_velocity if MAVLink GPS report it

This commit is contained in:
chobits 2018-03-01 15:00:15 +08:00 committed by WickedShell
parent b773334008
commit ea1a6b2044
1 changed files with 3 additions and 1 deletions

View File

@ -80,8 +80,10 @@ void AP_GPS_MAV::handle_msg(const mavlink_message_t *msg)
if (have_vel_h) {
Vector3f vel(packet.vn, packet.ve, 0);
if (have_vel_v)
if (have_vel_v) {
vel.z = packet.vd;
state.have_vertical_velocity = true;
}
state.velocity = vel;
state.ground_course = wrap_360(degrees(atan2f(vel.y, vel.x)));