aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-07-07 12:22:56 -0700
committerpx4dev <px4@purgatory.org>2013-07-07 12:22:56 -0700
commit43f1843cc750fcef07122feaeca07863ed28c036 (patch)
tree77f0192152038670fe5a875a2a38232b28e7d044 /src/drivers
parent9fe257c4d151280c770e607bc3160703f9503889 (diff)
parentcf2dbdf9a1ae06c7d0e0a7963916a3709a1bc075 (diff)
downloadpx4-firmware-43f1843cc750fcef07122feaeca07863ed28c036.tar.gz
px4-firmware-43f1843cc750fcef07122feaeca07863ed28c036.tar.bz2
px4-firmware-43f1843cc750fcef07122feaeca07863ed28c036.zip
Merge branch 'master' of https://github.com/PX4/Firmware into fmuv2_bringup
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_init.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_internal.h2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_led.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_pwm_servo.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_spi.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_usb.c2
-rw-r--r--src/drivers/boards/px4io/px4io_init.c2
-rw-r--r--src/drivers/boards/px4io/px4io_internal.h2
-rw-r--r--src/drivers/boards/px4io/px4io_pwm_servo.c2
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp160
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hott_telemetry/hott_telemetry_main.c2
-rw-r--r--src/drivers/hott_telemetry/messages.c13
-rw-r--r--src/drivers/md25/md25_main.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp2
-rw-r--r--src/drivers/stm32/adc/adc.cpp2
-rw-r--r--src/drivers/stm32/drv_hrt.c6
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c2
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp2
21 files changed, 117 insertions, 98 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index aeaf830de..735bdb41a 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[])
}
thread_should_exit = false;
- ardrone_interface_task = task_spawn("ardrone_interface",
+ ardrone_interface_task = task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
2048,
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c
index 69edc23ab..212a92cfa 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu/px4fmu_init.c
@@ -58,7 +58,7 @@
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu/px4fmu_internal.h
index 5a73c10bf..56173abf6 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu/px4fmu_internal.h
@@ -50,7 +50,7 @@
__BEGIN_DECLS
/* these headers are not C++ safe */
-#include <stm32_internal.h>
+#include <stm32.h>
/****************************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu/px4fmu_led.c
index 34fd194c3..31b25984e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu/px4fmu_led.c
@@ -41,7 +41,7 @@
#include <stdbool.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
index cb8918306..d85131dd8 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu/px4fmu_spi.c
index b5d00eac0..e05ddecf3 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu/px4fmu_spi.c
@@ -52,7 +52,7 @@
#include "up_arch.h"
#include "chip.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu/px4fmu_usb.c
index b0b669fbe..0be981c1e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu/px4fmu_usb.c
@@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io/px4io_init.c
index d36353c6f..15c59e423 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io/px4io_init.c
@@ -54,7 +54,7 @@
#include <nuttx/arch.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4io_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io/px4io_internal.h
index eb2820bb7..6638e715e 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io/px4io_internal.h
@@ -47,7 +47,7 @@
#include <nuttx/compiler.h>
#include <stdint.h>
-#include <stm32_internal.h>
+#include <stm32.h>
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io/px4io_pwm_servo.c
index a2f73c429..6df470da6 100644
--- a/src/drivers/boards/px4io/px4io_pwm_servo.c
+++ b/src/drivers/boards/px4io/px4io_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index e50395e47..b34d3fa5d 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -37,7 +37,7 @@
*
* Driver for the Eagle Tree Airspeed V3 connected via I2C.
*/
-
+
#include <nuttx/config.h>
#include <drivers/device/i2c.h>
@@ -77,15 +77,16 @@
#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
/* I2C bus address */
-#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
+#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
/* Register address */
-#define READ_CMD 0x07 /* Read the data */
-
+#define READ_CMD 0x07 /* Read the data */
+
/**
- * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * You can set this value to 12 if you want a zero reading below 15km/h.
*/
-#define MIN_ACCURATE_DIFF_PRES_PA 12
+#define MIN_ACCURATE_DIFF_PRES_PA 0
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@@ -105,38 +106,38 @@ class ETSAirspeed : public device::I2C
public:
ETSAirspeed(int bus, int address = I2C_ADDRESS);
virtual ~ETSAirspeed();
-
- virtual int init();
-
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
/**
* Diagnostics - print some basic information about the driver.
*/
- void print_info();
-
+ void print_info();
+
protected:
- virtual int probe();
+ virtual int probe();
private:
- work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- differential_pressure_s *_reports;
- bool _sensor_ok;
- int _measure_ticks;
- bool _collect_phase;
- int _diff_pres_offset;
-
- orb_advert_t _airspeed_pub;
-
- perf_counter_t _sample_perf;
- perf_counter_t _comms_errors;
- perf_counter_t _buffer_overflows;
-
-
+ work_s _work;
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ differential_pressure_s *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ int _diff_pres_offset;
+
+ orb_advert_t _airspeed_pub;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+
/**
* Test whether the device supported by the driver is present at a
* specific address.
@@ -144,28 +145,28 @@ private:
* @param address The I2C bus address to probe.
* @return True if the device is present.
*/
- int probe_address(uint8_t address);
-
+ int probe_address(uint8_t address);
+
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
- void start();
-
+ void start();
+
/**
* Stop the automatic measurement state machine.
*/
- void stop();
-
+ void stop();
+
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
- void cycle();
- int measure();
- int collect();
+ void cycle();
+ int measure();
+ int collect();
/**
* Static trampoline from the workq context; because we don't have a
@@ -173,9 +174,9 @@ private:
*
* @param arg Instance pointer for the driver that is polling.
*/
- static void cycle_trampoline(void *arg);
-
-
+ static void cycle_trampoline(void *arg);
+
+
};
/* helper macro for handling report buffer indices */
@@ -203,7 +204,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) :
{
// enable debug() calls
_debug_enabled = true;
-
+
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));
}
@@ -230,6 +231,7 @@ ETSAirspeed::init()
/* allocate basic report buffers */
_num_reports = 2;
_reports = new struct differential_pressure_s[_num_reports];
+
for (unsigned i = 0; i < _num_reports; i++)
_reports[i].max_differential_pressure_pa = 0;
@@ -351,11 +353,11 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
case SENSORIOCGQUEUEDEPTH:
return _num_reports - 1;
-
+
case SENSORIOCRESET:
/* XXX implement this */
return -EINVAL;
-
+
default:
/* give it to the superclass */
return I2C::ioctl(filp, cmd, arg);
@@ -432,14 +434,14 @@ ETSAirspeed::measure()
uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0);
- if (OK != ret)
- {
+ if (OK != ret) {
perf_count(_comms_errors);
log("i2c::transfer returned %d", ret);
return ret;
}
+
ret = OK;
-
+
return ret;
}
@@ -447,30 +449,31 @@ int
ETSAirspeed::collect()
{
int ret = -EIO;
-
+
/* read from the sensor */
uint8_t val[2] = {0, 0};
-
+
perf_begin(_sample_perf);
-
+
ret = transfer(nullptr, 0, &val[0], 2);
-
+
if (ret < 0) {
log("error reading from sensor: %d", ret);
return ret;
}
-
+
uint16_t diff_pres_pa = val[1] << 8 | val[0];
+ // XXX move the parameter read out of the driver.
param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
-
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+ if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
+
} else {
- diff_pres_pa -= _diff_pres_offset;
+ diff_pres_pa -= _diff_pres_offset;
}
- // XXX we may want to smooth out the readings to remove noise.
+ // XXX we may want to smooth out the readings to remove noise.
_reports[_next_report].timestamp = hrt_absolute_time();
_reports[_next_report].differential_pressure_pa = diff_pres_pa;
@@ -498,7 +501,7 @@ ETSAirspeed::collect()
ret = OK;
perf_end(_sample_perf);
-
+
return ret;
}
@@ -511,17 +514,19 @@ ETSAirspeed::start()
/* schedule a cycle to start things */
work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1);
-
+
/* notify about state change */
struct subsystem_info_s info = {
true,
true,
true,
- SUBSYSTEM_TYPE_DIFFPRESSURE};
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
static orb_advert_t pub = -1;
if (pub > 0) {
orb_publish(ORB_ID(subsystem_info), pub, &info);
+
} else {
pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
@@ -653,8 +658,7 @@ start(int i2c_bus)
fail:
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
@@ -668,15 +672,14 @@ fail:
void
stop()
{
- if (g_dev != nullptr)
- {
+ if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
- }
- else
- {
+
+ } else {
errx(1, "driver not running");
}
+
exit(0);
}
@@ -773,10 +776,10 @@ info()
} // namespace
-static void
-ets_airspeed_usage()
+static void
+ets_airspeed_usage()
{
- fprintf(stderr, "usage: ets_airspeed [options] command\n");
+ fprintf(stderr, "usage: ets_airspeed command [options]\n");
fprintf(stderr, "options:\n");
fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT);
fprintf(stderr, "command:\n");
@@ -789,6 +792,7 @@ ets_airspeed_main(int argc, char *argv[])
int i2c_bus = PX4_I2C_BUS_DEFAULT;
int i;
+
for (i = 1; i < argc; i++) {
if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
if (argc > i + 1) {
@@ -802,12 +806,12 @@ ets_airspeed_main(int argc, char *argv[])
*/
if (!strcmp(argv[1], "start"))
ets_airspeed::start(i2c_bus);
-
- /*
- * Stop the driver
- */
- if (!strcmp(argv[1], "stop"))
- ets_airspeed::stop();
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ ets_airspeed::stop();
/*
* Test the driver/device.
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index d9aa772d4..bd027ce0b 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -224,7 +224,7 @@ HIL::init()
// gpio_reset();
/* start the HIL interface task */
- _task = task_spawn("fmuhil",
+ _task = task_spawn_cmd("fmuhil",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c
index 1d2bdd92e..4699ce5bf 100644
--- a/src/drivers/hott_telemetry/hott_telemetry_main.c
+++ b/src/drivers/hott_telemetry/hott_telemetry_main.c
@@ -271,7 +271,7 @@ hott_telemetry_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn(daemon_name,
+ deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
2048,
diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c
index 369070f8c..0ce56acef 100644
--- a/src/drivers/hott_telemetry/messages.c
+++ b/src/drivers/hott_telemetry/messages.c
@@ -44,6 +44,7 @@
#include <string.h>
#include <systemlib/geo/geo.h>
#include <unistd.h>
+#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/sensor_combined.h>
@@ -56,6 +57,7 @@ static int battery_sub = -1;
static int gps_sub = -1;
static int home_sub = -1;
static int sensor_sub = -1;
+static int airspeed_sub = -1;
static bool home_position_set = false;
static double home_lat = 0.0d;
@@ -68,6 +70,7 @@ messages_init(void)
gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
home_sub = orb_subscribe(ORB_ID(home_position));
sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
+ airspeed_sub = orb_subscribe(ORB_ID(airspeed));
}
void
@@ -100,6 +103,16 @@ build_eam_response(uint8_t *buffer, size_t *size)
msg.altitude_L = (uint8_t)alt & 0xff;
msg.altitude_H = (uint8_t)(alt >> 8) & 0xff;
+ /* get a local copy of the airspeed data */
+ struct airspeed_s airspeed;
+ memset(&airspeed, 0, sizeof(airspeed));
+ orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
+
+ uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f);
+ msg.speed_L = (uint8_t)speed & 0xff;
+ msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
+
+
msg.stop = STOP_BYTE;
memcpy(buffer, &msg, *size);
}
diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp
index 80850e708..e62c46b0d 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("md25",
+ deamon_task = task_spawn_cmd("md25",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
2048,
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index c67276f8a..b54b7aba1 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -313,7 +313,7 @@ MK::init(unsigned motors)
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("mkblctrl",
+ _task = task_spawn_cmd("mkblctrl",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index e199a5998..ff99de02f 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -264,7 +264,7 @@ PX4FMU::init()
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("fmuservo",
+ _task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 911def943..1020eb946 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -58,7 +58,7 @@
#include <drivers/drv_adc.h>
#include <arch/stm32/chip.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <systemlib/err.h>
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index fd63681e3..7ef3db970 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -66,7 +66,7 @@
#include "up_internal.h"
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
@@ -278,8 +278,10 @@ static void hrt_call_invoke(void);
#ifdef CONFIG_HRT_PPM
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
+ *
+ * Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
*/
-# ifndef GTIM_CCER_CC1NP
+# ifdef CONFIG_ARCH_CORTEXM3
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index c1efb8515..7b060412c 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -64,7 +64,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index ac5511e60..167ef30a8 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -111,7 +111,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>