mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Follow: zreo velocities if not provided
This commit is contained in:
parent
99cf10ce12
commit
e6f488ccc1
@ -349,6 +349,8 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg)
|
||||
_target_velocity_ned.x = packet.vel[0]; // velocity north
|
||||
_target_velocity_ned.y = packet.vel[1]; // velocity east
|
||||
_target_velocity_ned.z = packet.vel[2]; // velocity down
|
||||
} else {
|
||||
_target_velocity_ned.zero();
|
||||
}
|
||||
|
||||
// get a local timestamp with correction for transport jitter
|
||||
|
Loading…
Reference in New Issue
Block a user