Skip to content

Commit

Permalink
Merge fixes from branch 'v3.9'
Browse files Browse the repository at this point in the history
* fix 3d plotting in calibration script to also work with matplotlib versions < 1.0
* turntable airframe files
* baro_bmp module hack to updated fw alt_kalman
* tunable nav_catapult
* logger led colors
  • Loading branch information
flixr committed Jun 12, 2012
2 parents 612c5d1 + 29f6233 commit 6939f14
Show file tree
Hide file tree
Showing 26 changed files with 319 additions and 102 deletions.
12 changes: 6 additions & 6 deletions conf/airframes/ENAC/fixed-wing/weasel.xml
Expand Up @@ -146,14 +146,14 @@
<!-- outer loop proportional gain -->
<define name="ALTITUDE_PGAIN" value="0.159999996424"/> <!-- -0.024 -->
<!-- outer loop saturation -->
<define name="ALTITUDE_MAX_CLIMB" value="5."/>
<define name="ALTITUDE_MAX_CLIMB" value="5." unit="m/s"/>

<!-- Cruise throttle + limits -->
<define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5"/>
<define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.25"/>
<define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.85"/>
<define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(20.)"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-RadOfDeg(20.)"/>
<define name="AUTO_PITCH_MAX_PITCH" value="20." unit="deg"/>
<define name="AUTO_PITCH_MIN_PITCH" value="-20." unit="deg"/>

<!-- Climb loop (throttle) -->
<define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" unit="%/(m/s)"/>
Expand All @@ -175,11 +175,11 @@
<define name="AUTO_AIRSPEED_PITCH_PGAIN" value="0.06"/>
<define name="AUTO_AIRSPEED_PITCH_DGAIN" value="0.0"/>
<define name="AUTO_AIRSPEED_PITCH_IGAIN" value="0.042"/>
<define name="AIRSPEED_MAX" value="30"/>
<define name="AIRSPEED_MIN" value="10"/>
<define name="AIRSPEED_MAX" value="30" unit="m/s"/>
<define name="AIRSPEED_MIN" value="10" unit="m/s"/>

<!-- groundspeed control -->
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15"/>
<define name="AUTO_GROUNDSPEED_SETPOINT" value="15" unit="m/s"/>
<define name="AUTO_GROUNDSPEED_PGAIN" value="1."/>
<define name="AUTO_GROUNDSPEED_IGAIN" value="0."/>

Expand Down
12 changes: 9 additions & 3 deletions conf/airframes/examples/microjet_lisa_m.xml
Expand Up @@ -12,9 +12,11 @@
<target name="sim" board="pc"/>
<target name="ap" board="lisa_m_1.0"/>

<define name="AGR_CLIMB" />
<define name="LOITER_TRIM" />
<define name="ALT_KALMAN" />
<define name="AGR_CLIMB"/>
<define name="LOITER_TRIM"/>
<define name="ALT_KALMAN"/>
<define name="USE_BARO_BMP"/>


<subsystem name="radio_control" type="ppm"/>

Expand All @@ -32,6 +34,10 @@

<modules>
<load name="sys_mon.xml"/>
<load name="baro_bmp.xml">
<define name="BMP_I2C_DEV" value="i2c2"/>
<define name="USE_I2C2"/>
</load>
</modules>

<servos>
Expand Down
@@ -1,4 +1,4 @@
<airframe name="MOTOR_BENCH">
<airframe name="Turntable">

<makefile>
ARCH=lpc21
Expand All @@ -9,6 +9,9 @@ MB=firmwares/motor_bench

main.ARCHDIR = $(ARCH)

# uncomment the next line to set the number of steps the encoder has (default 256)
#main.CFLAGS += -DNB_STEP=256

main.CFLAGS += -DBOARD_CONFIG=\"boards/olimex_lpc_h2148.h\" -I$(MB)
main.CFLAGS += -DPERIPHERALS_AUTO_INIT
main.srcs = $(MB)/main_turntable.c
Expand All @@ -20,24 +23,13 @@ main.CFLAGS += -DUSE_LED
main.CFLAGS += -DPERIODIC_FREQUENCY='512.' -DSYS_TIME_LED=1
main.srcs += mcu_periph/sys_time.c $(MB)/turntable_systime.c

