diff --git a/CMakeLists.txt b/CMakeLists.txt
index 52512357eb592a7e51976e2a2f9067a24957f51d..e58d10080da854d6bf7386f2568758eeb851f20d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -67,7 +67,8 @@ target_include_directories(main-entry-hil-milano PRIVATE ${OBSW_INCLUDE_DIRS})
 target_compile_definitions(main-entry-hil-milano PRIVATE HILSimulation MILANO BUZZER_LOW USE_SERIAL_TRANSCEIVER)
 sbs_target(main-entry-hil-milano stm32f429zi_stm32f4discovery)
 
-add_executable(main-entry-hil-maker-faire src/entrypoints/Main/main-entry.cpp ${MAIN_COMPUTER} ${HIL})
+add_executable(main-entry-hil-maker-faire src/entrypoints/Main/main-entry-maker-faire.cpp ${MAIN_COMPUTER} ${HIL})
+# add_executable(main-entry-hil-maker-faire src/entrypoints/Main/main-entry.cpp ${MAIN_COMPUTER} ${HIL})
 target_include_directories(main-entry-hil-maker-faire PRIVATE ${OBSW_INCLUDE_DIRS})
 target_compile_definitions(main-entry-hil-maker-faire PRIVATE HILSimulation EUROC BUZZER_LOW USE_SERIAL_TRANSCEIVER INTERP DEATHSTACK_V2)
 sbs_target(main-entry-hil-maker-faire stm32f429zi_skyward_death_stack_x_maker_faire)
@@ -114,7 +115,12 @@ add_executable(main-test-cutter src/tests/Main/actuators/test-cutter.cpp)
 sbs_target(main-test-cutter stm32f429zi_skyward_death_stack_v3)
 
 add_executable(main-test-servos src/tests/Main/actuators/test-servos.cpp)
-sbs_target(main-test-servos stm32f429zi_skyward_death_stack_v3)
+sbs_target(main-test-servos stm32f429zi_skyward_death_stack_x_maker_faire)
+
+add_executable(test-airbrakes-st src/tests/Main/actuators/test-airbrakes-st.cpp ${MAIN_COMPUTER} ${HIL})
+target_include_directories(test-airbrakes-st PRIVATE ${OBSW_INCLUDE_DIRS})
+target_compile_definitions(test-airbrakes-st PRIVATE HILSimulation)
+sbs_target(test-airbrakes-st stm32f429zi_skyward_death_stack_x_maker_faire)
 
 add_executable(main-test-bmx160-calibration src/tests/Main/calibration/test-bmx160-calibration.cpp)
 sbs_target(main-test-bmx160-calibration stm32f429zi_skyward_death_stack_v3)
diff --git a/skyward-boardcore b/skyward-boardcore
index e69670394bf3a76b37c4fcebdb617886e6847aaf..35b77ec7ade74002d184ba28314ca29f71c0b8ce 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit e69670394bf3a76b37c4fcebdb617886e6847aaf
+Subproject commit 35b77ec7ade74002d184ba28314ca29f71c0b8ce
diff --git a/src/boards/Main/Actuators/Actuators.cpp b/src/boards/Main/Actuators/Actuators.cpp
index fc2238c87b5b7336fadb7fa33cdf00befb7b8989..a143ba7e9745e4e41518d14b24ee66c96a395cd1 100644
--- a/src/boards/Main/Actuators/Actuators.cpp
+++ b/src/boards/Main/Actuators/Actuators.cpp
@@ -112,10 +112,10 @@ bool Actuators::disableServo(ServosList servoId)
     switch (servoId)
     {
         case AIR_BRAKES_SERVO:
-            servoAirbrakes.enable();
+            servoAirbrakes.disable();
             break;
         case EXPULSION_SERVO:
-            servoAirbrakes.enable();
+            servoAirbrakes.disable();
             break;
         default:
             return false;
diff --git a/src/boards/Main/Buses.h b/src/boards/Main/Buses.h
index 184b5a0837b137be06436005c514dcc7f407a3d8..4d845b69180f07a347813d71b061d82cfa4d50e1 100644
--- a/src/boards/Main/Buses.h
+++ b/src/boards/Main/Buses.h
@@ -69,6 +69,7 @@ private:
     {
         usart2.init();
         usart3.init();
+        uart4.init();
     }
 #endif
 };
diff --git a/src/boards/Main/Configs/ActuatorsConfigs.h b/src/boards/Main/Configs/ActuatorsConfigs.h
index f3c90c58ee1e397f57b57b2c7a0a0ed2eeff6c69..e5b55f3f4cf5486fd01b8c5abad789247a867467 100644
--- a/src/boards/Main/Configs/ActuatorsConfigs.h
+++ b/src/boards/Main/Configs/ActuatorsConfigs.h
@@ -33,22 +33,31 @@ namespace ActuatorsConfigs
 
 // Airbrakes servo
 #ifdef DEATHSTACK_V2
