aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/10015_tbs_discovery7
-rw-r--r--ROMFS/px4fmu_common/mixers/pass.aux.mix21
-rw-r--r--Tools/px4params/srcparser.py10
-rw-r--r--Tools/px4params/xmlout.py3
-rw-r--r--makefiles/firmware.mk2
-rw-r--r--msg/actuator_armed.msg1
-rw-r--r--src/drivers/gimbal/gimbal.cpp6
-rw-r--r--src/drivers/px4io/px4io.cpp29
-rw-r--r--src/modules/commander/calibration_routines.cpp14
-rw-r--r--src/modules/commander/commander.cpp15
-rw-r--r--src/modules/commander/esc_calibration.cpp152
-rw-r--r--src/modules/commander/esc_calibration.h47
-rw-r--r--src/modules/commander/module.mk1
13 files changed, 287 insertions, 21 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
index 2c7c0d68e..0dd483764 100644
--- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery
@@ -28,3 +28,10 @@ set MIXER quad_w
set PWM_OUT 1234
set PWM_MIN 1200
+
+set MIXER_AUX pass
+set PWM_AUX_RATE 50
+set PWM_AUX_OUT 1234
+set PWM_AUX_DISARMED 1000
+set PWM_AUX_MIN 1000
+set PWM_AUX_MAX 2000
diff --git a/ROMFS/px4fmu_common/mixers/pass.aux.mix b/ROMFS/px4fmu_common/mixers/pass.aux.mix
new file mode 100644
index 000000000..8e7011f0e
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/pass.aux.mix
@@ -0,0 +1,21 @@
+# Manual pass through mixer for servo outputs 1-4
+
+# AUX1 channel (select RC channel with RC_MAP_AUX1 param)
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 3 5 10000 10000 0 -10000 10000
+
+# AUX2 channel (select RC channel with RC_MAP_AUX2 param)
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 3 6 10000 10000 0 -10000 10000
+
+# AUX3 channel (select RC channel with RC_MAP_AUX3 param)
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 3 7 10000 10000 0 -10000 10000
+
+# FLAPS channel (select RC channel with RC_MAP_FLAPS param)
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 3 4 10000 10000 0 -10000 10000
diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py
index 0d2413a75..048836a4e 100644
--- a/Tools/px4params/srcparser.py
+++ b/Tools/px4params/srcparser.py
@@ -57,10 +57,10 @@ class Parameter(object):
def GetType(self):
return self.type
-
+
def GetDefault(self):
return self.default
-
+
def SetField(self, code, value):
"""
Set named field value
@@ -80,6 +80,10 @@ class Parameter(object):
"""
Return value of the given field code or None if not found.
"""
+ fv = self.fields.get(code)
+ if not fv:
+ # required because python 3 sorted does not accept None
+ return ""
return self.fields.get(code)
class SourceParser(object):
@@ -89,7 +93,7 @@ class SourceParser(object):
re_split_lines = re.compile(r'[\r\n]+')
re_comment_start = re.compile(r'^\/\*\*')
- re_comment_content = re.compile(r'^\*\s*(.*)')
+ re_comment_content = re.compile(r'^\*\s*(.*)')
re_comment_tag = re.compile(r'@([a-zA-Z][a-zA-Z0-9_]*)\s*(.*)')
re_comment_end = re.compile(r'(.*?)\s*\*\/')
re_parameter_definition = re.compile(r'PARAM_DEFINE_([A-Z_][A-Z0-9_]*)\s*\(([A-Z_][A-Z0-9_]*)\s*,\s*([^ ,\)]+)\s*\)\s*;')
diff --git a/Tools/px4params/xmlout.py b/Tools/px4params/xmlout.py
index 07cced478..b072ab79f 100644
--- a/Tools/px4params/xmlout.py
+++ b/Tools/px4params/xmlout.py
@@ -52,5 +52,4 @@ class XMLOutput():
self.xml_document = ET.ElementTree(xml_parameters)
def Save(self, filename):
- with codecs.open(filename, 'w', 'utf-8') as f:
- self.xml_document.write(f)
+ self.xml_document.write(filename, encoding="UTF-8")
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index af3ca249e..ebe7a09c2 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -494,7 +494,7 @@ $(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
@$(ECHO) %% Generating $@
ifdef GEN_PARAM_XML
- python $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --board CONFIG_ARCH_BOARD_$(CONFIG_BOARD) --xml
+ $(Q) $(PYTHON) $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --board CONFIG_ARCH_BOARD_$(CONFIG_BOARD) --xml
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
--git_identity $(PX4_BASE) \
--parameter_xml $(PRODUCT_PARAMXML) \
diff --git a/msg/actuator_armed.msg b/msg/actuator_armed.msg
index b83adb8f2..c8098724e 100644
--- a/msg/actuator_armed.msg
+++ b/msg/actuator_armed.msg
@@ -4,3 +4,4 @@ bool armed # Set to true if system is armed
bool ready_to_arm # Set to true if system is ready to be armed
bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL)
bool force_failsafe # Set to true if the actuators are forced to the failsafe position
+bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics
diff --git a/src/drivers/gimbal/gimbal.cpp b/src/drivers/gimbal/gimbal.cpp
index 1e27309d8..ae75d3a14 100644
--- a/src/drivers/gimbal/gimbal.cpp
+++ b/src/drivers/gimbal/gimbal.cpp
@@ -306,17 +306,17 @@ Gimbal::cycle()
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &att);
if (_attitude_compensation_roll) {
- roll = -att.roll;
+ roll = 1.0f / M_PI_F * -att.roll;
updated = true;
}
if (_attitude_compensation_pitch) {
- pitch = -att.pitch;
+ pitch = 1.0f / M_PI_F * -att.pitch;
updated = true;
}
if (_attitude_compensation_yaw) {
- yaw = att.yaw;
+ yaw = 1.0f / M_PI_F * att.yaw;
updated = true;
}
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index e5636ff0f..b974b711f 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -302,6 +302,7 @@ private:
float _battery_mamphour_total;///< amp hours consumed so far
uint64_t _battery_last_timestamp;///< last amp hour calculation timestamp
bool _cb_flighttermination; ///< true if the flight termination circuit breaker is enabled
+ bool _in_esc_calibration_mode; ///< do not send control outputs to IO (used for esc calibration)
int32_t _rssi_pwm_chan; ///< RSSI PWM input channel
int32_t _rssi_pwm_max; ///< max RSSI input on PWM channel
@@ -529,6 +530,7 @@ PX4IO::PX4IO(device::Device *interface) :
_battery_mamphour_total(0),
_battery_last_timestamp(0),
_cb_flighttermination(true),
+ _in_esc_calibration_mode(false),
_rssi_pwm_chan(0),
_rssi_pwm_max(0),
_rssi_pwm_min(0)
@@ -1167,12 +1169,29 @@ PX4IO::io_set_control_state(unsigned group)
break;
}
- if (!changed) {
+ if (!changed && (!_in_esc_calibration_mode || group != 0)) {
return -1;
+
+ } else if (_in_esc_calibration_mode && group == 0) {
+ /* modify controls to get max pwm (full thrust) on every esc */
+ memset(&controls, 0, sizeof(controls));
+
+ /* set maximum thrust */
+ controls.control[3] = 1.0f;
}
for (unsigned i = 0; i < _max_controls; i++) {
- regs[i] = FLOAT_TO_REG(controls.control[i]);
+
+ /* ensure FLOAT_TO_REG does not produce an integer overflow */
+ float ctrl = controls.control[i];
+
+ if (ctrl < -1.0f) {
+ ctrl = -1.0f;
+ } else if (ctrl > 1.0f) {
+ ctrl = 1.0f;
+ }
+
+ regs[i] = FLOAT_TO_REG(ctrl);
}
/* copy values to registers in IO */
@@ -1188,12 +1207,14 @@ PX4IO::io_set_arming_state()
int have_armed = orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
int have_control_mode = orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
+ _in_esc_calibration_mode = armed.in_esc_calibration_mode;
uint16_t set = 0;
uint16_t clear = 0;
- if (have_armed == OK) {
- if (armed.armed) {
+ if (have_armed == OK) {
+ _in_esc_calibration_mode = armed.in_esc_calibration_mode;
+ if (armed.armed || _in_esc_calibration_mode) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
} else {
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp
index 7e8c0fa52..e854c9aa7 100644
--- a/src/modules/commander/calibration_routines.cpp
+++ b/src/modules/commander/calibration_routines.cpp
@@ -43,12 +43,12 @@
#include <float.h>
#include <poll.h>
#include <drivers/drv_hrt.h>
-#include <drivers/drv_accel.h>
#include <mavlink/mavlink_log.h>
#include <geo/geo.h>
#include <string.h>
#include <uORB/topics/vehicle_command.h>
+#include <uORB/topics/sensor_combined.h>
#include "calibration_routines.h"
#include "calibration_messages.h"
@@ -236,7 +236,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int cancel_sub
{
const unsigned ndim = 3;
- struct accel_report sensor;
+ struct sensor_combined_s sensor;
float accel_ema[ndim] = { 0.0f }; // exponential moving average of accel
float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; // max-hold dispersion of accel
float ema_len = 0.5f; // EMA time constant in seconds
@@ -264,7 +264,7 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int cancel_sub
int poll_ret = poll(fds, 1, 1000);
if (poll_ret) {
- orb_copy(ORB_ID(sensor_accel), accel_sub, &sensor);
+ orb_copy(ORB_ID(sensor_combined), accel_sub, &sensor);
t = hrt_absolute_time();
float dt = (t - t_prev) / 1000000.0f;
t_prev = t;
@@ -275,13 +275,13 @@ enum detect_orientation_return detect_orientation(int mavlink_fd, int cancel_sub
float di = 0.0f;
switch (i) {
case 0:
- di = sensor.x;
+ di = sensor.accelerometer_m_s2[0];
break;
case 1:
- di = sensor.y;
+ di = sensor.accelerometer_m_s2[1];
break;
case 2:
- di = sensor.z;
+ di = sensor.accelerometer_m_s2[2];
break;
}
@@ -410,7 +410,7 @@ calibrate_return calibrate_from_orientation(int mavlink_fd,
// Setup subscriptions to onboard accel sensor
- int sub_accel = orb_subscribe_multi(ORB_ID(sensor_accel), 0);
+ int sub_accel = orb_subscribe(ORB_ID(sensor_combined));
if (sub_accel < 0) {
mavlink_and_console_log_critical(mavlink_fd, CAL_QGC_FAILED_MSG, "No onboard accel");
return calibrate_return_error;
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 7aaf5e5cd..50846ff4d 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -114,6 +114,7 @@
#include "baro_calibration.h"
#include "rc_calibration.h"
#include "airspeed_calibration.h"
+#include "esc_calibration.h"
#include "PreflightCheck.h"
/* oddly, ERROR is not defined for c++ */
@@ -1159,7 +1160,7 @@ int commander_thread_main(int argc, char *argv[])
/* initialize low priority thread */
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2000);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2600);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
@@ -2708,6 +2709,16 @@ void *commander_low_prio_loop(void *arg)
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+ } else if ((int)(cmd.param7) == 1) {
+ /* do esc calibration */
+ calib_ret = check_if_batt_disconnected(mavlink_fd);
+ if(calib_ret == OK) {
+ answer_command(cmd,VEHICLE_CMD_RESULT_ACCEPTED);
+ armed.in_esc_calibration_mode = true;
+ calib_ret = do_esc_calibration(mavlink_fd);
+ armed.in_esc_calibration_mode = false;
+ }
+
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
@@ -2717,6 +2728,8 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_info(mavlink_fd, "CAL: Re-enabling RC IN");
calib_ret = OK;
}
+ /* this always succeeds */
+ calib_ret = OK;
}
if (calib_ret == OK) {
diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp
new file mode 100644
index 000000000..541aca053
--- /dev/null
+++ b/src/modules/commander/esc_calibration.cpp
@@ -0,0 +1,152 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file esc_calibration.cpp
+ *
+ * Definition of esc calibration
+ *
+ * @author Roman Bapst <bapstr@ethz.ch>
+ */
+
+#include "esc_calibration.h"
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <sys/ioctl.h>
+#include <systemlib/err.h>
+#include <fcntl.h>
+#include <poll.h>
+#include "drivers/drv_pwm_output.h"
+#include <uORB/topics/battery_status.h>
+#include <uORB/topics/vehicle_command.h>
+#include <uORB/uORB.h>
+#include <drivers/drv_hrt.h>
+#include <mavlink/mavlink_log.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+int check_if_batt_disconnected(int mavlink_fd) {
+ struct battery_status_s battery;
+ memset(&battery,0,sizeof(battery));
+ int batt_sub = orb_subscribe(ORB_ID(battery_status));
+ orb_copy(ORB_ID(battery_status), batt_sub, &battery);
+
+ if (battery.voltage_filtered_v > 3.0f && !(hrt_absolute_time() - battery.timestamp > 500000)) {
+ mavlink_log_info(mavlink_fd, "Please disconnect battery and try again!");
+ return ERROR;
+ }
+ return OK;
+}
+
+
+int do_esc_calibration(int mavlink_fd) {
+
+ int fd = open(PWM_OUTPUT0_DEVICE_PATH, 0);
+ int ret;
+
+ if(fd < 0) {
+ err(1,"Can't open %s", PWM_OUTPUT0_DEVICE_PATH);
+ }
+
+ /* tell IO/FMU that its ok to disable its safety with the switch */
+ ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET_ARM_OK");
+ /* tell IO/FMU that the system is armed (it will output values if safety is off) */
+ ret = ioctl(fd, PWM_SERVO_ARM, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_ARM");
+ /* tell IO to switch off safety without using the safety switch */
+ ret = ioctl(fd, PWM_SERVO_SET_FORCE_SAFETY_OFF, 0);
+ if(ret!=0) {
+ err(1,"PWM_SERVO_SET_FORCE_SAFETY_OFF");
+ }
+
+ mavlink_log_info(mavlink_fd,"Please connect battery now");
+
+ struct battery_status_s battery;
+ memset(&battery,0,sizeof(battery));
+ int batt_sub = orb_subscribe(ORB_ID(battery_status));
+ orb_copy(ORB_ID(vehicle_command),batt_sub, &battery);
+ bool updated = false;
+
+ struct vehicle_command_s cmd;
+ memset(&cmd, 0, sizeof(cmd));
+ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
+ orb_copy(ORB_ID(vehicle_command),cmd_sub, &cmd);
+
+ /* wait for one of the following events:
+ 1) user has pressed the button in QGroundControl
+ 2) timeout of 5 seconds is reached
+ */
+ hrt_abstime start_time = hrt_absolute_time();
+
+ while(true) {
+ orb_check(batt_sub,&updated);
+ if(updated) {
+ orb_copy(ORB_ID(battery_status), batt_sub, &battery);
+ }
+ // user has connected battery
+ if(battery.voltage_filtered_v > 3.0f) {
+ orb_check(cmd_sub,&updated);
+ if(updated) {
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+ }
+ if((int)(cmd.param7) == 2 && cmd.command == VEHICLE_CMD_PREFLIGHT_CALIBRATION) {
+ break;
+ } else if (hrt_absolute_time() - start_time > 5000000) {
+ // waited for 5 seconds, switch to low pwm
+ break;
+ }
+ }
+ else {
+ start_time = hrt_absolute_time();
+ }
+ usleep(50000);
+ }
+
+ /* disarm */
+ ret = ioctl(fd, PWM_SERVO_DISARM, 0);
+ if (ret != OK)
+ err(1, "PWM_SERVO_DISARM");
+
+ mavlink_log_info(mavlink_fd,"ESC calibration finished");
+ return OK;
+ } \ No newline at end of file
diff --git a/src/modules/commander/esc_calibration.h b/src/modules/commander/esc_calibration.h
new file mode 100644
index 000000000..5539955eb
--- /dev/null
+++ b/src/modules/commander/esc_calibration.h
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file esc_calibration.h
+ *
+ * Definition of esc calibration
+ *
+ * @author Roman Bapst <bapstr@ethz.ch>
+ */
+
+#ifndef ESC_CALIBRATION_H_
+#define ESC_CALIBRATION_H_
+int check_if_batt_disconnected(int mavlink_fd);
+int do_esc_calibration(int mavlink_fd);
+
+#endif \ No newline at end of file
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 4437041e2..5331428c2 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,6 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp \
+ esc_calibration.cpp \
PreflightCheck.cpp
MODULE_STACKSIZE = 5000