aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-23 23:10:05 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-23 23:10:05 +0100
commitb3d98e4a19662af44432a0436a1b5de7fb9649c9 (patch)
tree3a0c6de54a6d177bfd165d983f8a98d42b8b8926 /src/modules
parent55f845888bece8aaa49ebc2b5e25663b6c8f3f3c (diff)
parent4524fe3e4888d569f855d1e7a82c8d5116636a0a (diff)
downloadpx4-firmware-b3d98e4a19662af44432a0436a1b5de7fb9649c9.tar.gz
px4-firmware-b3d98e4a19662af44432a0436a1b5de7fb9649c9.tar.bz2
px4-firmware-b3d98e4a19662af44432a0436a1b5de7fb9649c9.zip
Merge branch 'master' into beta
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/px4iofirmware/adc.c53
-rw-r--r--src/modules/px4iofirmware/controls.c11
-rw-r--r--src/modules/px4iofirmware/px4io.c55
-rw-r--r--src/modules/px4iofirmware/px4io.h2
-rw-r--r--src/modules/px4iofirmware/safety.c8
5 files changed, 81 insertions, 48 deletions
diff --git a/src/modules/px4iofirmware/adc.c b/src/modules/px4iofirmware/adc.c
index 81566eb2a..2f5908ac5 100644
--- a/src/modules/px4iofirmware/adc.c
+++ b/src/modules/px4iofirmware/adc.c
@@ -83,6 +83,14 @@ adc_init(void)
{
adc_perf = perf_alloc(PC_ELAPSED, "adc");
+ /* put the ADC into power-down mode */
+ rCR2 &= ~ADC_CR2_ADON;
+ up_udelay(10);
+
+ /* bring the ADC out of power-down mode */
+ rCR2 |= ADC_CR2_ADON;
+ up_udelay(10);
+
/* do calibration if supported */
#ifdef ADC_CR2_CAL
rCR2 |= ADC_CR2_RSTCAL;
@@ -96,41 +104,25 @@ adc_init(void)
if (rCR2 & ADC_CR2_CAL)
return -1;
-
#endif
- /* arbitrarily configure all channels for 55 cycle sample time */
- rSMPR1 = 0b00000011011011011011011011011011;
+ /*
+ * Configure sampling time.
+ *
+ * For electrical protection reasons, we want to be able to have
+ * 10K in series with ADC inputs that leave the board. At 12MHz this
+ * means we need 28.5 cycles of sampling time (per table 43 in the
+ * datasheet).
+ */
+ rSMPR1 = 0b00000000011011011011011011011011;
rSMPR2 = 0b00011011011011011011011011011011;
- /* XXX for F2/4, might want to select 12-bit mode? */
- rCR1 = 0;
-
- /* enable the temperature sensor / Vrefint channel if supported*/
- rCR2 =
-#ifdef ADC_CR2_TSVREFE
- /* enable the temperature sensor in CR2 */
- ADC_CR2_TSVREFE |
-#endif
- 0;
-
-#ifdef ADC_CCR_TSVREFE
- /* enable temperature sensor in CCR */
- rCCR = ADC_CCR_TSVREFE;
-#endif
+ rCR2 |= ADC_CR2_TSVREFE; /* enable the temperature sensor / Vrefint channel */
/* configure for a single-channel sequence */
rSQR1 = 0;
rSQR2 = 0;
- rSQR3 = 0; /* will be updated with the channel each tick */
-
- /* power-cycle the ADC and turn it on */
- rCR2 &= ~ADC_CR2_ADON;
- up_udelay(10);
- rCR2 |= ADC_CR2_ADON;
- up_udelay(10);
- rCR2 |= ADC_CR2_ADON;
- up_udelay(10);
+ rSQR3 = 0; /* will be updated with the channel at conversion time */
return 0;
}
@@ -141,11 +133,12 @@ adc_init(void)
uint16_t
adc_measure(unsigned channel)
{
+
perf_begin(adc_perf);
/* clear any previous EOC */
- if (rSR & ADC_SR_EOC)
- rSR &= ~ADC_SR_EOC;
+ rSR = 0;
+ (void)rDR;
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
rSQR3 = channel;
@@ -158,7 +151,6 @@ adc_measure(unsigned channel)
/* never spin forever - this will give a bogus result though */
if (hrt_elapsed_time(&now) > 100) {
- debug("adc timeout");
perf_end(adc_perf);
return 0xffff;
}
@@ -166,6 +158,7 @@ adc_measure(unsigned channel)
/* read the result and clear EOC */
uint16_t result = rDR;
+ rSR = 0;
perf_end(adc_perf);
return result;
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 541eed0e1..5e2c92bf4 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -114,9 +114,20 @@ controls_tick() {
perf_begin(c_gather_sbus);
bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &rssi, PX4IO_RC_INPUT_CHANNELS);
+
+ bool sbus_status = (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_SBUS);
+
if (sbus_updated) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
}
+
+ /* switch S.Bus output pin as needed */
+ if (sbus_status != (r_status_flags & PX4IO_P_STATUS_FLAGS_RC_SBUS)) {
+ #ifdef ENABLE_SBUS_OUT
+ ENABLE_SBUS_OUT((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_SBUS));
+ #endif
+ }
+
perf_end(c_gather_sbus);
/*
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index 0b8c4a6a8..e2da35939 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2014 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
@@ -196,6 +196,11 @@ user_start(int argc, char *argv[])
POWER_SERVO(true);
#endif
+ /* turn off S.Bus out (if supported) */
+#ifdef ENABLE_SBUS_OUT
+ ENABLE_SBUS_OUT(false);
+#endif
+
/* start the safety switch handler */
safety_init();
@@ -205,6 +210,9 @@ user_start(int argc, char *argv[])
/* initialise the control inputs */
controls_init();
+ /* set up the ADC */
+ adc_init();
+
/* start the FMU interface */
interface_init();
@@ -223,24 +231,41 @@ user_start(int argc, char *argv[])
/* initialize PWM limit lib */
pwm_limit_init(&pwm_limit);
-#if 0
- /* not enough memory, lock down */
- if (minfo.mxordblk < 500) {
+ /*
+ * P O L I C E L I G H T S
+ *
+ * Not enough memory, lock down.
+ *
+ * We might need to allocate mixers later, and this will
+ * ensure that a developer doing a change will notice
+ * that he just burned the remaining RAM with static
+ * allocations. We don't want him to be able to
+ * get past that point. This needs to be clearly
+ * documented in the dev guide.
+ *
+ */
+ if (minfo.mxordblk < 600) {
+
lowsyslog("ERR: not enough MEM");
bool phase = false;
- if (phase) {
- LED_AMBER(true);
- LED_BLUE(false);
- } else {
- LED_AMBER(false);
- LED_BLUE(true);
- }
+ while (true) {
+
+ if (phase) {
+ LED_AMBER(true);
+ LED_BLUE(false);
+ } else {
+ LED_AMBER(false);
+ LED_BLUE(true);
+ }
+ up_udelay(250000);
- phase = !phase;
- usleep(300000);
+ phase = !phase;
+ }
}
-#endif
+
+ /* Start the failsafe led init */
+ failsafe_led_init();
/*
* Run everything in a tight loop.
@@ -270,7 +295,6 @@ user_start(int argc, char *argv[])
check_reboot();
-#if 0
/* check for debug activity */
show_debug_messages();
@@ -287,7 +311,6 @@ user_start(int argc, char *argv[])
(unsigned)minfo.mxordblk);
last_debug_time = hrt_absolute_time();
}
-#endif
}
}
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index a0daa97ea..bffbc0ce2 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -160,6 +160,7 @@ extern pwm_limit_t pwm_limit;
# define PX4IO_RELAY_CHANNELS 0
# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s))
+# define ENABLE_SBUS_OUT(_s) stm32_gpiowrite(GPIO_SBUS_OENABLE, !(_s))
# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT))
@@ -183,6 +184,7 @@ extern void mixer_handle_text(const void *buffer, size_t length);
* Safety switch/LED.
*/
extern void safety_init(void);
+extern void failsafe_led_init(void);
/**
* FMU communications
diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c
index 83bd3026e..ff2e4af6e 100644
--- a/src/modules/px4iofirmware/safety.c
+++ b/src/modules/px4iofirmware/safety.c
@@ -83,7 +83,11 @@ safety_init(void)
{
/* arrange for the button handler to be called at 10Hz */
hrt_call_every(&arming_call, 1000, 100000, safety_check_button, NULL);
+}
+void
+failsafe_led_init(void)
+{
/* arrange for the failsafe blinker to be called at 8Hz */
hrt_call_every(&failsafe_call, 1000, 125000, failsafe_blink, NULL);
}
@@ -164,8 +168,8 @@ failsafe_blink(void *arg)
/* indicate that a serious initialisation error occured */
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)) {
LED_AMBER(true);
- return;
- }
+ return;
+ }
static bool failsafe = false;