+// calibrated at
+//  constexpr float ABK_SERVO_MIN_PULSE = 1080;  // [us]
+//  constexpr float ABK_SERVO_MAX_PULSE = 1600;  // [us]
+
 static TIM_TypeDef* const ABK_SERVO_TIMER = TIM8;
 constexpr Boardcore::TimerUtils::Channel ABK_SERVO_PWM_CH =
     Boardcore::TimerUtils::Channel::CHANNEL_2;
+
+constexpr float ABK_SERVO_ROTATION  = 53;    // [deg] AirBrakes without end stop
+constexpr float ABK_SERVO_MIN_PULSE = 1080;  // [us]
+constexpr float ABK_SERVO_MAX_PULSE = 1500;  // [us]
 #else
+// TODO: Fix rotation value
 static TIM_TypeDef* const ABK_SERVO_TIMER = TIM10;
 constexpr Boardcore::TimerUtils::Channel ABK_SERVO_PWM_CH =
     Boardcore::TimerUtils::Channel::CHANNEL_1;
-#endif
 
-// TODO: Fix rotation value
 constexpr float ABK_SERVO_ROTATION = 66.4;  // [deg] AirBrakes without end stop
 // constexpr float ABK_SERVO_ROTATION  = 65;  // [deg] AirBrakes with end stop
 constexpr float ABK_SERVO_MIN_PULSE = 1405;  // [deg]
 constexpr float ABK_SERVO_MAX_PULSE =
     ABK_SERVO_MIN_PULSE - 10 * ABK_SERVO_ROTATION;  // [us]
-constexpr float ABK_WIGGLE_TIME = 2 * 1000;         // [ms]
+#endif
+
+constexpr float ABK_WIGGLE_TIME = 2 * 1000;  // [ms]
 
 // Deployment servo
 static TIM_TypeDef* const DPL_SERVO_TIMER = TIM4;
@@ -63,9 +72,16 @@ constexpr float DPL_SERVO_RESET_POS = DPL_SERVO_ROTATION;             // [deg]
 constexpr float DPL_WIGGLE_TIME     = 5 * 1000;                       // [ms]
 
 // Buzzer
+
+#ifdef DEATHSTACK_V2
+TIM_TypeDef* const BUZZER_TIMER = TIM1;
+constexpr Boardcore::TimerUtils::Channel BUZZER_CHANNEL =
+    Boardcore::TimerUtils::Channel::CHANNEL_1;
+#else
 TIM_TypeDef* const BUZZER_TIMER = TIM8;
 constexpr Boardcore::TimerUtils::Channel BUZZER_CHANNEL =
     Boardcore::TimerUtils::Channel::CHANNEL_1;
+#endif
 
 #ifdef BUZZER_LOW
 constexpr float BUZZER_DUTY_CYCLE = 0.01;
diff --git a/src/boards/Main/Radio/Radio.cpp b/src/boards/Main/Radio/Radio.cpp
index 9ca0139e9f45f6a46e00c97d08e08c858f5a91ee..642dfe0b6857c96f143855cb92085d3ca36c5c7a 100644
--- a/src/boards/Main/Radio/Radio.cpp
+++ b/src/boards/Main/Radio/Radio.cpp
@@ -34,6 +34,7 @@
 #include <Main/TMRepository/TMRepository.h>
 #include <common/events/Events.h>
 #include <drivers/interrupt/external_interrupts.h>
+#include <interfaces-impl/hwmapping.h>
 
 #include <functional>
 
diff --git a/src/boards/Main/Sensors/Sensors.cpp b/src/boards/Main/Sensors/Sensors.cpp
index 2908ffab36bd0e00792c489bbb410beb2a45c3dd..b1f1b971e81a921aef4614fc4872bda2b71a6560 100644
--- a/src/boards/Main/Sensors/Sensors.cpp
+++ b/src/boards/Main/Sensors/Sensors.cpp
@@ -28,6 +28,7 @@
 #include <common/events/Events.h>
 #include <drivers/interrupt/external_interrupts.h>
 #include <events/EventBroker.h>
+#include <interfaces-impl/hwmapping.h>
 
 using namespace std;
 using namespace miosix;
diff --git a/src/boards/Main/StateMachines/AirBrakesController/AirBrakesController.cpp b/src/boards/Main/StateMachines/AirBrakesController/AirBrakesController.cpp
index 48ffb2bceeee16369358841f3f178ee08735792e..444762f472672ca340076e78bd99adf4be6c0ab7 100644
--- a/src/boards/Main/StateMachines/AirBrakesController/AirBrakesController.cpp
+++ b/src/boards/Main/StateMachines/AirBrakesController/AirBrakesController.cpp
@@ -248,10 +248,7 @@ void AirBrakesController::wiggleServo()
 {
     for (int i = 0; i < 2; i++)
     {
-        Actuators::getInstance().setServoAngle(AIR_BRAKES_SERVO,
-                                               ABK_SERVO_ROTATION);
-        miosix::Thread::sleep(500);
-        Actuators::getInstance().setServoAngle(AIR_BRAKES_SERVO, 0);
+        Actuators::getInstance().wiggleServo(AIR_BRAKES_SERVO);
         miosix::Thread::sleep(500);
     }
 }
