diff --git a/.vscode/settings.json b/.vscode/settings.json
index 301582c728fb174400df740c940f7813796cca70..1e4a5cb51a682ae308bb4bc66aa04bc5dded9a33 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -98,5 +98,8 @@
     "editor.defaultFormatter": "chiehyu.vscode-astyle",
     "[xml]": {
         "editor.defaultFormatter": "redhat.vscode-xml"
-    }
+    },
+    "cSpell.words": [
+        "Mavlink"
+    ]
 }
\ No newline at end of file
diff --git a/Modules/Mavlink/mavlinkcommandadapter.h b/Modules/Mavlink/mavlinkcommandadapter.h
index 3de65f87cdf997b0f2b4b9124e267ced05b18f0a..9a7b269e16125797758e972e7fc9aebb43ba2eb0 100644
--- a/Modules/Mavlink/mavlinkcommandadapter.h
+++ b/Modules/Mavlink/mavlinkcommandadapter.h
@@ -1,25 +1,26 @@
 #ifndef MAVLINKCOMMANDADAPTER_H
 #define MAVLINKCOMMANDADAPTER_H
 
+#include <QMap>
 #include <QObject>
 #include <QSerialPort>
-#include <QMap>
 
-#include "mavlinkversionheader.h"
 #include "Core/Message/modulemessage.h"
-#include "mavlinkwriter.h"
 #include "Core/modulesmanager.h"
+#include "mavlinkversionheader.h"
+#include "mavlinkwriter.h"
 
 class MavlinkModule;
 
 /*
- * This class translate commands received from the UI in mavlink messages that can be sent.
+ * This class translate commands received from the UI in mavlink messages that
+ * can be sent.
  */
