mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 02:17:07 +08:00
mavlink: don't send uninitialized bytes
Valgrind did not approve uninitialized bytes from either home or vehicle global position to be sent.
This commit is contained in:
@@ -1479,8 +1479,8 @@ protected:
|
||||
|
||||
void send(const hrt_abstime t)
|
||||
{
|
||||
struct vehicle_global_position_s pos;
|
||||
struct home_position_s home;
|
||||
struct vehicle_global_position_s pos = {};
|
||||
struct home_position_s home = {};
|
||||
|
||||
bool updated = _pos_sub->update(&_pos_time, &pos);
|
||||
updated |= _home_sub->update(&_home_time, &home);
|
||||
|
||||
Reference in New Issue
Block a user