diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index c6eb4a9d3101ebb2e198177c961c736e517a24a6..19a3a40cac3f80abeaa64c86806106b845303058 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -162,16 +162,11 @@ bool Mavlink::_boot_complete = false;
 
 Mavlink::Mavlink() :
 	ModuleParams(nullptr),
-	_device_name("/dev/ttyS1"),
 	_task_should_exit(false),
-	next(nullptr),
 	_instance_id(0),
 	_transmitting_enabled(true),
 	_transmitting_enabled_commanded(false),
 	_mavlink_log_pub(nullptr),
-	_task_running(false),
-	_mavlink_buffer{},
-	_mavlink_status{},
 	_hil_enabled(false),
 	_generate_rc(false),
 	_is_usb_uart(false),
@@ -221,10 +216,6 @@ Mavlink::Mavlink() :
 	_protocol(SERIAL),
 	_network_port(14556),
 	_remote_port(DEFAULT_REMOTE_PORT_UDP),
-	_message_buffer {},
-	_message_buffer_mutex {},
-	_send_mutex {},
-
 	/* performance counters */
 	_loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
 	_loop_interval_perf(perf_alloc(PC_INTERVAL, "mavlink_int"))
@@ -316,7 +307,8 @@ Mavlink::~Mavlink()
 	}
 }
 
-void Mavlink::mavlink_update_parameters()
+void
+Mavlink::mavlink_update_parameters()
 {
 	updateParams();
 
@@ -352,7 +344,7 @@ Mavlink::set_proto_version(unsigned version)
 int
 Mavlink::instance_count()
 {
-	unsigned inst_index = 0;
+	size_t inst_index = 0;
 	Mavlink *inst;
 
 	LL_FOREACH(::_mavlink_instances, inst) {
@@ -549,7 +541,8 @@ Mavlink::get_uart_fd(unsigned index)
 	return -1;
 }
 
-int Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_control)
+int
+Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_control)
 {
 #ifndef B460800
 #define B460800 460800
@@ -1219,7 +1212,8 @@ Mavlink::send_statustext_emergency(const char *string)
 	mavlink_log_emergency(&_mavlink_log_pub, "%s", string);
 }
 
-void Mavlink::send_autopilot_capabilites()
+void
+Mavlink::send_autopilot_capabilites()
 {
 	struct vehicle_status_s status;
 
@@ -1282,7 +1276,8 @@ void Mavlink::send_autopilot_capabilites()
 	}
 }
 
-void Mavlink::send_protocol_version()
+void
+Mavlink::send_protocol_version()
 {
 	mavlink_protocol_version_t msg = {};
 
@@ -1303,7 +1298,8 @@ void Mavlink::send_protocol_version()
 	set_proto_version(curr_proto_ver);
 }
 
-MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic, int instance, bool disable_sharing)
+MavlinkOrbSubscription *
+Mavlink::add_orb_subscription(const orb_id_t topic, int instance, bool disable_sharing)
 {
 	if (!disable_sharing) {
 		/* check if already subscribed to this topic */
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 294b9fe364c318f555a6dd3c1ed64727b3d70d1e..4a43cbf8b494ec71c3aa640291b151d073da67f1 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -112,7 +112,7 @@ public:
 	/**
 	* Start the mavlink task.
 	 *
-	 * @return		OK on success.
+	 * @return OK on success.
 	 */
 	static int		start(int argc, char *argv[]);
 
@@ -166,18 +166,18 @@ public:
 	/**
 	 * Get the MAVLink system id.
 	 *
-	 * @return		The system ID of this vehicle
+	 * @return The system ID of this vehicle
 	 */
 	int			get_system_id() const { return mavlink_system.sysid; }
 
 	/**
 	 * Get the MAVLink component id.
 	 *
-	 * @return		The component ID of this vehicle
+	 * @return The component ID of this vehicle
 	 */
 	int			get_component_id() const { return mavlink_system.compid; }
 
-	const char *_device_name;
+	const char *_device_name{DEFAULT_DEVICE_NAME};
 
 	enum MAVLINK_MODE {
 		MAVLINK_MODE_NORMAL = 0,
@@ -454,9 +454,9 @@ public:
 	int 			get_socket_fd() { return _socket_fd; };
 
 #ifdef __PX4_POSIX
-	const in_addr query_netmask_addr(const int socket_fd, const ifreq &ifreq);
+	const in_addr		query_netmask_addr(const int socket_fd, const ifreq &ifreq);
 
-	const in_addr compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask_addr);
+	const in_addr		compute_broadcast_addr(const in_addr &host_addr, const in_addr &netmask_addr);
 #endif
 
 #if defined(CONFIG_NET) || defined(__PX4_POSIX)
@@ -524,7 +524,7 @@ public:
 	struct ping_statistics_s &get_ping_statistics() { return _ping_stats; }
 
 protected:
-	Mavlink			*next;
+	Mavlink			*next{nullptr};
 
 private:
 	int			_instance_id;
@@ -535,14 +535,15 @@ private:
 	orb_advert_t		_mavlink_log_pub{nullptr};
 	orb_advert_t		_telem_status_pub{nullptr};
 
-	bool			_task_running;
+	bool			_task_running{false};
 	static bool		_boot_complete;
-	static constexpr int MAVLINK_MAX_INSTANCES = 4;
-	static constexpr int MAVLINK_MIN_INTERVAL = 1500;
-	static constexpr int MAVLINK_MAX_INTERVAL = 10000;
-	static constexpr float MAVLINK_MIN_MULTIPLIER = 0.0005f;
-	mavlink_message_t _mavlink_buffer;
-	mavlink_status_t _mavlink_status;
+	static constexpr int	MAVLINK_MAX_INSTANCES{4};
+	static constexpr int	MAVLINK_MIN_INTERVAL{1500};
+	static constexpr int	MAVLINK_MAX_INTERVAL{10000};
+	static constexpr float	MAVLINK_MIN_MULTIPLIER{0.0005f};
+
+	mavlink_message_t	_mavlink_buffer {};
+	mavlink_status_t	_mavlink_status {};
 
 	/* states */
 	bool			_hil_enabled;		/**< Hardware In the Loop mode */
@@ -564,7 +565,7 @@ private:
 
 	mavlink_channel_t	_channel;
 
-	ringbuffer::RingBuffer		_logbuffer;
+	ringbuffer::RingBuffer	_logbuffer;
 
 	pthread_t		_receive_thread;
 
@@ -590,9 +591,9 @@ private:
 
 	bool			mavlink_link_termination_allowed;
 
-	char 			*_subscribe_to_stream;
+	char			*_subscribe_to_stream;
 	float			_subscribe_to_stream_rate;  ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default)
-	bool 			_udp_initialised;
+	bool			_udp_initialised;
 
 	enum FLOW_CONTROL_MODE	_flow_control_mode;
 	uint64_t		_last_write_success_time;
@@ -607,23 +608,23 @@ private:
 	uint64_t		_bytes_timestamp;
 
 #if defined(CONFIG_NET) || defined(__PX4_POSIX)
-	struct sockaddr_in _myaddr;
-	struct sockaddr_in _src_addr;
-	struct sockaddr_in _bcast_addr;
-	bool _src_addr_initialized;
-	bool _broadcast_address_found;
-	bool _broadcast_address_not_found_warned;
-	bool _broadcast_failed_warned;
-	uint8_t _network_buf[MAVLINK_MAX_PACKET_LEN];
-	unsigned _network_buf_len;
+	struct			sockaddr_in _myaddr;
+	struct			sockaddr_in _src_addr;
+	struct			sockaddr_in _bcast_addr;
+	bool			_src_addr_initialized;
+	bool			_broadcast_address_found;
+	bool			_broadcast_address_not_found_warned;
+	bool			_broadcast_failed_warned;
+	uint8_t			_network_buf[MAVLINK_MAX_PACKET_LEN];
+	unsigned		_network_buf_len;
 #endif
 
-	const char *_interface_name;
+	const char 		*_interface_name;
 
-	int _socket_fd;
-	Protocol	_protocol;
-	unsigned short _network_port;
-	unsigned short _remote_port;
+	int			_socket_fd;
+	Protocol		_protocol;
+	unsigned short		_network_port;
+	unsigned short		_remote_port;
 
 	radio_status_s		_rstatus{};
 	telemetry_status_s	_tstatus{};
@@ -637,10 +638,10 @@ private:
 		char *data;
 	};
 
-	mavlink_message_buffer	_message_buffer;
+	mavlink_message_buffer	_message_buffer {};
 
-	pthread_mutex_t		_message_buffer_mutex;
-	pthread_mutex_t		_send_mutex;
+	pthread_mutex_t		_message_buffer_mutex {};
+	pthread_mutex_t		_send_mutex {};
 
 	DEFINE_PARAMETERS(
 		(ParamInt<px4::params::MAV_SYS_ID>) _param_system_id,
@@ -721,7 +722,7 @@ private:
 	 */
 	int		task_main(int argc, char *argv[]);
 
-	/* do not allow copying this class */
-	Mavlink(const Mavlink &);
-	Mavlink operator=(const Mavlink &);
+	// Disallow copy construction and move assignment.
+	Mavlink(const Mavlink &) = delete;
+	Mavlink operator=(const Mavlink &) = delete;
 };