#main.CFLAGS += -DUSE_USB_SERIAL
#main.srcs += $(SRC_ARCH)/usb_ser_hw.c
#main.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c
#main.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c
#main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=UsbS

main.CFLAGS += -DUSE_UART0 -DUART0_BAUD=B115200
main.srcs += mcu_periph/uart.c
main.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=Uart0

main.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c

main.CFLAGS += -DMB_TACHO
main.srcs += $(MB)/mb_tacho.c



</makefile>

</airframe>
36 changes: 36 additions & 0 deletions conf/airframes/turntable_usb.xml
@@ -0,0 +1,36 @@
<airframe name="TurntableUsb">

<makefile>
ARCH=lpc21

FLASH_MODE = IAP

MB=firmwares/motor_bench

main.ARCHDIR = $(ARCH)

# uncomment the next line to set the number of steps the encoder has (default 256)
#main.CFLAGS += -DNB_STEP=256

main.CFLAGS += -DBOARD_CONFIG=\"boards/olimex_lpc_h2148.h\" -I$(MB)
main.CFLAGS += -DPERIPHERALS_AUTO_INIT
main.srcs = $(MB)/main_turntable.c
main.srcs += $(SRC_ARCH)/armVIC.c
main.srcs += mcu.c
main.srcs += $(SRC_ARCH)/mcu_arch.c

main.CFLAGS += -DUSE_LED
main.CFLAGS += -DPERIODIC_FREQUENCY='512.' -DSYS_TIME_LED=1
main.srcs += mcu_periph/sys_time.c $(MB)/turntable_systime.c

main.CFLAGS += -DUSE_USB_SERIAL
main.srcs += $(SRC_ARCH)/usb_ser_hw.c
main.srcs += $(SRC_ARCH)/lpcusb/usbhw_lpc.c $(SRC_ARCH)/lpcusb/usbinit.c
main.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdreq.c
main.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_DEVICE=UsbS

main.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c

</makefile>

</airframe>
7 changes: 5 additions & 2 deletions conf/firmwares/subsystems/fixedwing/ins_xsens.makefile
Expand Up @@ -31,14 +31,17 @@ ifeq ($(TARGET), ap)
# </makefile>

# ImuEvent -> XSensEvent
ap.CFLAGS += -DUSE_AHRS
ap.CFLAGS += -DUSE_AHRS -DUSE_INS
ap.CFLAGS += -DIMU_TYPE_H=\"modules/ins/ins_xsens.h\"

# AHRS Results
ap.CFLAGS += -DAHRS_TYPE_H=\"modules/ins/ins_xsens.h\"
ap.CFLAGS += -DINS_MODULE_H=\"modules/ins/ins_xsens.h\"
ap.CFLAGS += -DAHRS_TYPE_H=\"modules/ins/ins_xsens.h\"
ap.CFLAGS += -DGPS_TYPE_H=\"modules/ins/ins_xsens.h\"

#B230400
#B115200

ap.CFLAGS += -DUSE_UART$(XSENS_UART_NR)
ap.CFLAGS += -DINS_LINK=Uart$(XSENS_UART_NR)
ap.CFLAGS += -DUART$(XSENS_UART_NR)_BAUD=B230400
Expand Down
2 changes: 1 addition & 1 deletion conf/modules/baro_bmp.xml
Expand Up @@ -18,7 +18,7 @@
<init fun="baro_bmp_init()"/>
<periodic fun="baro_bmp_periodic()" freq="8"/>
<event fun="baro_bmp_event()"/>
<makefile target="ap">
<makefile>
<file name="baro_bmp.c"/>
</makefile>
</module>
Expand Down
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
13 changes: 13 additions & 0 deletions conf/settings/control/nav_catapult.xml
@@ -0,0 +1,13 @@
<!DOCTYPE settings SYSTEM "../settings.dtd">

