diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 2fe17e4231ae63f17ea800a356698af0d5cc34d8..5243e7b72ce46e2c6c0f326bd8c67bcc85e35050 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -132,10 +132,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
 	_debug_array_pub(nullptr),
 	_gps_inject_data_pub(nullptr),
 	_command_ack_pub(nullptr),
-	_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
-	_actuator_armed_sub(orb_subscribe(ORB_ID(actuator_armed))),
-	_vehicle_attitude_sub(orb_subscribe(ORB_ID(vehicle_attitude))),
-	_global_ref_timestamp(0),
 	_hil_frames(0),
 	_old_timestamp(0),
 	_hil_local_proj_inited(0),
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index b94c068b6cafaa82de45d4c6dc009fcccf6d96c4..8aadd074c17d283526254f9d2d9e6ca33e523616 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -253,12 +253,13 @@ private:
 
 	static const int _gps_inject_data_queue_size = 6;
 
-	int _actuator_armed_sub;
-	int _control_mode_sub;
+	int _actuator_armed_sub{orb_subscribe(ORB_ID(actuator_armed))};
+	int _control_mode_sub{orb_subscribe(ORB_ID(vehicle_control_mode))};
+	int _vehicle_attitude_sub{orb_subscribe(ORB_ID(vehicle_attitude))};
+
 	int _hil_frames;
-	int _vehicle_attitude_sub;
 
-	uint64_t _global_ref_timestamp;
+	uint64_t _global_ref_timestamp{0};
 	uint64_t _old_timestamp;
 
 	bool _hil_local_proj_inited;