AP_GPS: set have_vertical_velocity if MAVLink GPS report it
This commit is contained in:
parent
b773334008
commit
ea1a6b2044
@ -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)));
|
||||
|
Loading…
Reference in New Issue
Block a user