<settings>
<dl_settings name="control">
<dl_settings name="catapult">
<dl_setting max="250" min="1" step="1" module="nav/nav_catapult" var="nav_catapult_motor_delay" shortname="Motor Delay" param="NAV_CATAPULT_MOTOR_DELAY" unit="step" />
<dl_setting max="3.0" min="-3.0" step="0.1" var="nav_catapult_acceleration_threshold" shortname="G-Threshold" param="NAV_CATAPULT_ACCELERATION_THRESHOLD" unit="g" />
<dl_setting max="600" min="15" step="15" var="nav_catapult_heading_delay" shortname="Heading-Delay" param="NAV_CATAPULT_HEADING_DELAY" unit="step" />
<dl_setting max="1.0" min="-0.5" step="0.01" var="nav_catapult_initial_pitch" shortname="TO Pitch" param="NAV_CATAPULT_INITIAL_PITCH" unit="rad" />
<dl_setting max="1.0" min="0.0" step="0.01" var="nav_catapult_initial_throttle" shortname="TO Gas" param="NAV_CATAPULT_INITIAL_THROTTLE" unit="percent" />
</dl_settings>
</dl_settings>
</settings>
10 changes: 7 additions & 3 deletions sw/airborne/estimator.c
Expand Up @@ -113,7 +113,6 @@ bool_t alt_kalman_enabled;
#endif

#define GPS_SIGMA2 1.

#define GPS_DT 0.25
#define GPS_R 2.

