diff --git a/libraries/SITL/SIM_Ship.cpp b/libraries/SITL/SIM_Ship.cpp index 0af352ecea..b45699eab8 100644 --- a/libraries/SITL/SIM_Ship.cpp +++ b/libraries/SITL/SIM_Ship.cpp @@ -185,8 +185,13 @@ void ShipSim::send_report(void) last_heartbeat_ms = now; const mavlink_heartbeat_t heartbeat{ + custom_mode: 0, type : MAV_TYPE_SURFACE_BOAT, - autopilot : MAV_AUTOPILOT_INVALID}; + autopilot : MAV_AUTOPILOT_INVALID, + base_mode: 0, + system_status: 0, + mavlink_version: 0, + }; mavlink_message_t msg; mavlink_msg_heartbeat_encode_status( diff --git a/libraries/SITL/SIM_Vicon.cpp b/libraries/SITL/SIM_Vicon.cpp index df55518ab0..ea86270f69 100644 --- a/libraries/SITL/SIM_Vicon.cpp +++ b/libraries/SITL/SIM_Vicon.cpp @@ -50,8 +50,12 @@ void Vicon::maybe_send_heartbeat() last_heartbeat_ms = now; const mavlink_heartbeat_t heartbeat{ - type : MAV_TYPE_GCS, - autopilot : MAV_AUTOPILOT_INVALID, + custom_mode: 0, + type : MAV_TYPE_GCS, + autopilot : MAV_AUTOPILOT_INVALID, + base_mode: 0, + system_status: 0, + mavlink_version: 0, }; mavlink_msg_heartbeat_encode_status(