forked from Archive/PX4-Autopilot
Merge branch 'master' into 6point_accel_calibration
This commit is contained in:
commit
29057cb3bd
|
@ -32,6 +32,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
|
||||||
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
|
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
|
||||||
$(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \
|
$(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \
|
||||||
$(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \
|
$(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \
|
||||||
|
$(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \
|
||||||
$(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
|
$(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
|
||||||
$(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
|
$(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
|
||||||
$(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \
|
$(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \
|
||||||
|
|
|
@ -0,0 +1,7 @@
|
||||||
|
Multirotor mixer for PX4FMU
|
||||||
|
===========================
|
||||||
|
|
||||||
|
This file defines a single mixer for a quadrotor in the V configuration. All controls
|
||||||
|
are mixed 100%.
|
||||||
|
|
||||||
|
R: 4v 10000 10000 10000 0
|
|
@ -35,8 +35,9 @@ APPNAME = attitude_estimator_ekf
|
||||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
CSRCS = attitude_estimator_ekf_main.c \
|
CXXSRCS = attitude_estimator_ekf_main.cpp
|
||||||
attitude_estimator_ekf_params.c \
|
|
||||||
|
CSRCS = attitude_estimator_ekf_params.c \
|
||||||
codegen/eye.c \
|
codegen/eye.c \
|
||||||
codegen/attitudeKalmanfilter.c \
|
codegen/attitudeKalmanfilter.c \
|
||||||
codegen/mrdivide.c \
|
codegen/mrdivide.c \
|
||||||
|
|
|
@ -66,11 +66,17 @@
|
||||||
#include <systemlib/perf_counter.h>
|
#include <systemlib/perf_counter.h>
|
||||||
#include <systemlib/err.h>
|
#include <systemlib/err.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
#include "codegen/attitudeKalmanfilter_initialize.h"
|
#include "codegen/attitudeKalmanfilter_initialize.h"
|
||||||
#include "codegen/attitudeKalmanfilter.h"
|
#include "codegen/attitudeKalmanfilter.h"
|
||||||
#include "attitude_estimator_ekf_params.h"
|
#include "attitude_estimator_ekf_params.h"
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
__EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
extern "C" __EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||||
|
|
||||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||||
static bool thread_running = false; /**< Deamon status flag */
|
static bool thread_running = false; /**< Deamon status flag */
|
||||||
|
@ -265,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||||
/* Main loop*/
|
/* Main loop*/
|
||||||
while (!thread_should_exit) {
|
while (!thread_should_exit) {
|
||||||
|
|
||||||
struct pollfd fds[2] = {
|
struct pollfd fds[2];
|
||||||
{ .fd = sub_raw, .events = POLLIN },
|
fds[0].fd = sub_raw;
|
||||||
{ .fd = sub_params, .events = POLLIN }
|
fds[0].events = POLLIN;
|
||||||
};
|
fds[1].fd = sub_params;
|
||||||
|
fds[1].events = POLLIN;
|
||||||
int ret = poll(fds, 2, 1000);
|
int ret = poll(fds, 2, 1000);
|
||||||
|
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
|
@ -92,6 +92,7 @@
|
||||||
|
|
||||||
#include <nuttx/config.h>
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
#include <drivers/device/i2c.h>
|
#include <drivers/device/i2c.h>
|
||||||
|
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
|
@ -841,7 +842,7 @@ int
|
||||||
blinkm_main(int argc, char *argv[])
|
blinkm_main(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
|
|
||||||
int i2cdevice = 3;
|
int i2cdevice = PX4_I2C_BUS_EXPANSION;
|
||||||
int blinkmadr = 9;
|
int blinkmadr = 9;
|
||||||
|
|
||||||
int x;
|
int x;
|
||||||
|
|
|
@ -125,7 +125,7 @@
|
||||||
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
|
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
|
||||||
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
|
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
|
||||||
# if CONFIG_STM32_TIM8
|
# if CONFIG_STM32_TIM8
|
||||||
# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
|
# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=8
|
||||||
# endif
|
# endif
|
||||||
#elif HRT_TIMER == 9
|
#elif HRT_TIMER == 9
|
||||||
# define HRT_TIMER_BASE STM32_TIM9_BASE
|
# define HRT_TIMER_BASE STM32_TIM9_BASE
|
||||||
|
|
|
@ -494,7 +494,7 @@ ToneAlarm::init()
|
||||||
return ret;
|
return ret;
|
||||||
|
|
||||||
/* configure the GPIO to the idle state */
|
/* configure the GPIO to the idle state */
|
||||||
stm32_configgpio(GPIO_TONE_ALARM);
|
stm32_configgpio(GPIO_TONE_ALARM_IDLE);
|
||||||
|
|
||||||
/* clock/power on our timer */
|
/* clock/power on our timer */
|
||||||
modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
|
modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
|
||||||
|
@ -606,6 +606,8 @@ ToneAlarm::start_note(unsigned note)
|
||||||
rEGR = GTIM_EGR_UG; // force a reload of the period
|
rEGR = GTIM_EGR_UG; // force a reload of the period
|
||||||
rCCER |= TONE_CCER; // enable the output
|
rCCER |= TONE_CCER; // enable the output
|
||||||
|
|
||||||
|
// configure the GPIO to enable timer output
|
||||||
|
stm32_configgpio(GPIO_TONE_ALARM);
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
@ -616,10 +618,8 @@ ToneAlarm::stop_note()
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Make sure the GPIO is not driving the speaker.
|
* Make sure the GPIO is not driving the speaker.
|
||||||
*
|
|
||||||
* XXX this presumes PX4FMU and the onboard speaker driver FET.
|
|
||||||
*/
|
*/
|
||||||
stm32_gpiowrite(GPIO_TONE_ALARM, 0);
|
stm32_configgpio(GPIO_TONE_ALARM_IDLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
#
|
#
|
||||||
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||||
#
|
#
|
||||||
# Redistribution and use in source and binary forms, with or without
|
# Redistribution and use in source and binary forms, with or without
|
||||||
# modification, are permitted provided that the following conditions
|
# modification, are permitted provided that the following conditions
|
||||||
|
@ -32,7 +32,7 @@
|
||||||
############################################################################
|
############################################################################
|
||||||
|
|
||||||
#
|
#
|
||||||
# Basic example application
|
# Full attitude / position Extended Kalman Filter
|
||||||
#
|
#
|
||||||
|
|
||||||
APPNAME = kalman_demo
|
APPNAME = kalman_demo
|
||||||
|
|
|
@ -64,6 +64,8 @@ ROOTDEPPATH = --dep-path .
|
||||||
|
|
||||||
VPATH =
|
VPATH =
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
||||||
all: .built
|
all: .built
|
||||||
.PHONY: clean depend distclean
|
.PHONY: clean depend distclean
|
||||||
|
|
||||||
|
|
|
@ -229,6 +229,13 @@ l_vehicle_gps_position(const struct listener *l)
|
||||||
/* copy gps data into local buffer */
|
/* copy gps data into local buffer */
|
||||||
orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps);
|
orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps);
|
||||||
|
|
||||||
|
/* GPS COG is 0..2PI in degrees * 1e2 */
|
||||||
|
float cog_deg = gps.cog_rad;
|
||||||
|
if (cog_deg > M_PI_F)
|
||||||
|
cog_deg -= 2.0f * M_PI_F;
|
||||||
|
cog_deg *= M_RAD_TO_DEG_F;
|
||||||
|
|
||||||
|
|
||||||
/* GPS position */
|
/* GPS position */
|
||||||
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
|
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
|
||||||
gps.timestamp_position,
|
gps.timestamp_position,
|
||||||
|
@ -236,13 +243,14 @@ l_vehicle_gps_position(const struct listener *l)
|
||||||
gps.lat,
|
gps.lat,
|
||||||
gps.lon,
|
gps.lon,
|
||||||
gps.alt,
|
gps.alt,
|
||||||
(uint16_t)(gps.eph_m * 1e2f), // from m to cm
|
gps.eph_m * 1e2f, // from m to cm
|
||||||
(uint16_t)(gps.epv_m * 1e2f), // from m to cm
|
gps.epv_m * 1e2f, // from m to cm
|
||||||
(uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s
|
gps.vel_m_s * 1e2f, // from m/s to cm/s
|
||||||
(uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100
|
cog_deg * 1e2f, // from rad to deg * 100
|
||||||
gps.satellites_visible);
|
gps.satellites_visible);
|
||||||
|
|
||||||
if (gps.satellite_info_available && (gps_counter % 4 == 0)) {
|
/* update SAT info every 10 seconds */
|
||||||
|
if (gps.satellite_info_available && (gps_counter % 50 == 0)) {
|
||||||
mavlink_msg_gps_status_send(MAVLINK_COMM_0,
|
mavlink_msg_gps_status_send(MAVLINK_COMM_0,
|
||||||
gps.satellites_visible,
|
gps.satellites_visible,
|
||||||
gps.satellite_prn,
|
gps.satellite_prn,
|
||||||
|
|
|
@ -107,6 +107,8 @@ endif
|
||||||
ROOTDEPPATH = --dep-path .
|
ROOTDEPPATH = --dep-path .
|
||||||
VPATH =
|
VPATH =
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
||||||
# Build targets
|
# Build targets
|
||||||
|
|
||||||
all: .built
|
all: .built
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 12000
|
STACKSIZE = 12000
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -64,6 +64,7 @@ VPATH =
|
||||||
APPNAME = i2c
|
APPNAME = i2c
|
||||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
||||||
# Build targets
|
# Build targets
|
||||||
|
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 4096
|
STACKSIZE = 4096
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_MAX - 1
|
||||||
STACKSIZE = 4096
|
STACKSIZE = 4096
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 4096
|
STACKSIZE = 4096
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 4096
|
STACKSIZE = 4096
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 4096
|
STACKSIZE = 4096
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||||
STACKSIZE = 2048
|
STACKSIZE = 2048
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT - 10
|
||||||
STACKSIZE = 3000
|
STACKSIZE = 3000
|
||||||
|
|
||||||
include $(APPDIR)/mk/app.mk
|
include $(APPDIR)/mk/app.mk
|
||||||
|
|
||||||
|
MAXOPTIMIZATION = -Os
|
||||||
|
|
|
@ -418,6 +418,7 @@ public:
|
||||||
enum Geometry {
|
enum Geometry {
|
||||||
QUAD_X = 0, /**< quad in X configuration */
|
QUAD_X = 0, /**< quad in X configuration */
|
||||||
QUAD_PLUS, /**< quad in + configuration */
|
QUAD_PLUS, /**< quad in + configuration */
|
||||||
|
QUAD_V, /**< quad in V configuration */
|
||||||
HEX_X, /**< hex in X configuration */
|
HEX_X, /**< hex in X configuration */
|
||||||
HEX_PLUS, /**< hex in + configuration */
|
HEX_PLUS, /**< hex in + configuration */
|
||||||
OCTA_X,
|
OCTA_X,
|
||||||
|
|
|
@ -82,6 +82,12 @@ const MultirotorMixer::Rotor _config_quad_plus[] = {
|
||||||
{ 0.000000, 1.000000, -1.00 },
|
{ 0.000000, 1.000000, -1.00 },
|
||||||
{ -0.000000, -1.000000, -1.00 },
|
{ -0.000000, -1.000000, -1.00 },
|
||||||
};
|
};
|
||||||
|
const MultirotorMixer::Rotor _config_quad_v[] = {
|
||||||
|
{ -0.927184, 0.374607, 1.00 },
|
||||||
|
{ 0.694658, -0.719340, 1.00 },
|
||||||
|
{ 0.927184, 0.374607, -1.00 },
|
||||||
|
{ -0.694658, -0.719340, -1.00 },
|
||||||
|
};
|
||||||
const MultirotorMixer::Rotor _config_hex_x[] = {
|
const MultirotorMixer::Rotor _config_hex_x[] = {
|
||||||
{ -1.000000, 0.000000, -1.00 },
|
{ -1.000000, 0.000000, -1.00 },
|
||||||
{ 1.000000, 0.000000, 1.00 },
|
{ 1.000000, 0.000000, 1.00 },
|
||||||
|
@ -121,6 +127,7 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
|
||||||
const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
||||||
&_config_quad_x[0],
|
&_config_quad_x[0],
|
||||||
&_config_quad_plus[0],
|
&_config_quad_plus[0],
|
||||||
|
&_config_quad_v[0],
|
||||||
&_config_hex_x[0],
|
&_config_hex_x[0],
|
||||||
&_config_hex_plus[0],
|
&_config_hex_plus[0],
|
||||||
&_config_octa_x[0],
|
&_config_octa_x[0],
|
||||||
|
@ -129,6 +136,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME
|
||||||
const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
||||||
4, /* quad_x */
|
4, /* quad_x */
|
||||||
4, /* quad_plus */
|
4, /* quad_plus */
|
||||||
|
4, /* quad_v */
|
||||||
6, /* hex_x */
|
6, /* hex_x */
|
||||||
6, /* hex_plus */
|
6, /* hex_plus */
|
||||||
8, /* octa_x */
|
8, /* octa_x */
|
||||||
|
@ -184,6 +192,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
|
||||||
} else if (!strcmp(geomname, "4x")) {
|
} else if (!strcmp(geomname, "4x")) {
|
||||||
geometry = MultirotorMixer::QUAD_X;
|
geometry = MultirotorMixer::QUAD_X;
|
||||||
|
|
||||||
|
} else if (!strcmp(geomname, "4v")) {
|
||||||
|
geometry = MultirotorMixer::QUAD_V;
|
||||||
|
|
||||||
} else if (!strcmp(geomname, "6+")) {
|
} else if (!strcmp(geomname, "6+")) {
|
||||||
geometry = MultirotorMixer::HEX_PLUS;
|
geometry = MultirotorMixer::HEX_PLUS;
|
||||||
|
|
||||||
|
|
|
@ -20,6 +20,13 @@ set quad_plus {
|
||||||
180 CW
|
180 CW
|
||||||
}
|
}
|
||||||
|
|
||||||
|
set quad_v {
|
||||||
|
68 CCW
|
||||||
|
-136 CCW
|
||||||
|
-68 CW
|
||||||
|
136 CW
|
||||||
|
}
|
||||||
|
|
||||||
set hex_x {
|
set hex_x {
|
||||||
90 CW
|
90 CW
|
||||||
-90 CCW
|
-90 CCW
|
||||||
|
@ -60,7 +67,7 @@ set octa_plus {
|
||||||
90 CW
|
90 CW
|
||||||
}
|
}
|
||||||
|
|
||||||
set tables {quad_x quad_plus hex_x hex_plus octa_x octa_plus}
|
set tables {quad_x quad_plus quad_v hex_x hex_plus octa_x octa_plus}
|
||||||
|
|
||||||
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
|
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
|
||||||
|
|
||||||
|
|
|
@ -326,6 +326,7 @@
|
||||||
*/
|
*/
|
||||||
#define TONE_ALARM_TIMER 3 /* timer 3 */
|
#define TONE_ALARM_TIMER 3 /* timer 3 */
|
||||||
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
|
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
|
||||||
|
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
|
||||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
|
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
|
||||||
|
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
|
|
|
@ -112,7 +112,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||||
|
|
||||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
||||||
ARCHOPTIMIZATION += -g
|
ARCHOPTIMIZATION += -g
|
||||||
ARCHSCRIPT += -g
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ARCHCFLAGS = -std=gnu99
|
ARCHCFLAGS = -std=gnu99
|
||||||
|
@ -145,7 +144,7 @@ ARCHDEFINES =
|
||||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
||||||
|
|
||||||
# this seems to be the only way to add linker flags
|
# this seems to be the only way to add linker flags
|
||||||
ARCHSCRIPT += --warn-common \
|
EXTRA_LIBS += --warn-common \
|
||||||
--gc-sections
|
--gc-sections
|
||||||
|
|
||||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
||||||
|
|
Loading…
Reference in New Issue