Expand Down Expand Up @@ -150,6 +149,12 @@ void alt_kalman(float gps_z) {
R = baro_ets_r;
SIGMA2 = baro_ets_sigma2;
} else
#elif USE_BARO_BMP
if (baro_bmp_enabled) {
DT = BARO_BMP_DT;
R = baro_bmp_r;
SIGMA2 = baro_bmp_sigma2;
} else
#endif
{
DT = GPS_DT;
Expand Down Expand Up @@ -205,7 +210,7 @@ void estimator_update_state_gps( void ) {
gps_north -= nav_utm_north0;

EstimatorSetPosXY(gps_east, gps_north);
#ifndef USE_BARO_ETS
#if !USE_BARO_BMP && !USE_BARO_ETS && !USE_BARO_MS5534A
float falt = gps.hmsl / 1000.;
EstimatorSetAlt(falt);
#endif
Expand All @@ -217,4 +222,3 @@ void estimator_update_state_gps( void ) {
// Heading estimation now in ahrs_infrared

}

6 changes: 5 additions & 1 deletion sw/airborne/estimator.h
Expand Up @@ -40,6 +40,10 @@
#include "modules/sensors/baro_ets.h"
#endif

#if USE_BARO_BMP
#include "modules/sensors/baro_bmp.h"
#endif

/* position in meters, ENU frame, relative to reference */
extern float estimator_x; ///< east position in meters
extern float estimator_y; ///< north position in meters
Expand Down Expand Up @@ -92,7 +96,7 @@ extern void alt_kalman( float );
#ifdef ALT_KALMAN
#define EstimatorSetPosXY(x, y) { estimator_x = x; estimator_y = y; }

#if USE_BARO_MS5534A || USE_BARO_ETS
#if USE_BARO_MS5534A || USE_BARO_ETS || USE_BARO_BMP
/* Kalman filter cannot be disabled in this mode (no z_dot) */
#define EstimatorSetAlt(z) alt_kalman(z)
#else /* USE_BARO_x */
Expand Down
73 changes: 60 additions & 13 deletions sw/airborne/firmwares/logger/main_logger.c
Expand Up @@ -92,6 +92,9 @@
#include "max11040.h"
#endif

#include "LPC21xx.h"


#ifndef FALSE
#define FALSE 0
#endif
Expand Down Expand Up @@ -326,7 +329,7 @@ void log_xbee(unsigned char c, unsigned char source)
#ifndef USE_MAX11040
log_payload(xbeel_payload_len-XBEE_RFDATA_OFFSET, source, xbeel_timestamp);
#endif
LED_TOGGLE(3);
LED_TOGGLE(LED_GREEN);
goto restart;
}
return;
Expand Down Expand Up @@ -380,7 +383,7 @@ void log_pprz(unsigned char c, unsigned char source)
#ifndef USE_MAX11040
log_payload(pprzl_payload_len, source, pprzl_timestamp);
#endif
LED_TOGGLE(3);
LED_TOGGLE(LED_GREEN);
goto restart;
}
return;
Expand Down Expand Up @@ -422,7 +425,7 @@ int do_log(void)
#ifdef USE_MAX11040
if ((max11040_data == MAX11040_DATA_AVAILABLE) &&
(max11040_buf_in != max11040_buf_out)) {
// LED_TOGGLE(3);
// LED_TOGGLE(LED_GREEN);
int i;

max11040_data = MAX11040_IDLE;
Expand Down Expand Up @@ -450,7 +453,7 @@ int do_log(void)
temp = 0;
while (Uart0ChAvailable() && (temp++ < 128))
{
// LED_TOGGLE(3);
// LED_TOGGLE(LED_GREEN);
inc = Uart0Getch();
#ifdef LOG_XBEE
log_xbee(inc, LOG_SOURCE_UART0);
Expand All @@ -467,7 +470,7 @@ int do_log(void)
temp = 0;
while (Uart1ChAvailable() && (temp++ < 128))
{
// LED_TOGGLE(3);
// LED_TOGGLE(LED_GREEN);
inc = Uart1Getch();
#ifdef LOG_XBEE
log_xbee(inc, LOG_SOURCE_UART1);
Expand All @@ -481,7 +484,7 @@ int do_log(void)
}
#endif
}
LED_OFF(3);
LED_OFF(LED_GREEN);

file_fclose( &filew );
fs_umount( &efs.myFs ) ;
Expand Down Expand Up @@ -528,11 +531,52 @@ int main(void)
#endif


#ifdef _DEBUG_BOARD_
while(1)
{
if (IO0PIN & (1 << LOG_STOP_KEY))
{
LED_ON(LED_YELLOW);
}
else
{
LED_OFF(LED_YELLOW);
}

if (IO1PIN & (1 << CARD_DETECT_PIN))
{
LED_OFF(LED_GREEN);
}
else
{
LED_ON(LED_GREEN);
}

if (IO0PIN & (1 << POWER_DETECT_PIN))
// if (IO0PIN & (1 << VBUS_PIN))
{
LED_ON(LED_RED);
}
else
{
LED_OFF(LED_RED);
}
}
#endif

// Direct SD Reader Mode
if ((IO0PIN & _BV(VBUS_PIN))>>VBUS_PIN)
{
LED_OFF(LED_YELLOW);
LED_ON(LED_RED);
main_mass_storage();
}

while(1)
{
LED_ON(2);
LED_ON(LED_YELLOW);
do_log();
LED_OFF(2);
LED_OFF(LED_YELLOW);

waitloop = 0;
ledcount = 0;
Expand All @@ -544,9 +588,9 @@ int main(void)
{
if (ledcount++ > 9) {
ledcount=0;
LED_ON(2);
LED_ON(LED_YELLOW);
} else {
LED_OFF(2);
LED_OFF(LED_YELLOW);
}
if (((IO0PIN & _BV(LOG_STOP_KEY))>>LOG_STOP_KEY) == 1) {
waitloop=0;
Expand All @@ -557,12 +601,12 @@ int main(void)

if ((IO0PIN & _BV(VBUS_PIN))>>VBUS_PIN)
{
LED_OFF(2);
LED_ON(1);
LED_OFF(LED_YELLOW);
LED_ON(LED_RED);
main_mass_storage();
}
}
LED_ON(2);
LED_ON(LED_YELLOW);
while (((IO0PIN & _BV(LOG_STOP_KEY))>>LOG_STOP_KEY) == 0);
}

Expand All @@ -574,12 +618,15 @@ static inline void main_init( void ) {
sys_time_init();
led_init();


#ifdef USE_MAX11040
max11040_init_ssp();
max11040_init();
#endif

mcu_int_enable();

PINSEL2 = ~ (0x0c);
}

static inline void main_periodic_task( void ) {
Expand Down

0 comments on commit 6939f14

Please sign in to comment.