diff --git a/src/hardware_in_the_loop/HIL/HILTransceiver.cpp b/src/hardware_in_the_loop/HIL/HILTransceiver.cpp
index 4077d3595cb52f19087e5e6c11bccd5ecd561315..f5e23848123a92fadb8c29974db5fc6abe64eaa2 100644
--- a/src/hardware_in_the_loop/HIL/HILTransceiver.cpp
+++ b/src/hardware_in_the_loop/HIL/HILTransceiver.cpp
@@ -34,7 +34,7 @@ using namespace Main;
  * @brief Construct a serial connection attached to a control algorithm
  */
 HILTransceiver::HILTransceiver()
-    : hilSerial(Buses::getInstance().usart3), actuatorData(ActuatorData{})
+    : hilSerial(Buses::getInstance().uart4), actuatorData(ActuatorData{})
 {
 }
 
diff --git a/src/hardware_in_the_loop/HIL_actuators/HILServo.h b/src/hardware_in_the_loop/HIL_actuators/HILServo.h
index bb7c5df993b9d2c695920318d28e0907e7105eb4..947bd8ae87e0f30d7b69306ebfc6087dfafd87bd 100644
--- a/src/hardware_in_the_loop/HIL_actuators/HILServo.h
+++ b/src/hardware_in_the_loop/HIL_actuators/HILServo.h
@@ -25,26 +25,17 @@
 #include <actuators/Servo/Servo.h>
 
 #include "HIL.h"
-#include "HILConfig.h"
 
 class HILServo : public Boardcore::Servo
 {
 public:
     explicit HILServo(TIM_TypeDef* const timer,
                       Boardcore::TimerUtils::Channel pwmChannel,
-                      unsigned int minPulse = 1000,
-                      unsigned int maxPulse = 2000, unsigned int frequency = 50)
+                      unsigned int minPulse, unsigned int maxPulse,
+                      unsigned int frequency = 50)
         : Servo(timer, pwmChannel, minPulse, maxPulse, frequency)
     {
     }
 
-    void setPosition(float position, bool limited = true)
-    {
-        Servo::setPosition(position, limited);
-
-        // Send the position to MatLab
-        // HIL::getInstance().send(position);
-    }
-
     void sendToSimulator() { HIL::getInstance().send(getPosition()); }
 };
diff --git a/src/tests/Main/actuators/test-airbrakes-st.cpp b/src/tests/Main/actuators/test-airbrakes-st.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..125499df4e3d6cad3335922bab0794992a521029
--- /dev/null
+++ b/src/tests/Main/actuators/test-airbrakes-st.cpp
@@ -0,0 +1,90 @@
+/* Copyright (c) 2019 Skyward Experimental Rocketry
+ * Authors: Luca Erbetta, Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include <Main/Actuators/Actuators.h>
+#include <Main/Sensors/Sensors.h>
+#include <actuators/Servo/Servo.h>
+#include <miosix.h>
+#include <scheduler/TaskScheduler.h>
+#include <utils/ClockUtils.h>
+
+#include <iostream>
+
+#include "HIL_actuators/HILServo.h"
+
+using namespace Boardcore;
+using namespace miosix;
+
+HILServo airbrakesServo(TIM8, TimerUtils::Channel::CHANNEL_2, 1080, 1600);
+
+// Position to cycle through for the servo 1, 2 and 3
+
+void moveServo()
+{
+    // Main::Actuators::getInstance().setServo(AIR_BRAKES_SERVO, 1);
+    airbrakesServo.setPosition(1);
+    Thread::sleep(1000);
+    // Main::Actuators::getInstance().setServo(AIR_BRAKES_SERVO, 0);
+    airbrakesServo.setPosition(0);
+}
+
+int main()
+{
+    char c[10];
+
+    // Set the clock divider for the analog circuitry (/8)
+    ADC->CCR |= ADC_CCR_ADCPRE_0 | ADC_CCR_ADCPRE_1;
+    InternalADC internalADC = InternalADC(ADC3, 3.3);
+    internalADC.enableChannel(InternalADC::CH5);
+    internalADC.init();
+
+    std::function<ADCData()> get_batVoltage_function =
+        std::bind(&InternalADC::getVoltage, &internalADC, InternalADC::CH5);
+
+    BatteryVoltageSensor batterySensor(get_batVoltage_function, 5.98);
+
+    // Enable the timers
+    // Main::Actuators::getInstance().enableServo(AIR_BRAKES_SERVO);
+    // Main::Actuators::getInstance().setServo(AIR_BRAKES_SERVO, 0);
+    airbrakesServo.enable();
+    airbrakesServo.setPosition(0);
+
+    while (true)
+    {
+        // checking for battery charge. if too low for the actuator (< 10.5 V),
+        // disable the real actuation of the servo
+        internalADC.sample();
+        batterySensor.sample();
+        float vbat = batterySensor.getLastSample().batVoltage -
+                     0.4;  // subtracting 0.4 as offset
+
+        if (vbat < 10.5)
+        {
+            airbrakesServo.disable();
+            printf("Airbrakes can't be attuated, vbat too low\n");
+        }
+
+        scanf("%c\n", c);
+        moveServo();
+        printf("vbat: %f\n", vbat);
+    }
+}