I converted UART signal to i2c with arduino after all. I tried to build firmware, but this error occured.
[1197/1199] Linking CXX executable px4_fmu-v5_default.elf
FAILED: px4_fmu-v5_default.elf
: && /usr/local/bin/arm-none-eabi-g++ -mcpu=cortex-m7 -mthumb -mfpu=fpv5-d16 -mfloat-abi=hard -Os -DNDEBUG --specs=nosys.specs platforms/nuttx/CMakeFiles/px4.dir/__/__/src/platforms/empty.c.obj -o px4_fmu-v5_default.elf -L/Users/THashimoto/Firmware/build/px4_fmu-v5_default/external/Install/lib -nostartfiles -nodefaultlibs -nostdlib -nostdinc++ -fno-exceptions -fno-rtti -Wl,--script=/Users/THashimoto/Firmware/build/px4_fmu-v5_default/NuttX/nuttx-config/scripts/script.ld -Wl,-Map=px4_fmu-v5_default.map -Wl,--warn-common -Wl,--gc-sections -Wl,--start-group src/drivers/boards/common/stm32/libdrivers_boards_common_arch.a NuttX/apps/libapps.a NuttX/nuttx/arch/arm/src/libarch.a NuttX/nuttx/binfmt/libbinfmt.a NuttX/nuttx/libs/libc/libc.a NuttX/nuttx/configs/libconfigs.a NuttX/nuttx/libs/libxx/libxx.a NuttX/nuttx/drivers/libdrivers.a NuttX/nuttx/fs/libfs.a NuttX/nuttx/mm/libmm.a NuttX/nuttx/sched/libsched.a -Wl,--end-group -lm -lgcc src/lib/cdev/test/liblib__cdev__test__cdev_test.a src/lib/controllib/controllib_test/liblib__controllib__controllib_test.a src/modules/uORB/libmodules__uORB.a src/modules/uORB/uORB_tests/libmodules__uORB__uORB_tests.a src/drivers/barometer/bmp280/libdrivers__bmp280.a src/drivers/barometer/lps22hb/libdrivers__barometer__lps22hb.a src/drivers/barometer/ms5611/libdrivers__ms5611.a src/drivers/batt_smbus/libdrivers__batt_smbus.a src/drivers/camera_capture/libdrivers__camera_capture.a src/drivers/camera_trigger/libdrivers__camera_trigger.a src/drivers/differential_pressure/ets/libdrivers__ets_airspeed.a src/drivers/differential_pressure/ms4525/libdrivers__ms4525_airspeed.a src/drivers/differential_pressure/ms5525/libdrivers__ms5525_airspeed.a src/drivers/differential_pressure/sdp3x/libdrivers__sdp3x_airspeed.a src/drivers/differential_pressure/ft205ev/libdrivers__ft205ev.a src/drivers/distance_sensor/cm8jl65/libdrivers__cm8jl65.a src/drivers/distance_sensor/leddar_one/libdrivers__leddar_one.a src/drivers/distance_sensor/ll40ls/libdrivers__ll40ls.a src/drivers/distance_sensor/mb12xx/libdrivers__mb12xx.a src/drivers/distance_sensor/pga460/libdrivers__pga460.a src/drivers/distance_sensor/sf0x/libdrivers__sf0x.a src/drivers/distance_sensor/sf0x/sf0x_tests/libdrivers__sf0x__sf0x_tests.a src/drivers/distance_sensor/sf1xx/libdrivers__sf1xx.a src/drivers/distance_sensor/srf02/libdrivers__srf02.a src/drivers/distance_sensor/teraranger/libdrivers__teraranger.a src/drivers/distance_sensor/tfmini/libdrivers__tfmini.a src/drivers/distance_sensor/ulanding/libdrivers__ulanding.a src/drivers/distance_sensor/vl53lxx/libdrivers__vl53lxx.a src/drivers/gps/libdrivers__gps.a src/drivers/imu/adis16448/libdrivers__adis16448.a src/drivers/imu/adis16497/libdrivers__imu__adis16497.a src/drivers/imu/bmi055/libdrivers__bmi055.a src/drivers/imu/mpu6000/libdrivers__mpu6000.a src/drivers/imu/mpu9250/libdrivers__mpu9250.a src/drivers/irlock/libdrivers__irlock.a src/drivers/lights/blinkm/libdrivers__blinkm.a src/drivers/lights/oreoled/libdrivers__oreoled.a src/drivers/lights/pca8574/libdrivers__pca8574.a src/drivers/lights/rgbled/libdrivers__rgbled.a src/drivers/lights/rgbled_ncp5623c/libdrivers__rgbled_ncp5623c.a src/drivers/lights/rgbled_pwm/libdrivers__rgbled_pwm.a src/drivers/magnetometer/ak09916/libdrivers__ak09916.a src/drivers/magnetometer/bmm150/libdrivers__bmm150.a src/drivers/magnetometer/hmc5883/libdrivers__hmc5883.a src/drivers/magnetometer/qmc5883/libdrivers__qmc5883.a src/drivers/magnetometer/ist8310/libdrivers__ist8310.a src/drivers/magnetometer/lis3mdl/libdrivers__lis3mdl.a src/drivers/magnetometer/lsm303agr/libdrivers__magnetometer__lsm303agr.a src/drivers/magnetometer/rm3100/libdrivers__rm3100.a src/drivers/mkblctrl/libdrivers__mkblctrl.a src/drivers/pca9685/libdrivers__pca9685.a src/drivers/pmw3901/libdrivers__pmw3901.a src/drivers/power_monitor/ina226/libdrivers__ina226.a src/drivers/pwm_input/libdrivers__pwm_input.a src/drivers/pwm_out_sim/libdrivers__pwm_out_sim.a src/drivers/px4flow/libdrivers__px4flow.a src/drivers/px4fmu/libdrivers__px4fmu.a src/drivers/px4io/libdrivers__px4io.a src/drivers/rc_input/libdrivers__rc_input.a src/drivers/roboclaw/libdrivers__roboclaw.a src/drivers/stm32/adc/libdrivers__adc.a src/drivers/stm32/armv7-m_dcache/libdrivers__armv7-m_dcache.a src/drivers/tap_esc/libdrivers__tap_esc.a src/drivers/telemetry/bst/libdrivers__bst.a src/drivers/telemetry/frsky_telemetry/libdrivers__frsky_telemetry.a src/drivers/telemetry/hott/hott_sensors/libdrivers__hott__hott_sensors.a src/drivers/telemetry/hott/hott_telemetry/libdrivers__hott__hott_telemetry.a src/drivers/telemetry/iridiumsbd/libdrivers__iridiumsbd.a src/drivers/test_ppm/libdrivers__test_ppm.a src/drivers/tone_alarm/libdrivers__tone_alarm.a src/drivers/uavcan/libmodules__uavcan.a src/modules/attitude_estimator_q/libmodules__attitude_estimator_q.a src/modules/camera_feedback/libmodules__camera_feedback.a src/modules/commander/libmodules__commander.a src/modules/commander/commander_tests/libmodules__commander__commander_tests.a src/modules/dataman/libmodules__dataman.a src/modules/ekf2/libmodules__ekf2.a src/modules/events/libmodules__events.a src/modules/fw_att_control/libmodules__fw_att_control.a src/modules/fw_pos_control_l1/libmodules__fw_pos_control_l1.a src/modules/gnd_att_control/libmodules__gnd_att_control.a src/modules/gnd_pos_control/libmodules__gnd_pos_control.a src/modules/land_detector/libmodules__land_detector.a src/modules/landing_target_estimator/libmodules__landing_target_estimator.a src/modules/load_mon/libmodules__load_mon.a src/modules/local_position_estimator/libmodules__local_position_estimator.a src/modules/logger/libmodules__logger.a src/modules/mavlink/libmodules__mavlink.a src/modules/mavlink/mavlink_tests/libmodules__mavlink__mavlink_tests.a src/modules/mc_att_control/libmodules__mc_att_control.a src/modules/mc_pos_control/libmodules__mc_pos_control.a src/modules/navigator/libmodules__navigator.a src/modules/sensors/libmodules__sensors.a src/modules/sih/libmodules__sih.a src/modules/vmount/libdrivers__vmount.a src/modules/vtol_att_control/libmodules__vtol_att_control.a src/modules/wind_estimator/libmodules__wind_estimator.a src/systemcmds/bl_update/libsystemcmds__bl_update.a src/systemcmds/config/libsystemcmds__config.a src/systemcmds/dumpfile/libsystemcmds__dumpfile.a src/systemcmds/esc_calib/libsystemcmds__esc_calib.a src/systemcmds/hardfault_log/libsystemcmds__hardfault_log.a src/systemcmds/led_control/libsystemcmds__led_control.a src/systemcmds/mixer/libsystemcmds__mixer.a src/systemcmds/motor_ramp/libsystemcmds__motor_ramp.a src/systemcmds/motor_test/libsystemcmds__motor_test.a src/systemcmds/mtd/libsystemcmds__mtd.a src/systemcmds/nshterm/libsystemcmds__nshterm.a src/systemcmds/param/libsystemcmds__param.a src/systemcmds/perf/libsystemcmds__perf.a src/systemcmds/pwm/libsystemcmds__pwm.a src/systemcmds/reboot/libsystemcmds__reboot.a src/systemcmds/reflect/libsystemcmds__reflect.a src/systemcmds/sd_bench/libsystemcmds__sd_bench.a src/systemcmds/shutdown/libsystemcmds__shutdown.a src/systemcmds/tests/libsystemcmds__tests.a src/systemcmds/tests/hrt_test/libsystemcmds__tests__hrt_test.a src/systemcmds/top/libsystemcmds__top.a src/systemcmds/topic_listener/libsystemcmds__topic_listener.a src/systemcmds/tune_control/libsystemcmds__tune_control.a src/systemcmds/usb_connected/libsystemcmds__usb_connected.a src/systemcmds/ver/libsystemcmds__ver.a src/examples/bottle_drop/libmodules__bottle_drop.a src/examples/fixedwing_control/libexamples__fixedwing_control.a src/examples/hello/libexamples__hello.a src/examples/hwtest/libexamples__hwtest.a src/examples/position_estimator_inav/libmodules__position_estimator_inav.a src/examples/px4_mavlink_debug/libexamples__px4_mavlink_debug.a src/examples/px4_simple_app/libexamples__px4_simple_app.a src/examples/rover_steering_control/libexamples__rover_steering_control.a src/examples/segway/libexamples__segway.a src/examples/uuv_example_app/libexamples__uuv_example_app.a ROMFS/libromfs.a src/lib/drivers/smbus/libdrivers__smbus.a src/lib/drivers/airspeed/libdrivers__airspeed.a src/lib/drivers/accelerometer/libdrivers_accelerometer.a src/lib/drivers/gyroscope/libdrivers_gyroscope.a src/lib/led/libled.a src/lib/rc/librc.a src/drivers/telemetry/hott/libdrivers__hott.a src/drivers/stm32/tone_alarm/libtone_alarm_interface.a src/drivers/uavcan/libuavcan/libuavcan/libuavcan.a src/drivers/uavcan/libuavcan/libuavcan_drivers/stm32/driver/libuavcan_stm32_driver.a src/lib/DriverFramework/framework/src/libdf_driver_framework.a src/modules/commander/failure_detector/libfailure_detector.a src/lib/ecl/EKF/libecl_EKF.a src/lib/ecl/attitude_fw/libecl_attitude_fw.a src/lib/ecl/tecs/libecl_tecs.a src/modules/fw_pos_control_l1/launchdetection/liblaunchdetection.a src/modules/fw_pos_control_l1/runway_takeoff/librunway_takeoff.a src/lib/ecl/l1/libecl_l1.a src/lib/pid/libpid.a src/lib/circuit_breaker/libcircuit_breaker.a src/modules/mc_att_control/AttitudeControl/libAttitudeControl.a src/lib/controllib/libcontrollib.a src/lib/FlightTasks/libFlightTasks.a src/lib/FlightTasks/tasks/ManualAltitudeSmoothVel/libFlightTaskManualAltitudeSmoothVel.a src/lib/FlightTasks/tasks/ManualPositionSmooth/libFlightTaskManualPositionSmooth.a src/lib/FlightTasks/tasks/ManualPositionSmoothVel/libFlightTaskManualPositionSmoothVel.a src/lib/FlightTasks/tasks/ManualPosition/libFlightTaskManualPosition.a src/lib/FlightTasks/tasks/AutoLine/libFlightTaskAutoLine.a src/lib/FlightTasks/tasks/AutoMapper/libFlightTaskAutoMapper.a src/lib/FlightTasks/tasks/AutoLineSmoothVel/libFlightTaskAutoLineSmoothVel.a src/lib/FlightTasks/tasks/AutoMapper2/libFlightTaskAutoMapper2.a src/lib/FlightTasks/tasks/AutoFollowMe/libFlightTaskAutoFollowMe.a src/lib/FlightTasks/tasks/Auto/libFlightTaskAuto.a src/lib/FlightTasks/tasks/Offboard/libFlightTaskOffboard.a src/lib/FlightTasks/tasks/Failsafe/libFlightTaskFailsafe.a src/lib/FlightTasks/tasks/Transition/libFlightTaskTransition.a src/lib/FlightTasks/tasks/Orbit/libFlightTaskOrbit.a src/lib/FlightTasks/tasks/ManualAltitudeSmooth/libFlightTaskManualAltitudeSmooth.a src/lib/FlightTasks/tasks/ManualAltitude/libFlightTaskManualAltitude.a src/lib/FlightTasks/tasks/Manual/libFlightTaskManual.a src/lib/FlightTasks/tasks/Utility/libFlightTaskUtility.a src/lib/FlightTasks/tasks/FlightTask/libFlightTask.a src/lib/WeatherVane/libWeatherVane.a src/lib/CollisionPrevention/libCollisionPrevention.a src/modules/mc_pos_control/Takeoff/libTakeoff.a src/lib/landing_slope/liblanding_slope.a src/lib/airspeed/libairspeed.a src/lib/conversion/libconversion.a src/lib/battery/libbattery.a src/lib/ecl/validation/libecl_validation.a src/lib/mathlib/libmathlib.a src/lib/ecl/airdata/libecl_airdata.a src/lib/mixer/libmixer.a src/lib/pwm_limit/libpwm_limit.a src/lib/ecl/geo_lookup/libecl_geo_lookup.a src/lib/tunes/libtunes.a src/lib/version/libversion.a src/lib/ecl/geo/libecl_geo.a src/lib/terrain_estimation/libterrain_estimation.a src/drivers/boards/common/stm32/libdrivers_boards_common_arch.a NuttX/nuttx/arch/arm/src/libarch.a src/modules/uORB/libmodules__uORB.a boards/px4/fmu-v5/src/libdrivers_board.a src/drivers/stm32/libdrivers_arch.a src/drivers/boards/common/libdrivers_boards_common.a platforms/nuttx/src/px4_layer/libpx4_layer.a src/platforms/common/libpx4_platform.a src/lib/systemlib/libsystemlib.a src/lib/cdev/libcdev.a src/lib/drivers/device/libdrivers__device.a src/lib/drivers/led/libdrivers__led.a src/lib/parameters/libparameters.a src/lib/parameters/flashparams/libflashparams.a src/drivers/boards/common/stm32/libdrivers_boards_common_arch.a NuttX/nuttx/arch/arm/src/libarch.a src/modules/uORB/libmodules__uORB.a boards/px4/fmu-v5/src/libdrivers_board.a src/drivers/stm32/libdrivers_arch.a src/drivers/boards/common/libdrivers_boards_common.a platforms/nuttx/src/px4_layer/libpx4_layer.a src/platforms/common/libpx4_platform.a src/lib/systemlib/libsystemlib.a src/lib/cdev/libcdev.a src/lib/drivers/device/libdrivers__device.a src/lib/drivers/led/libdrivers__led.a src/lib/parameters/libparameters.a src/lib/parameters/flashparams/libflashparams.a NuttX/apps/libapps.a NuttX/nuttx/libs/libxx/libxx.a NuttX/nuttx/libs/libc/libc.a NuttX/nuttx/drivers/libdrivers.a NuttX/nuttx/fs/libfs.a NuttX/nuttx/mm/libmm.a NuttX/nuttx/sched/libsched.a -lm -lgcc msg/libuorb_msgs.a src/lib/perf/libperf.a src/lib/parameters/tinybson/libtinybson.a && :
NuttX/apps/libapps.a(builtin_list.o):(.rodata.g_builtins+0x20c): undefined reference to `ft205ev_main'
collect2: error: ld returned 1 exit status
ninja: build stopped: subcommand failed.
make: *** [px4_fmu-v5_default] Error 1
And this is the driver I wrote using ets_airspeed.cpp as template.
#include <float.h>
#include <px4_config.h>
#include <drivers/device/i2c.h>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <perf/perf_counter.h>
#include <px4_getopt.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <drivers/airspeed/airspeed.h>
#include <airspeed/airspeed.h>
#include <uORB/topics/airspeed.h>
/* I2C bus address */
#define I2C_ADDRESS 8 /* 7-bit address. 8-bit address is 0xEA */
#define FT205EV_PATH "/dev/ft205ev"
/* Register address */
#define READ_CMD 0x07 /* Read the data */
/**
* 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 0
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
class FT205EV : public Airspeed
{
public:
FT205EV(int bus, int address = I2C_ADDRESS, const char *path = FT205EV_PATH);
protected:
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
virtual void cycle();
virtual int measure();
virtual int collect();
};
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int ft205ev_airspeed_main(int argc, char *argv[]);
FT205EV::FT205EV(int bus, int address, const char *path) : Airspeed(bus, address,
CONVERSION_INTERVAL, path)
{
_device_id.devid_s.devtype = DRV_DIFF_PRESS_DEVTYPE_MS4525;
}
int
FT205EV::measure()
{
int ret;
/*
* Send the command to begin a measurement.
*/
uint8_t cmd = READ_CMD;
ret = transfer(&cmd, 1, nullptr, 0);
if (OK != ret) {
perf_count(_comms_errors);
}
return ret;
}
int
FT205EV::collect()
{
int ret = -EIO;
/* read from the sensor */
uint8_t val[8];
perf_begin(_sample_perf);
ret = transfer(nullptr, 0, &val[0], 8);
if (ret < 0) {
perf_count(_comms_errors);
return ret;
}
union{
double d;
uint8_t i8[8];
} converter;
memcpy(converter.i8,val,8);
float aspd = (float)converter.d;
airspeed_s report;
report.timestamp = hrt_absolute_time();
// XXX we may want to smooth out the readings to remove noise.
report.indicated_airspeed_m_s = aspd;
report.true_airspeed_m_s = aspd;
report.air_temperature_celsius = -1000.0;
report.confidence = 1;
if (_airspeed_pub == nullptr) {
_airspeed_pub = orb_advertise(ORB_ID(airspeed), &report);
} else {
orb_publish(ORB_ID(airspeed), _airspeed_pub, &report);
}
ret = OK;
perf_end(_sample_perf);
return ret;
}
void
FT205EV::cycle()
{
int ret;
/* collection phase? */
if (_collect_phase) {
/* perform collection */
ret = collect();
if (OK != ret) {
perf_count(_comms_errors);
/* restart the measurement state machine */
start();
_sensor_ok = false;
return;
}
/* next phase is measurement */
_collect_phase = false;
/*
* Is there a collect->measure gap?
*/
if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) {
/* schedule a fresh cycle call when we are ready to measure again */
work_queue(HPWORK,
&_work,
(worker_t)&Airspeed::cycle_trampoline,
this,
_measure_ticks - USEC2TICK(CONVERSION_INTERVAL));
return;
}
}
/* measurement phase */
ret = measure();
if (OK != ret) {
DEVICE_DEBUG("measure error");
}
_sensor_ok = (ret == OK);
/* next phase is collection */
_collect_phase = true;
/* schedule a fresh cycle call when the measurement is done */
work_queue(HPWORK,
&_work,
(worker_t)&Airspeed::cycle_trampoline,
this,
USEC2TICK(CONVERSION_INTERVAL));
}
/**
* Local functions in support of the shell command.
*/
namespace ft205ev_airspeed
{
FT205EV *g_dev = nullptr;
int start();
int start_bus(int i2c_bus);
int stop();
int reset();
int info();
/**
* Attempt to start driver on all available I2C busses.
*
* This function will return as soon as the first sensor
* is detected on one of the available busses or if no
* sensors are detected.
*
*/
int
start()
{
for (unsigned i = 0; i < NUM_I2C_BUS_OPTIONS; i++) {
if (start_bus(i2c_bus_options[i]) == PX4_OK) {
return PX4_OK;
}
}
return PX4_ERROR;
}
/**
* Start the driver on a specific bus.
*
* This function only returns if the sensor is up and running
* or could not be detected successfully.
*/
int
start_bus(int i2c_bus)
{
int fd;
if (g_dev != nullptr) {
PX4_ERR("already started");
return PX4_ERROR;
}
/* create the driver */
g_dev = new FT205EV(i2c_bus);
if (g_dev == nullptr) {
goto fail;
}
if (OK != g_dev->init()) {
goto fail;
}
/* set the poll rate to default, starts automatic data collection */
fd = px4_open(AIRSPEED0_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
goto fail;
}
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
goto fail;
}
return PX4_OK;
fail:
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
}
return PX4_ERROR;
}
/**
* Stop the driver
*/
int
stop()
{
if (g_dev != nullptr) {
delete g_dev;
g_dev = nullptr;
} else {
PX4_ERR("driver not running");
return PX4_ERROR;
}
return PX4_OK;
}
/**
* Reset the driver.
*/
int
reset()
{
int fd = px4_open(FT205EV_PATH, O_RDONLY);
if (fd < 0) {
PX4_ERR("failed");
return PX4_ERROR;
}
if (px4_ioctl(fd, SENSORIOCRESET, 0) < 0) {
PX4_ERR("driver reset failed");
return PX4_ERROR;
}
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
PX4_ERR("driver poll restart failed");
return PX4_ERROR;
}
return PX4_OK;
}
} // namespace
static void
ft205ev_airspeed_usage()
{
PX4_INFO("usage: ft205ev_airspeed command [options]");
PX4_INFO("options:");
PX4_INFO("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT);
PX4_INFO("\t-a --all");
PX4_INFO("command:");
PX4_INFO("\tstart|stop|reset|info");
}
int
ft205ev_airspeed_main(int argc, char *argv[])
{
int i2c_bus = PX4_I2C_BUS_DEFAULT;
int myoptind = 1;
int ch;
const char *myoptarg = nullptr;
bool start_all = false;
while ((ch = px4_getopt(argc, argv, "ab:", &myoptind, &myoptarg)) != EOF) {
switch (ch) {
case 'b':
i2c_bus = atoi(myoptarg);
break;
case 'a':
start_all = true;
break;
default:
ft205ev_airspeed_usage();
return 0;
}
}
if (myoptind >= argc) {
ft205ev_airspeed_usage();
return -1;
}
/*
* Start/load the driver.
*/
if (!strcmp(argv[myoptind], "start")) {
if (start_all) {
return ft205ev_airspeed::start();
} else {
return ft205ev_airspeed::start_bus(i2c_bus);
}
}
/*
* Stop the driver
*/
if (!strcmp(argv[myoptind], "stop")) {
return ft205ev_airspeed::stop();
}
/*
* Reset the driver.
*/
if (!strcmp(argv[myoptind], "reset")) {
return ft205ev_airspeed::reset();
}
ft205ev_airspeed_usage();
return 0;
}
Also, CMakeLists.txt included in the same folder as ft205ev.cpp is below.
px4_add_module(
MODULE drivers__ft205ev
MAIN ft205ev
STACK_MAIN 1200
COMPILE_FLAGS
SRCS
ft205ev.cpp
DEPENDS
drivers__airspeed
)
Could you tell me what’s wrong with these codes?
Thanks.