-class MavlinkCommandAdapter : public QObject {
+class MavlinkCommandAdapter : public QObject
+{
     Q_OBJECT
 
-  public:
-
+public:
     MavlinkCommandAdapter();
 
     void send(mavlink_message_t msg);
@@ -30,12 +31,11 @@ class MavlinkCommandAdapter : public QObject {
     static const int MAV_CMP = 96;
     static const int MAV_SYS = 171;
 
-  private:
+private:
     QSerialPort* serial = nullptr;
 
     MavlinkWriter mavlinkWriter;
     QMap<QString, int> msgNameIdMap;
-
 };
 
-#endif // MAVLINKCOMMANDADAPTER_H
+#endif  // MAVLINKCOMMANDADAPTER_H
diff --git a/Modules/Mavlink/mavlinkmodule.cpp b/Modules/Mavlink/mavlinkmodule.cpp
index 82746d17816a3cda92abbd0776451ed976039afd..9f229c79535e1c34f6a5f61952113629df0f4a21 100644
--- a/Modules/Mavlink/mavlinkmodule.cpp
+++ b/Modules/Mavlink/mavlinkmodule.cpp
@@ -1,100 +1,114 @@
 #include "mavlinkmodule.h"
-#include "ui_mavlinkmodule.h"
-#include "Components/ContextMenuSeparator/contextmenuseparator.h"
+
 #include <QDebug>
 #include <QSerialPortInfo>
+
+#include "Components/ContextMenuSeparator/contextmenuseparator.h"
 #include "Core/modulemessagesbroker.h"
 #include "Modules/skywardhubstrings.h"
+#include "ui_mavlinkmodule.h"
 
-MavlinkModule::MavlinkModule(QWidget* parent) : DefaultModule(parent), ui(new Ui::MavlinkModule), mavlinkReader(this), serialPort(this) {
+MavlinkModule::MavlinkModule(QWidget* parent)
+    : DefaultModule(parent), ui(new Ui::MavlinkModule), mavlinkReader(this),
+      serialPort(this)
+{
     ui->setupUi(this);
     defaultContextMenuSetup();
 
     initializeSerialPortView();
-    //    buildCentralGraphView();
-    connectUiSlots();
+
+    ui->startStopButtonLayout->insertWidget(0, &startSerialStreamToggleButton);
+    connect(&startSerialStreamToggleButton, &ToggleButton::toggled, this,
+            &MavlinkModule::onStartStreamToggled);
+    connect(ui->openLogFolderButton, &QPushButton::clicked, this,
+            &MavlinkModule::onOpenLogFolderClick);
+
     qRegisterMetaType<ModuleMessage>();
-    connect(&mavlinkReader, &MavlinkReader::msgReceived, this, &MavlinkModule::onMsgReceived);
-    connect(&linkQualityTimer, &QTimer::timeout, this, &MavlinkModule::onLinkQualityTimerTick);
+    connect(&mavlinkReader, &MavlinkReader::msgReceived, this,
+            &MavlinkModule::onMsgReceived);
+    connect(&linkQualityTimer, &QTimer::timeout, this,
+            &MavlinkModule::onLinkQualityTimerTick);
 
     mavlinkCommandAdapter.setSerialPort(&serialPort);
 
-    getCore()->getModuleMessagesBroker()->subscribe({SkywardHubStrings::commandsTopic + "/*"}, this, [this](const ModuleMessage & msg) {
-        onCommandReceived(msg);
-    });
+    getCore()->getModuleMessagesBroker()->subscribe(
+        {SkywardHubStrings::commandsTopic + "/*"}, this,
+        [this](const ModuleMessage& msg) { onCommandReceived(msg); });
 }
 
-MavlinkModule::~MavlinkModule() {
+MavlinkModule::~MavlinkModule()
+{
     mavlinkReader.stopReading();
     delete ui;
     onStopClicked();
 }
 
-QWidget* MavlinkModule::toWidget() {
-    return this;
-}
+QWidget* MavlinkModule::toWidget() { return this; }
 
-XmlObject MavlinkModule::toXmlObject() {
+XmlObject MavlinkModule::toXmlObject()
+{
     XmlObject obj(getName(ModuleId::MAVLINK));
-    obj.addAttribute("BaudRateIndex", QString::number(ui->comboBox_baudRate->currentIndex()));
+    obj.addAttribute("BaudRateIndex",
+                     QString::number(ui->comboBoxBaudRate->currentIndex()));
     return obj;
 }
 
-void MavlinkModule::fromXmlObject(const XmlObject& xmlObject) {
-    if(xmlObject.getObjectName() == getName(ModuleId::MAVLINK)) {
+void MavlinkModule::fromXmlObject(const XmlObject& xmlObject)
+{
+    if (xmlObject.getObjectName() == getName(ModuleId::MAVLINK))
+    {
         bool ok;
         int index = xmlObject.getAttribute("BaudRateIndex").toInt(&ok);
-        if(ok) {
-            ui->comboBox_baudRate->setCurrentIndex(index);
+        if (ok)
+        {
+            ui->comboBoxBaudRate->setCurrentIndex(index);
         }
     }
 }
 
-void MavlinkModule::closePort() {
-    if(serialPort.isOpen()) {
+void MavlinkModule::closePort()
+{
+    if (serialPort.isOpen())
+    {
         serialPort.close();
     }
 }
 
+void MavlinkModule::initializeSerialPortView()
+{
+    // Fill the baud rate combo box
+    ui->comboBoxBaudRate->addItem("115200", QSerialPort::Baud115200);
+    ui->comboBoxBaudRate->addItem("19200", QSerialPort::Baud19200);
+    ui->comboBoxBaudRate->addItem("9600", QSerialPort::Baud9600);
 
-void MavlinkModule::initializeSerialPortView() {
-    //fill the baud rate combo box
-    QString baudPrefix = "BaudRate: ";
-    ui->comboBox_baudRate->addItem(baudPrefix + "115200", QSerialPort::Baud115200);
-    // ui->comboBox_baudRate->addItem(baudPrefix + "57600", QSerialPort::Baud57600);
-    // ui->comboBox_baudRate->addItem(baudPrefix + "38400", QSerialPort::Baud38400);
-    ui->comboBox_baudRate->addItem(baudPrefix + "19200", QSerialPort::Baud19200);
-    ui->comboBox_baudRate->addItem(baudPrefix + "9600", QSerialPort::Baud9600);
-    // ui->comboBox_baudRate->addItem(baudPrefix + "4800", QSerialPort::Baud4800);
-    // ui->comboBox_baudRate->addItem(baudPrefix + "2400", QSerialPort::Baud2400);
-    // ui->comboBox_baudRate->addItem(baudPrefix + "1200", QSerialPort::Baud1200);
-
-
-    bool first = true;
-    //Check available port
+    // Check available port
     const auto serialPortInfos = QSerialPortInfo::availablePorts();
-    for (const QSerialPortInfo& serialPortInfo : serialPortInfos) {
-        //        QString serialNumber = serialPortInfo.serialNumber();
-        //        QVariant data = (!serialNumber.isEmpty() ? serialNumber : "N/A");
-        QVariant data(serialPortInfo.portName());
-        ui->comboBox_serialPort->addItem(serialPortInfo.portName(), data);
-
-        if(first) {
-            ui->lineEdit_serialPort->setText(serialPortInfo.portName());
-            first = false;
-        }
+
+    for (auto serialPortInfo = serialPortInfos.rbegin();
+         serialPortInfo != serialPortInfos.rend(); serialPortInfo++)
+    {
+        QVariant portName(serialPortInfo->portName());
+        ui->comboBoxSerialPort->addItem(serialPortInfo->portName(), portName);
     }
-}
 
+    ui->comboBoxSerialPort->setCurrentIndex(0);
+}
 
-bool MavlinkModule::startReadingOnSerialPort() {
-    QString portName = ui->lineEdit_serialPort->text().trimmed();
-    bool ok;
-    int baudRate = ui->comboBox_baudRate->currentData().toInt(&ok);
+bool MavlinkModule::startReadingOnSerialPort()
+{
+    QString portName = ui->comboBoxSerialPort->currentData().toString();
+    bool baudrateOk;
+    int baudRate = ui->comboBoxBaudRate->currentData().toInt(&baudrateOk);
 
-    if(!ok || portName == "" || serialPort.isOpen())
+    // Check if the parameters are ok
+    if (!baudrateOk)
         return false;
 
+    // The serial port should not be already open
+    if (serialPort.isOpen())
+        return true;
+
+    // Open the serial port
     QSerialPortInfo port(portName);
     serialPort.setPort(port);
     serialPort.setBaudRate(baudRate);
@@ -104,102 +118,103 @@ bool MavlinkModule::startReadingOnSerialPort() {
     return serialPort.open(QIODevice::ReadWrite);
 }
 
-void MavlinkModule::onStartClicked() {
-    if(startReadingOnSerialPort()) {
-        onLinkQualityIndicatorClicked(ui->linkQuality_groupBox->isChecked());
+void MavlinkModule::onStartClicked()
+{
+    if (startReadingOnSerialPort())
+    {
+        linkQualityTimer.start(linkQualityPeriod);
+
         mavlinkReader.setSerialPort(&serialPort);
+        mavlinkCommandAdapter.setSerialPort(&serialPort);
 
-        if(ui->logEnabled_checkBox->isChecked()) {
+        // TODO: Allow the checkbox to start and stop the logging
+        if (ui->logEnabledCheckBox->isChecked())
             mavlinkReader.openLogFile();
-        }
 
         mavlinkReader.startReading();
-        mavlinkCommandAdapter.setSerialPort(&serialPort);
-    } else {
-        error(tr("Mavlink"), "Unable to open selected serial port.");
+    }
+    else
+    {
+        error("Mavlink", "Unable to open selected serial port.");
         startSerialStreamToggleButton.setState(false);
     }
 }
 
-void MavlinkModule::onStopClicked() {
+void MavlinkModule::onStopClicked()
+{
+    linkQualityTimer.stop();
     mavlinkReader.stopReading();
     closePort();
 }
 
-void MavlinkModule::onMsgReceived(const ModuleMessage& msg) {
+void MavlinkModule::onMsgReceived(const ModuleMessage& msg)
+{
     msgArrived++;
     getCore()->getModuleMessagesBroker()->publish(msg);
 }
 
-void MavlinkModule::onStartStreamToggled(bool state) {
-    if(state) {
+void MavlinkModule::onStartStreamToggled(bool state)
+{
+    if (state)
         onStartClicked();
-    } else {
+    else
         onStopClicked();
-    }
-}
-
-void MavlinkModule::onLinkQualityIndicatorClicked(bool checked) {
-    if(checked && !linkQualityTimer.isActive()) {
-        linkQualityTimer.start(linkQualityPeriod);
-    } else if(!checked && linkQualityTimer.isActive()) {
-        linkQualityTimer.stop();
-    }
 }
 
-void MavlinkModule::onLinkQualityTimerTick() {
+void MavlinkModule::onLinkQualityTimerTick()
+{
     float ratio = (float)msgArrived / linkQualityPeriod * 1000.0;
     updateLinkSignalIndicator(msgArrived, ratio);
     msgArrived = 0;
 }
 
-void MavlinkModule::updateLinkSignalIndicator(int msgArrived, float ratio) {
-    ui->msgPerSecond_label->setText(QString::number(ratio));
+void MavlinkModule::updateLinkSignalIndicator(int msgArrived, float ratio)
+{
+    ui->rateText->setText(QString::number(ratio));
     ModuleMessage linkQuality(SkywardHubStrings::mavlink_quality_link_topic);
     linkQuality.setField("ReceivedMsgNumber", {QString::number(msgArrived)});
     linkQuality.setField("ReceivedRatio", {QString::number(ratio)});
     getCore()->getModuleMessagesBroker()->publish(linkQuality);
 }
 
-void MavlinkModule::onOpenLogFolderClick() {
+void MavlinkModule::onOpenLogFolderClick()
+{
     QDir dir(SkywardHubStrings::defaultLogsFolder);
-    if (dir.exists()) {
-        QDesktopServices::openUrl( QUrl::fromLocalFile(SkywardHubStrings::defaultLogsFolder) );
-    } else {
-        warning(tr("Mavlink"), tr("The log folder does not exist yet. It will be created when opening the serial port."));
+    if (dir.exists())
+    {
+        QDesktopServices::openUrl(
+            QUrl::fromLocalFile(SkywardHubStrings::defaultLogsFolder));
+    }
+    else
+    {
+        warning(tr("Mavlink"), tr("The log folder does not exist yet. It will "
+                                  "be created when opening the serial port."));
     }
 }
 
-void MavlinkModule::connectUiSlots() {
-    ui->startStop_button_layout->insertWidget(0, &startSerialStreamToggleButton);
-    connect(&startSerialStreamToggleButton, &ToggleButton::toggled, this, &MavlinkModule::onStartStreamToggled);
-
-    //    connect(ui->button_start,&QPushButton::clicked,this, &MavlinkModule::onStartClicked);
-    //    connect(ui->button_stop,&QPushButton::clicked,this, &MavlinkModule::onStopClicked);
-    //    connect(ui->spinBox_maxPackets,SIGNAL(valueChanged(int)),this,SLOT(onMaxPackedValueChanged(int)));
-    connect(ui->openLogFolder_button, &QPushButton::clicked, this, &MavlinkModule::onOpenLogFolderClick);
-    connect(ui->comboBox_serialPort, SIGNAL(currentIndexChanged(int)), this, SLOT(onSerialPortIndexChanged(int)));
-    connect(ui->linkQuality_groupBox, &QGroupBox::clicked, this, &MavlinkModule::onLinkQualityIndicatorClicked);
-}
-
-void MavlinkModule::onSerialPortIndexChanged(int index) {
-    QVariant data = ui->comboBox_serialPort->itemData(index);
-    ui->lineEdit_serialPort->setText(data.toString());
-}
-
-void MavlinkModule::onCommandReceived(const ModuleMessage& msg) {
+void MavlinkModule::onCommandReceived(const ModuleMessage& msg)
+{
     mavlink_message_t encoded_mvl_msg;
-    if(!mavlinkCommandAdapter.encodeCommand(msg, encoded_mvl_msg)) {
-        error(tr("Mavlink"), tr("Cannot encode command into a valid mavlink message."));
-    } else if(!serialPort.isOpen()) {
+    if (!mavlinkCommandAdapter.encodeCommand(msg, encoded_mvl_msg))
+    {
+        error(tr("Mavlink"),
+              tr("Cannot encode command into a valid mavlink message."));
+    }
+    else if (!serialPort.isOpen())
+    {
         error(tr("Mavlink"), "Cannot send message: serial port is closed.");
-    } else {
+    }
+    else
+    {
         mavlinkCommandAdapter.send(encoded_mvl_msg);
 
         ModuleMessage confirmationMsg(SkywardHubStrings::logCommandsTopic);
-        confirmationMsg.setField("name", msg.getTopic().toString().replace(SkywardHubStrings::commandsTopic + "/", ""));
-        confirmationMsg.setField("message_id", (uint64_t) encoded_mvl_msg.msgid);
-        confirmationMsg.setField("sequence_number", (uint64_t) encoded_mvl_msg.seq);
+        confirmationMsg.setField(
+            "name", msg.getTopic().toString().replace(
+                        SkywardHubStrings::commandsTopic + "/", ""));
+        confirmationMsg.setField("message_id", (uint64_t)encoded_mvl_msg.msgid);
+        confirmationMsg.setField("sequence_number",
+                                 (uint64_t)encoded_mvl_msg.seq);
         getCore()->getModuleMessagesBroker()->publish(confirmationMsg);
     }
 }
diff --git a/Modules/Mavlink/mavlinkmodule.h b/Modules/Mavlink/mavlinkmodule.h
index a37926e0675e6a94807cbedd5048d96df8182d75..ed1931e66593aef1bd729ed6c1b9a4d6bdfae1ab 100644
--- a/Modules/Mavlink/mavlinkmodule.h
+++ b/Modules/Mavlink/mavlinkmodule.h
@@ -16,7 +16,7 @@ Q_DECLARE_METATYPE(ModuleMessage);
 
 namespace Ui
 {
-    class MavlinkModule;
+class MavlinkModule;
 }
 
 class MavlinkModule : public DefaultModule
@@ -37,11 +37,9 @@ public slots:
     void onStartClicked();
     void onStopClicked();
     void onMsgReceived(const ModuleMessage &msg);
-    void onLinkQualityIndicatorClicked(bool checked);
     void onLinkQualityTimerTick();
 
 protected:
-    void connectUiSlots();
     void initializeSerialPortView();
 
     mavlink_message_t parseMavlinkMsg(char *buffer, int readCount);
@@ -53,7 +51,6 @@ protected:
     void onOpenLogFolderClick();
 
 private slots:
-    void onSerialPortIndexChanged(int index);
     bool startReadingOnSerialPort();
     void onStartStreamToggled(bool state);
 
@@ -61,15 +58,14 @@ private:
     Ui::MavlinkModule *ui;
 
     ToggleButton startSerialStreamToggleButton;
-    QString dateFormat = "HH:mm:ss\n(zzz)";
     MavlinkReader mavlinkReader;
     MavlinkCommandAdapter mavlinkCommandAdapter;
     QSerialPort serialPort;
 
     QTimer linkQualityTimer;
-    int linkQualityPeriod = 2000; // [ms]
-    int msgArrived = 0;
+    int linkQualityPeriod = 2000;  // [ms]
+    int msgArrived        = 0;
     bool portOpen;
 };
 
-#endif // MAVLINKMODULE_H
+#endif  // MAVLINKMODULE_H
diff --git a/Modules/Mavlink/mavlinkmodule.ui b/Modules/Mavlink/mavlinkmodule.ui
index acaf86a5abee6f296060a57dc7d0ec56651730bf..c2aeaa9efb8ecde91c19e53bc0eebd4eb404712f 100644
--- a/Modules/Mavlink/mavlinkmodule.ui
+++ b/Modules/Mavlink/mavlinkmodule.ui
@@ -6,208 +6,123 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>545</width>
-    <height>256</height>
+    <width>596</width>
+    <height>91</height>
    </rect>
   </property>
+  <property name="sizePolicy">
+   <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+    <horstretch>0</horstretch>
+    <verstretch>0</verstretch>
+   </sizepolicy>
+  </property>
   <property name="windowTitle">
    <string>Form</string>
   </property>
-  <layout class="QVBoxLayout" name="verticalLayout" stretch="0,1,1">
-   <item>
-    <widget class="QLabel" name="module_title">
-     <property name="text">
-      <string>Mavlink</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-    </widget>
-   </item>
-   <item>
-    <widget class="QGroupBox" name="linkQuality_groupBox">
-     <property name="title">
-      <string>Link quality</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-     <property name="flat">
-      <bool>true</bool>
-     </property>
-     <property name="checkable">
-      <bool>true</bool>
-     </property>
-     <layout class="QGridLayout" name="gridLayout_2">
-      <item row="1" column="3">
-       <widget class="QLabel" name="label_7">
-        <property name="text">
-         <string>Msg Received/s</string>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="1">
-       <widget class="QLabel" name="label_5">
-        <property name="sizePolicy">
-         <sizepolicy hsizetype="Fixed" vsizetype="Preferred">
-          <horstretch>0</horstretch>
-          <verstretch>0</verstretch>
-         </sizepolicy>
-        </property>
-        <property name="text">
-         <string>Maximum Packets/second</string>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="4">
-       <widget class="QLabel" name="msgPerSecond_label">
-        <property name="text">
-         <string>msgpersecond value</string>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="0">
-       <widget class="QSpinBox" name="spinBox_maxPackets">
-        <property name="sizePolicy">
-         <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-          <horstretch>0</horstretch>
-          <verstretch>0</verstretch>
-         </sizepolicy>
-        </property>
-        <property name="minimum">
-         <number>1</number>
-        </property>
-        <property name="maximum">
-         <number>99999</number>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="2">
-       <spacer name="horizontalSpacer">
-        <property name="orientation">
-         <enum>Qt::Horizontal</enum>
-        </property>
-        <property name="sizeHint" stdset="0">
-         <size>
-          <width>40</width>
-          <height>20</height>
-         </size>
-        </property>
-       </spacer>
-      </item>
-     </layout>
-    </widget>
-   </item>
+  <layout class="QVBoxLayout" name="verticalLayout" stretch="0">
    <item>
-    <widget class="QGroupBox" name="groupBox_2">
-     <property name="title">
-      <string>Setup</string>
-     </property>
-     <property name="alignment">
-      <set>Qt::AlignCenter</set>
-     </property>
-     <layout class="QGridLayout" name="gridLayout">
-      <item row="1" column="0">
-       <spacer name="horizontalSpacer_3">
-        <property name="orientation">
-         <enum>Qt::Horizontal</enum>
-        </property>
-        <property name="sizeHint" stdset="0">
-         <size>
-          <width>40</width>
-          <height>20</height>
-         </size>
-        </property>
-       </spacer>
-      </item>
-      <item row="1" column="7">
-       <spacer name="horizontalSpacer_2">
-        <property name="orientation">
-         <enum>Qt::Horizontal</enum>
-        </property>
-        <property name="sizeHint" stdset="0">
-         <size>
-          <width>40</width>
-          <height>20</height>
-         </size>
-        </property>
-       </spacer>
-      </item>
-      <item row="1" column="2">
-       <widget class="QLineEdit" name="lineEdit_serialPort">
-        <property name="sizePolicy">
-         <sizepolicy hsizetype="Fixed" vsizetype="Fixed">
-          <horstretch>0</horstretch>
-          <verstretch>0</verstretch>
-         </sizepolicy>
-        </property>
-       </widget>
-      </item>
-      <item row="0" column="1">
-       <widget class="QLabel" name="label_2">
-        <property name="text">
-         <string>Available Port</string>
-        </property>
-        <property name="alignment">
-         <set>Qt::AlignCenter</set>
-        </property>
-       </widget>
-      </item>
-      <item row="0" column="2">
-       <widget class="QLabel" name="label_4">
-        <property name="text">
-         <string>Selected Port</string>
-        </property>
-        <property name="alignment">
-         <set>Qt::AlignCenter</set>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="5">
-       <layout class="QHBoxLayout" name="startStop_button_layout"/>
-      </item>
-      <item row="0" column="3">
-       <widget class="QLabel" name="label_3">
-        <property name="text">
-         <string>Baud Rate</string>
-        </property>
-       </widget>
-      </item>
-      <item row="0" column="5">
-       <widget class="QLabel" name="label_6">
-        <property name="text">
-         <string>Start/Stop</string>
-        </property>
-        <property name="alignment">
-         <set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="6">
-       <widget class="QPushButton" name="openLogFolder_button">
-        <property name="text">
-         <string>Log Folder</string>
-        </property>
-       </widget>
-      </item>
-      <item row="1" column="1">
-       <widget class="QComboBox" name="comboBox_serialPort"/>
-      </item>
-      <item row="1" column="3">
-       <widget class="QComboBox" name="comboBox_baudRate"/>
-      </item>
-      <item row="0" column="6">
-       <widget class="QCheckBox" name="logEnabled_checkBox">
-        <property name="text">
-         <string>Enable Log</string>
-        </property>
-        <property name="checked">
-         <bool>true</bool>
-        </property>
-       </widget>
-      </item>
-     </layout>
-    </widget>
+    <layout class="QGridLayout" name="gridLayout_2">
+     <item row="1" column="0">
+      <widget class="QComboBox" name="comboBoxSerialPort"/>
+     </item>
+     <item row="0" column="3">
+      <widget class="QCheckBox" name="logEnabledCheckBox">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Minimum" vsizetype="Minimum">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Enable Log</string>
+       </property>
+       <property name="checked">
+        <bool>true</bool>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="3">
+      <widget class="QPushButton" name="openLogFolderButton">
+       <property name="text">
+        <string>Log Folder</string>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="2">
+      <widget class="QLabel" name="startStopLabel">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Start/Stop</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignBottom|Qt::AlignHCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="1">
+      <widget class="QComboBox" name="comboBoxBaudRate"/>
+     </item>
+     <item row="0" column="0">
+      <widget class="QLabel" name="availablePortsLabel">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Available ports</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignBottom|Qt::AlignHCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="0" column="1">
+      <widget class="QLabel" name="baudrateLabel">
+       <property name="sizePolicy">
+        <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
+         <horstretch>0</horstretch>
+         <verstretch>0</verstretch>
+        </sizepolicy>
+       </property>
+       <property name="text">
+        <string>Baudrate</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignBottom|Qt::AlignHCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="2">
+      <layout class="QHBoxLayout" name="startStopButtonLayout"/>
+     </item>
+     <item row="0" column="4">
+      <widget class="QLabel" name="rateLabel">
+       <property name="text">
+        <string>Rate</string>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+     <item row="1" column="4">
+      <widget class="QLabel" name="rateText">
+       <property name="text">
+        <string/>
+       </property>
+       <property name="alignment">
+        <set>Qt::AlignCenter</set>
+       </property>
+      </widget>
+     </item>
+    </layout>
    </item>
   </layout>
  </widget>
diff --git a/Modules/Mavlink/mavlinkreader.cpp b/Modules/Mavlink/mavlinkreader.cpp
index d1790d5575fee48ca3d96cb2ea920ab1613fab5f..990432f613bfc407c38315969c855b4fc7174c9b 100644
--- a/Modules/Mavlink/mavlinkreader.cpp
+++ b/Modules/Mavlink/mavlinkreader.cpp
@@ -1,109 +1,134 @@
 #include "mavlinkreader.h"
 
-#include <QFile>
-#include <QTextStream>
 #include <QDebug>
 #include <QDir>
+#include <QFile>
+#include <QTextStream>
 
 #include "Modules/skywardhubstrings.h"
 #include "mavlinkcommandadapter.h"
 #include "mavlinkmodule.h"
 
-MavlinkReader::MavlinkReader(MavlinkModule* parent) : module(parent) {
-}
+MavlinkReader::MavlinkReader(MavlinkModule* parent) : module(parent) {}
 
-MavlinkReader::~MavlinkReader() {
-    closeLog();
-}
+MavlinkReader::~MavlinkReader() { closeLog(); }
 
-void MavlinkReader::startReading() {
-    if(serialPort) {
-        QObject::connect(serialPort, &QSerialPort::readyRead, this, &MavlinkReader::onReadyRead);
+void MavlinkReader::startReading()
+{
+    if (serialPort)
+    {
+        QObject::connect(serialPort, &QSerialPort::readyRead, this,
+                         &MavlinkReader::onReadyRead);
     }
 }
 
-void MavlinkReader::stopReading() {
-    if(serialPort) {
-        QObject::disconnect(serialPort, &QSerialPort::readyRead, this, &MavlinkReader::onReadyRead);
+void MavlinkReader::stopReading()
+{
+    if (serialPort)
+    {
+        QObject::disconnect(serialPort, &QSerialPort::readyRead, this,
+                            &MavlinkReader::onReadyRead);
     }
 }
 
-const mavlink_message_info_t& MavlinkReader::getMessageFormat(uint8_t messageId) {
+const mavlink_message_info_t& MavlinkReader::getMessageFormat(uint8_t messageId)
+{
     static mavlink_message_info_t infos[256] = MAVLINK_MESSAGE_INFO;
     return infos[messageId];
 }
 
-void MavlinkReader::onReadyRead() {
-    if(serialPort == nullptr) {
+void MavlinkReader::onReadyRead()
+{
+    if (serialPort == nullptr)
+    {
         qDebug() << "Error: serialPort is nullptr";
         return;
     }
 
     auto bytes = serialPort->readAll();
-    for(auto it = bytes.begin(); it != bytes.end(); ++it) {
-        if(mavlink_parse_char(MAVLINK_COMM_0, *it, &decodedMessage, &mavlinkStatus)) {
+    for (auto it = bytes.begin(); it != bytes.end(); ++it)
+    {
+        if (mavlink_parse_char(MAVLINK_COMM_0, *it, &decodedMessage,
+                               &mavlinkStatus))
+        {
             emit msgReceived(generateModuleMessage(decodedMessage));
         }
     }
 
-    if(logFile.isOpen()) {
+    if (logFile.isOpen())
+    {
         logFile.write(bytes.constData(), sizeof(char) * bytes.length());
     }
 }
 
-void MavlinkReader::setSerialPort(QSerialPort* port) {
-    serialPort = port;
-}
+void MavlinkReader::setSerialPort(QSerialPort* port) { serialPort = port; }
 
-ModuleMessage MavlinkReader::generateModuleMessage(const mavlink_message_t& msg) {
+ModuleMessage MavlinkReader::generateModuleMessage(const mavlink_message_t& msg)
+{
     const mavlink_message_info_t& info = getMessageFormat(msg.msgid);
 
     QMap<QString, MessageField> fields;
-    for (unsigned i = 0; i < info.num_fields; i++) {
+    for (unsigned i = 0; i < info.num_fields; i++)
+    {
         fields[QString(info.fields[i].name)] = decodeField(msg, info.fields[i]);
     }
 
     ModuleMessage output;
-    output.setTopic(SkywardHubStrings::mavlink_received_msg_topic + "/" + info.name);
+    output.setTopic(SkywardHubStrings::mavlink_received_msg_topic + "/" +
+                    info.name);
     output.setFields(std::move(fields));
     return output;
 }
 
-void MavlinkReader::closeLog() {
-    if(logFile.isOpen())
+void MavlinkReader::closeLog()
+{
+    if (logFile.isOpen())
         logFile.close();
 }
 
-void MavlinkReader::openLogFile() {
+void MavlinkReader::openLogFile()
+{
     closeLog();
 
     setLogFilePath();
 
     logFile.setFileName(logFilePath);
-    if (logFile.open(QIODevice::WriteOnly)) {
-        if(module != nullptr) {
-            module->info(tr("Mavlink"), tr("Opened file ") + logFilePath + tr(" for logging."));
+    if (logFile.open(QIODevice::WriteOnly))
+    {
+        if (module != nullptr)
+        {
+            module->info(tr("Mavlink"), tr("Opened file ") + logFilePath +
+                                            tr(" for logging."));
         }
         QTextStream out(&logFile);
-        out << "Log started " << QDateTime::currentDateTime().toString() << "\n";
-    } else {
-        if(module != nullptr) {
-            module->error(tr("Mavlink"), tr("Error, cannot open file ") + logFilePath);
+        out << "Log started " << QDateTime::currentDateTime().toString()
+            << "\n";
+    }
+    else
+    {
+        if (module != nullptr)
+        {
+            module->error(tr("Mavlink"),
+                          tr("Error, cannot open file ") + logFilePath);
         }
     }
 }
 
-void MavlinkReader::setLogFilePath() {
+void MavlinkReader::setLogFilePath()
+{
     QDir dir(SkywardHubStrings::defaultLogsFolder);
     if (!dir.exists())
         dir.mkpath(".");
 
     QString extension = ".dat";
-    QString currentFile =  QDateTime::currentDateTime().toString("yyyyMMdd_hh.mm.ss");
-    QString proposedFilePath = SkywardHubStrings::defaultLogsFolder + "/" + currentFile;
+    QString currentFile =
+        QDateTime::currentDateTime().toString("yyyyMMdd_hh.mm.ss");
+    QString proposedFilePath =
+        SkywardHubStrings::defaultLogsFolder + "/" + currentFile;
     QString fileNumber = "";
-    int i = 1;
-    while(QFile::exists(proposedFilePath + fileNumber + extension) && i < 200) {
+    int i              = 1;
+    while (QFile::exists(proposedFilePath + fileNumber + extension) && i < 200)
+    {
         i++;
         fileNumber = " (" + QString::number(i) + ")";
     }
@@ -111,25 +136,35 @@ void MavlinkReader::setLogFilePath() {
     logFilePath = proposedFilePath + fileNumber + extension;
 }
 
-MessageField MavlinkReader::decodeField(const mavlink_message_t& msg, const mavlink_field_info_t& field) {
-    if (field.array_length == 0) {
+MessageField MavlinkReader::decodeField(const mavlink_message_t& msg,
+                                        const mavlink_field_info_t& field)
+{
+    if (field.array_length == 0)
+    {
         return decodeArrayElement(msg, field, 0);
-    } else {
-        if (field.type == MAVLINK_TYPE_CHAR) {
+    }
+    else
+    {
+        if (field.type == MAVLINK_TYPE_CHAR)
+        {
             QString str;
 
-            for(unsigned i = 0; i < field.array_length; i++) {
+            for (unsigned i = 0; i < field.array_length; i++)
+            {
                 str.append(_MAV_RETURN_char(&msg, field.wire_offset + i));
 
-                if(_MAV_RETURN_char(&msg, field.wire_offset + i) == '\0')
+                if (_MAV_RETURN_char(&msg, field.wire_offset + i) == '\0')
                     break;
             }
 
             return MessageField(str);
-        } else {
+        }
+        else
+        {
             QList<MessageField> array;
             array.reserve(field.array_length);
-            for (unsigned i = 0; i < field.array_length; i++) {
+            for (unsigned i = 0; i < field.array_length; i++)
+            {
                 array.append(decodeArrayElement(msg, field, i));
             }
             return MessageField(std::move(array));
@@ -137,42 +172,68 @@ MessageField MavlinkReader::decodeField(const mavlink_message_t& msg, const mavl
     }
 }
 
-MessageField MavlinkReader::decodeArrayElement(const mavlink_message_t& msg, const mavlink_field_info_t& field, int idx) {
-    switch (field.type) {
-        case MAVLINK_TYPE_CHAR: {
-            return MessageField(_MAV_RETURN_char(&msg, field.wire_offset + idx * 1));
-        }
-        case MAVLINK_TYPE_UINT8_T: {
-            return MessageField(static_cast<uint64_t>(_MAV_RETURN_uint8_t(&msg, field.wire_offset + idx * 1)));
-        }
-        case MAVLINK_TYPE_INT8_T: {
-            return MessageField(static_cast<int64_t>(_MAV_RETURN_int8_t(&msg, field.wire_offset + idx * 1)));
-        }
-        case MAVLINK_TYPE_UINT16_T: {
-            return MessageField(static_cast<uint64_t>(_MAV_RETURN_uint16_t(&msg, field.wire_offset + idx * 2)));
-        }
-        case MAVLINK_TYPE_INT16_T: {
-            return MessageField(static_cast<int64_t>(_MAV_RETURN_int16_t(&msg, field.wire_offset + idx * 2)));
-        }
-        case MAVLINK_TYPE_UINT32_T: {
-            return MessageField(static_cast<uint64_t>(_MAV_RETURN_uint32_t(&msg, field.wire_offset + idx * 4)));
-        }
-        case MAVLINK_TYPE_INT32_T: {
-            return MessageField(static_cast<int64_t>(_MAV_RETURN_int32_t(&msg, field.wire_offset + idx * 4)));
-        }
-        case MAVLINK_TYPE_UINT64_T: {
-            return MessageField(static_cast<uint64_t>(_MAV_RETURN_uint64_t(&msg, field.wire_offset + idx * 8)));
-        }
-        case MAVLINK_TYPE_INT64_T: {
-            return MessageField(static_cast<int64_t>(_MAV_RETURN_int64_t(&msg, field.wire_offset + idx * 8)));
-        }
-        case MAVLINK_TYPE_FLOAT: {
-            return MessageField(static_cast<double>(_MAV_RETURN_float(&msg, field.wire_offset + idx * 4)));
-        }
-        case MAVLINK_TYPE_DOUBLE: {
-            return MessageField(static_cast<double>(_MAV_RETURN_double(&msg, field.wire_offset + idx * 8)));
-        }
-        default: {
+MessageField MavlinkReader::decodeArrayElement(
+    const mavlink_message_t& msg, const mavlink_field_info_t& field, int idx)
+{
+    switch (field.type)
+    {
+        case MAVLINK_TYPE_CHAR:
+        {
+            return MessageField(
+                _MAV_RETURN_char(&msg, field.wire_offset + idx * 1));
+        }
+        case MAVLINK_TYPE_UINT8_T:
+        {
+            return MessageField(static_cast<uint64_t>(
+                _MAV_RETURN_uint8_t(&msg, field.wire_offset + idx * 1)));
+        }
+        case MAVLINK_TYPE_INT8_T:
+        {
+            return MessageField(static_cast<int64_t>(
+                _MAV_RETURN_int8_t(&msg, field.wire_offset + idx * 1)));
+        }
+        case MAVLINK_TYPE_UINT16_T:
+        {
+            return MessageField(static_cast<uint64_t>(
+                _MAV_RETURN_uint16_t(&msg, field.wire_offset + idx * 2)));
+        }
+        case MAVLINK_TYPE_INT16_T:
+        {
+            return MessageField(static_cast<int64_t>(
+                _MAV_RETURN_int16_t(&msg, field.wire_offset + idx * 2)));
+        }
+        case MAVLINK_TYPE_UINT32_T:
+        {
+            return MessageField(static_cast<uint64_t>(
+                _MAV_RETURN_uint32_t(&msg, field.wire_offset + idx * 4)));
+        }
+        case MAVLINK_TYPE_INT32_T:
+        {
+            return MessageField(static_cast<int64_t>(
+                _MAV_RETURN_int32_t(&msg, field.wire_offset + idx * 4)));
+        }
+        case MAVLINK_TYPE_UINT64_T:
+        {
+            return MessageField(static_cast<uint64_t>(
+                _MAV_RETURN_uint64_t(&msg, field.wire_offset + idx * 8)));
+        }
+        case MAVLINK_TYPE_INT64_T:
+        {
+            return MessageField(static_cast<int64_t>(
+                _MAV_RETURN_int64_t(&msg, field.wire_offset + idx * 8)));
+        }
+        case MAVLINK_TYPE_FLOAT:
+        {
+            return MessageField(static_cast<double>(
+                _MAV_RETURN_float(&msg, field.wire_offset + idx * 4)));
+        }
+        case MAVLINK_TYPE_DOUBLE:
+        {
+            return MessageField(static_cast<double>(
+                _MAV_RETURN_double(&msg, field.wire_offset + idx * 8)));
+        }
+        default:
+        {
             // Unsupported: return EMPTY
             return MessageField();
         }