Merge branch 'master' into 6point_accel_calibration

This commit is contained in:
Anton Babushkin 2013-04-28 17:01:44 +04:00
commit 29057cb3bd
29 changed files with 96 additions and 23 deletions

View File

@ -32,6 +32,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.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_v.mix~mixers/FMU_quad_v.mix \
$(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
$(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
$(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \

View File

@ -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

View File

@ -35,8 +35,9 @@ APPNAME = attitude_estimator_ekf
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
CSRCS = attitude_estimator_ekf_main.c \
attitude_estimator_ekf_params.c \
CXXSRCS = attitude_estimator_ekf_main.cpp
CSRCS = attitude_estimator_ekf_params.c \
codegen/eye.c \
codegen/attitudeKalmanfilter.c \
codegen/mrdivide.c \

View File

@ -66,11 +66,17 @@
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#ifdef __cplusplus
extern "C" {
#endif
#include "codegen/attitudeKalmanfilter_initialize.h"
#include "codegen/attitudeKalmanfilter.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_running = false; /**< Deamon status flag */
@ -265,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* Main loop*/
while (!thread_should_exit) {
struct pollfd fds[2] = {
{ .fd = sub_raw, .events = POLLIN },
{ .fd = sub_params, .events = POLLIN }
};
struct pollfd fds[2];
fds[0].fd = sub_raw;
fds[0].events = POLLIN;
fds[1].fd = sub_params;
fds[1].events = POLLIN;
int ret = poll(fds, 2, 1000);
if (ret < 0) {

View File

@ -92,6 +92,7 @@
#include <nuttx/config.h>
#include <arch/board/board.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
@ -841,7 +842,7 @@ int
blinkm_main(int argc, char *argv[])
{
int i2cdevice = 3;
int i2cdevice = PX4_I2C_BUS_EXPANSION;
int blinkmadr = 9;
int x;

View File

@ -125,7 +125,7 @@
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
# 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
#elif HRT_TIMER == 9
# define HRT_TIMER_BASE STM32_TIM9_BASE

View File

@ -494,7 +494,7 @@ ToneAlarm::init()
return ret;
/* configure the GPIO to the idle state */
stm32_configgpio(GPIO_TONE_ALARM);
stm32_configgpio(GPIO_TONE_ALARM_IDLE);
/* clock/power on our timer */
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
rCCER |= TONE_CCER; // enable the output
// configure the GPIO to enable timer output
stm32_configgpio(GPIO_TONE_ALARM);
}
void
@ -616,10 +618,8 @@ ToneAlarm::stop_note()
/*
* 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

View File

@ -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
# modification, are permitted provided that the following conditions
@ -32,7 +32,7 @@
############################################################################
#
# Basic example application
# Full attitude / position Extended Kalman Filter
#
APPNAME = kalman_demo

View File

@ -64,6 +64,8 @@ ROOTDEPPATH = --dep-path .
VPATH =
MAXOPTIMIZATION = -Os
all: .built
.PHONY: clean depend distclean

View File

@ -229,6 +229,13 @@ l_vehicle_gps_position(const struct listener *l)
/* copy gps data into local buffer */
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 */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
gps.timestamp_position,
@ -236,13 +243,14 @@ l_vehicle_gps_position(const struct listener *l)
gps.lat,
gps.lon,
gps.alt,
(uint16_t)(gps.eph_m * 1e2f), // from m to cm
(uint16_t)(gps.epv_m * 1e2f), // from m to cm
(uint16_t)(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
gps.eph_m * 1e2f, // from m to cm
gps.epv_m * 1e2f, // from m to cm
gps.vel_m_s * 1e2f, // from m/s to cm/s
cog_deg * 1e2f, // from rad to deg * 100
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,
gps.satellites_visible,
gps.satellite_prn,

View File

@ -107,6 +107,8 @@ endif
ROOTDEPPATH = --dep-path .
VPATH =
MAXOPTIMIZATION = -Os
# Build targets
all: .built

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 12000
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -64,6 +64,7 @@ VPATH =
APPNAME = i2c
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
MAXOPTIMIZATION = -Os
# Build targets

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_MAX - 1
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT - 10
STACKSIZE = 3000
include $(APPDIR)/mk/app.mk
MAXOPTIMIZATION = -Os

View File

@ -418,6 +418,7 @@ public:
enum Geometry {
QUAD_X = 0, /**< quad in X configuration */
QUAD_PLUS, /**< quad in + configuration */
QUAD_V, /**< quad in V configuration */
HEX_X, /**< hex in X configuration */
HEX_PLUS, /**< hex in + configuration */
OCTA_X,

View File

@ -82,6 +82,12 @@ const MultirotorMixer::Rotor _config_quad_plus[] = {
{ 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[] = {
{ -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] = {
&_config_quad_x[0],
&_config_quad_plus[0],
&_config_quad_v[0],
&_config_hex_x[0],
&_config_hex_plus[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] = {
4, /* quad_x */
4, /* quad_plus */
4, /* quad_v */
6, /* hex_x */
6, /* hex_plus */
8, /* octa_x */
@ -184,6 +192,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "4x")) {
geometry = MultirotorMixer::QUAD_X;
} else if (!strcmp(geomname, "4v")) {
geometry = MultirotorMixer::QUAD_V;
} else if (!strcmp(geomname, "6+")) {
geometry = MultirotorMixer::HEX_PLUS;

View File

@ -20,6 +20,13 @@ set quad_plus {
180 CW
}
set quad_v {
68 CCW
-136 CCW
-68 CW
136 CW
}
set hex_x {
90 CW
-90 CCW
@ -60,7 +67,7 @@ set octa_plus {
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]]}

View File

@ -326,6 +326,7 @@
*/
#define TONE_ALARM_TIMER 3 /* timer 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)
/************************************************************************************

View File

@ -112,7 +112,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
ARCHSCRIPT += -g
endif
ARCHCFLAGS = -std=gnu99
@ -145,7 +144,7 @@ ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
ARCHSCRIPT += --warn-common \
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common