aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-02-09 16:04:32 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-02-09 16:04:32 +0100
commit773f70a9df376745523bf78f29d6747c8878c01d (patch)
treef63d9f6c2d4bb3bb3018b230ae9f42f89ff85c7a /src/modules
parentac326beaaae7b38d65ad6d7d13f00dfeaa6ae520 (diff)
parentf52f15c7914983ea1569e584e516d53d21cdde56 (diff)
downloadpx4-firmware-773f70a9df376745523bf78f29d6747c8878c01d.tar.gz
px4-firmware-773f70a9df376745523bf78f29d6747c8878c01d.tar.bz2
px4-firmware-773f70a9df376745523bf78f29d6747c8878c01d.zip
Merged origin/master into pubsub_cleanup
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp112
-rw-r--r--src/modules/commander/commander_helper.cpp7
-rw-r--r--src/modules/commander/commander_helper.h3
-rw-r--r--src/modules/commander/rc_calibration.cpp11
-rw-r--r--src/modules/commander/rc_calibration.h2
-rw-r--r--src/modules/mavlink/orb_listener.c4
-rw-r--r--src/modules/px4iofirmware/adc.c53
-rw-r--r--src/modules/px4iofirmware/controls.c242
-rw-r--r--src/modules/px4iofirmware/mixer.cpp45
-rw-r--r--src/modules/px4iofirmware/protocol.h20
-rw-r--r--src/modules/px4iofirmware/px4io.c61
-rw-r--r--src/modules/px4iofirmware/px4io.h14
-rw-r--r--src/modules/px4iofirmware/registers.c71
-rw-r--r--src/modules/px4iofirmware/safety.c9
-rw-r--r--src/modules/px4iofirmware/sbus.c48
-rw-r--r--src/modules/sdlog2/sdlog2.c282
-rw-r--r--src/modules/sdlog2/sdlog2_version.h62
-rw-r--r--src/modules/sensors/sensor_params.c63
-rw-r--r--src/modules/sensors/sensors.cpp40
-rw-r--r--src/modules/systemlib/cpuload.c3
-rw-r--r--src/modules/systemlib/cpuload.h12
-rw-r--r--src/modules/systemlib/module.mk3
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c114
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.h20
-rw-r--r--src/modules/uORB/topics/vehicle_status.h1
25 files changed, 826 insertions, 476 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index add7312de..54219a34a 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -154,6 +154,16 @@ static bool on_usb_power = false;
static float takeoff_alt = 5.0f;
+static struct vehicle_status_s status;
+
+/* armed topic */
+static struct actuator_armed_s armed;
+
+static struct safety_s safety;
+
+/* flags for control apps */
+struct vehicle_control_mode_s control_mode;
+
/* tasks waiting for low prio thread */
typedef enum {
LOW_PRIO_TASK_NONE = 0,
@@ -204,12 +214,15 @@ void check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicl
transition_result_t check_main_state_machine(struct vehicle_status_s *current_status);
-void print_reject_mode(const char *msg);
+void print_reject_mode(struct vehicle_status_s *current_status, const char *msg);
void print_reject_arm(const char *msg);
void print_status();
+int arm();
+int disarm();
+
transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
/**
@@ -277,6 +290,16 @@ int commander_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "arm")) {
+ arm();
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "disarm")) {
+ disarm();
+ exit(0);
+ }
+
usage("unrecognized command");
exit(1);
}
@@ -344,6 +367,30 @@ void print_status()
static orb_advert_t control_mode_pub;
static orb_advert_t status_pub;
+int arm()
+{
+ int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_ARMED, &armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
+ return 0;
+ } else {
+ return 1;
+ }
+}
+
+int disarm()
+{
+ int arming_res = arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by commandline");
+ return 0;
+ } else {
+ return 1;
+ }
+}
+
void handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_control_mode_s *control_mode, struct vehicle_command_s *cmd, struct actuator_armed_s *armed)
{
/* result of the command */
@@ -537,16 +584,6 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
-static struct vehicle_status_s status;
-
-/* armed topic */
-static struct actuator_armed_s armed;
-
-static struct safety_s safety;
-
-/* flags for control apps */
-struct vehicle_control_mode_s control_mode;
-
int commander_thread_main(int argc, char *argv[])
{
/* not yet initialized */
@@ -583,6 +620,8 @@ int commander_thread_main(int argc, char *argv[])
/* make sure we are in preflight state */
memset(&status, 0, sizeof(status));
status.condition_landed = true; // initialize to safe value
+ // We want to accept RC inputs as default
+ status.rc_input_blocked = false;
/* armed topic */
orb_advert_t armed_pub;
@@ -1039,7 +1078,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* ignore RC signals if in offboard control mode */
- if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0) {
+ if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0 && !status.rc_input_blocked) {
/* start RC input check */
if (hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
/* handle the case where RC signal was regained */
@@ -1366,7 +1405,7 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
{
/* main mode switch */
if (!isfinite(sp_man->mode_switch)) {
- warnx("mode sw not finite");
+ /* default to manual if signal is invalid */
current_status->mode_switch = MODE_SWITCH_MANUAL;
} else if (sp_man->mode_switch > STICK_ON_OFF_LIMIT) {
@@ -1433,7 +1472,7 @@ check_main_state_machine(struct vehicle_status_s *current_status)
break; // changed successfully or already in this state
// else fallback to SEATBELT
- print_reject_mode("EASY");
+ print_reject_mode(current_status, "EASY");
}
res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
@@ -1442,7 +1481,7 @@ check_main_state_machine(struct vehicle_status_s *current_status)
break; // changed successfully or already in this mode
if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages
- print_reject_mode("SEATBELT");
+ print_reject_mode(current_status, "SEATBELT");
// else fallback to MANUAL
res = main_state_transition(current_status, MAIN_STATE_MANUAL);
@@ -1456,7 +1495,7 @@ check_main_state_machine(struct vehicle_status_s *current_status)
break; // changed successfully or already in this state
// else fallback to SEATBELT (EASY likely will not work too)
- print_reject_mode("AUTO");
+ print_reject_mode(current_status, "AUTO");
res = main_state_transition(current_status, MAIN_STATE_SEATBELT);
if (res != TRANSITION_DENIED)
@@ -1475,16 +1514,25 @@ check_main_state_machine(struct vehicle_status_s *current_status)
}
void
-print_reject_mode(const char *msg)
+print_reject_mode(struct vehicle_status_s *current_status, const char *msg)
{
hrt_abstime t = hrt_absolute_time();
if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
last_print_mode_reject_time = t;
char s[80];
- sprintf(s, "#audio: warning: reject %s", msg);
+ sprintf(s, "#audio: REJECT %s", msg);
mavlink_log_critical(mavlink_fd, s);
- tune_negative();
+
+ // only buzz if armed, because else we're driving people nuts indoors
+ // they really need to look at the leds as well.
+ if (current_status->arming_state == ARMING_STATE_ARMED) {
+ tune_negative();
+ } else {
+
+ // Always show the led indication
+ led_negative();
+ }
}
}
@@ -1758,7 +1806,15 @@ void *commander_low_prio_loop(void *arg)
} else if ((int)(cmd.param4) == 1) {
/* RC calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
- calib_ret = do_rc_calibration(mavlink_fd);
+ /* disable RC control input completely */
+ status.rc_input_blocked = true;
+ calib_ret = OK;
+ mavlink_log_info(mavlink_fd, "CAL: Disabling RC IN");
+
+ } else if ((int)(cmd.param4) == 2) {
+ /* RC trim calibration */
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ calib_ret = do_trim_calibration(mavlink_fd);
} else if ((int)(cmd.param5) == 1) {
/* accelerometer calibration */
@@ -1769,6 +1825,18 @@ void *commander_low_prio_loop(void *arg)
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+ } else if ((int)(cmd.param4) == 0) {
+ /* RC calibration ended - have we been in one worth confirming? */
+ if (status.rc_input_blocked) {
+ answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
+ /* enable RC control input */
+ status.rc_input_blocked = false;
+ mavlink_log_info(mavlink_fd, "CAL: Re-enabling RC IN");
+ }
+
+ /* this always succeeds */
+ calib_ret = OK;
+
}
if (calib_ret == OK)
@@ -1827,6 +1895,10 @@ void *commander_low_prio_loop(void *arg)
break;
}
+ case VEHICLE_CMD_START_RX_PAIR:
+ /* handled in the IO driver */
+ break;
+
default:
answer_command(cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 21a1c4c2c..033e7dc88 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -124,10 +124,15 @@ void tune_neutral()
void tune_negative()
{
+ led_negative();
+ ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
+}
+
+void led_negative()
+{
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_RED);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
- ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
}
int tune_arm()
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
index d0393f45a..af25a5e97 100644
--- a/src/modules/commander/commander_helper.h
+++ b/src/modules/commander/commander_helper.h
@@ -62,6 +62,9 @@ int tune_arm(void);
int tune_low_bat(void);
int tune_critical_bat(void);
void tune_stop(void);
+
+void led_negative();
+
int blink_msg_state();
int led_init(void);
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 90ede499a..41f3ca0aa 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -53,17 +53,16 @@
#endif
static const int ERROR = -1;
-int do_rc_calibration(int mavlink_fd)
+int do_trim_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "trim calibration starting");
-
int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint));
+ usleep(200000);
struct manual_control_setpoint_s sp;
bool changed;
orb_check(sub_man, &changed);
if (!changed) {
- mavlink_log_critical(mavlink_fd, "no manual control, aborting");
+ mavlink_log_critical(mavlink_fd, "no inputs, aborting");
return ERROR;
}
@@ -82,12 +81,12 @@ int do_rc_calibration(int mavlink_fd)
int save_ret = param_save_default();
if (save_ret != 0) {
- mavlink_log_critical(mavlink_fd, "TRIM CAL: WARN: auto-save of params failed");
+ mavlink_log_critical(mavlink_fd, "TRIM: SAVE FAIL");
close(sub_man);
return ERROR;
}
- mavlink_log_info(mavlink_fd, "trim calibration done");
+ mavlink_log_info(mavlink_fd, "trim cal done");
close(sub_man);
return OK;
}
diff --git a/src/modules/commander/rc_calibration.h b/src/modules/commander/rc_calibration.h
index 9aa6faafa..45efedf55 100644
--- a/src/modules/commander/rc_calibration.h
+++ b/src/modules/commander/rc_calibration.h
@@ -41,6 +41,6 @@
#include <stdint.h>
-int do_rc_calibration(int mavlink_fd);
+int do_trim_calibration(int mavlink_fd);
#endif /* RC_CALIBRATION_H_ */
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 92b1b45be..e1dabfd21 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -352,10 +352,10 @@ l_input_rc(const struct listener *l)
const unsigned port_width = 8;
- for (unsigned i = 0; (i * port_width) < (rc_raw.channel_count + port_width); i++) {
+ for (unsigned i = 0; (i * port_width) < rc_raw.channel_count; i++) {
/* Channels are sent in MAVLink main loop at a fixed interval */
mavlink_msg_rc_channels_raw_send(chan,
- rc_raw.timestamp / 1000,
+ rc_raw.timestamp_publication / 1000,
i,
(rc_raw.channel_count > (i * port_width) + 0) ? rc_raw.values[(i * port_width) + 0] : UINT16_MAX,
(rc_raw.channel_count > (i * port_width) + 1) ? rc_raw.values[(i * port_width) + 1] : UINT16_MAX,
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..941500f0d 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.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
@@ -59,6 +59,11 @@ static perf_counter_t c_gather_ppm;
void
controls_init(void)
{
+ /* no channels */
+ r_raw_rc_count = 0;
+ system_state.rc_channels_timestamp_received = 0;
+ system_state.rc_channels_timestamp_valid = 0;
+
/* DSM input (USART1) */
dsm_init("/dev/ttyS0");
@@ -97,26 +102,64 @@ controls_tick() {
/* receive signal strenght indicator (RSSI). 0 = no connection, 255: perfect connection */
uint16_t rssi = 0;
+#ifdef ADC_RSSI
+ if (r_setup_features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) {
+ unsigned counts = adc_measure(ADC_RSSI);
+ if (counts != 0xffff) {
+ /* use 1:1 scaling on 3.3V ADC input */
+ unsigned mV = counts * 3300 / 4096;
+
+ /* scale to 0..253 */
+ rssi = mV / 13;
+ }
+ }
+#endif
+
perf_begin(c_gather_dsm);
uint16_t temp_count = r_raw_rc_count;
bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count);
if (dsm_updated) {
- r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
+ r_raw_rc_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
r_raw_rc_count = temp_count & 0x7fff;
if (temp_count & 0x8000)
- r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11;
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
else
- r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
+ r_raw_rc_flags &= ~PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
+
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
- rssi = 255;
}
perf_end(c_gather_dsm);
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);
+
+ bool sbus_failsafe, sbus_frame_drop;
+ bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &sbus_failsafe, &sbus_frame_drop, PX4IO_RC_INPUT_CHANNELS);
+
if (sbus_updated) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
+
+ rssi = 255;
+
+ if (sbus_frame_drop) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FRAME_DROP;
+ rssi = 100;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ }
+
+ if (sbus_failsafe) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_FAILSAFE;
+ rssi = 0;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ }
+
}
+
perf_end(c_gather_sbus);
/*
@@ -125,13 +168,12 @@ controls_tick() {
* disable the PPM decoder completely if we have S.bus signal.
*/
perf_begin(c_gather_ppm);
- bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_status[PX4IO_P_STATUS_RC_DATA]);
+ bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_raw_rc_input[PX4IO_P_RAW_RC_DATA]);
if (ppm_updated) {
- /* XXX sample RSSI properly here */
- rssi = 255;
-
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
}
perf_end(c_gather_ppm);
@@ -139,6 +181,9 @@ controls_tick() {
if (r_raw_rc_count > PX4IO_RC_INPUT_CHANNELS)
r_raw_rc_count = PX4IO_RC_INPUT_CHANNELS;
+ /* store RSSI */
+ r_page_raw_rc_input[PX4IO_P_RAW_RC_NRSSI] = rssi;
+
/*
* In some cases we may have received a frame, but input has still
* been lost.
@@ -150,97 +195,100 @@ controls_tick() {
*/
if (dsm_updated || sbus_updated || ppm_updated) {
- /* update RC-received timestamp */
- system_state.rc_channels_timestamp = hrt_absolute_time();
-
/* record a bitmask of channels assigned */
unsigned assigned_channels = 0;
- /* map raw inputs to mapped inputs */
- /* XXX mapping should be atomic relative to protocol */
- for (unsigned i = 0; i < r_raw_rc_count; i++) {
-
- /* map the input channel */
- uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
-
- if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
-
- uint16_t raw = r_raw_rc_values[i];
-
- int16_t scaled;
-
- /*
- * 1) Constrain to min/max values, as later processing depends on bounds.
- */
- if (raw < conf[PX4IO_P_RC_CONFIG_MIN])
- raw = conf[PX4IO_P_RC_CONFIG_MIN];
- if (raw > conf[PX4IO_P_RC_CONFIG_MAX])
- raw = conf[PX4IO_P_RC_CONFIG_MAX];
-
- /*
- * 2) Scale around the mid point differently for lower and upper range.
- *
- * This is necessary as they don't share the same endpoints and slope.
- *
- * First normalize to 0..1 range with correct sign (below or above center),
- * then scale to 20000 range (if center is an actual center, -10000..10000,
- * if parameters only support half range, scale to 10000 range, e.g. if
- * center == min 0..10000, if center == max -10000..0).
- *
- * As the min and max bounds were enforced in step 1), division by zero
- * cannot occur, as for the case of center == min or center == max the if
- * statement is mutually exclusive with the arithmetic NaN case.
- *
- * DO NOT REMOVE OR ALTER STEP 1!
- */
- if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
- scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
-
- } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
- scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
-
- } else {
- /* in the configured dead zone, output zero */
- scaled = 0;
- }
-
- /* invert channel if requested */
- if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE)
- scaled = -scaled;
+ /* update RC-received timestamp */
+ system_state.rc_channels_timestamp_received = hrt_absolute_time();
+
+ /* do not command anything in failsafe, kick in the RC loss counter */
+ if (!(r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE)) {
+
+ /* update RC-received timestamp */
+ system_state.rc_channels_timestamp_valid = system_state.rc_channels_timestamp_received;
+
+ /* map raw inputs to mapped inputs */
+ /* XXX mapping should be atomic relative to protocol */
+ for (unsigned i = 0; i < r_raw_rc_count; i++) {
+
+ /* map the input channel */
+ uint16_t *conf = &r_page_rc_input_config[i * PX4IO_P_RC_CONFIG_STRIDE];
+
+ if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) {
+
+ uint16_t raw = r_raw_rc_values[i];
+
+ int16_t scaled;
+
+ /*
+ * 1) Constrain to min/max values, as later processing depends on bounds.
+ */
+ if (raw < conf[PX4IO_P_RC_CONFIG_MIN])
+ raw = conf[PX4IO_P_RC_CONFIG_MIN];
+ if (raw > conf[PX4IO_P_RC_CONFIG_MAX])
+ raw = conf[PX4IO_P_RC_CONFIG_MAX];
+
+ /*
+ * 2) Scale around the mid point differently for lower and upper range.
+ *
+ * This is necessary as they don't share the same endpoints and slope.
+ *
+ * First normalize to 0..1 range with correct sign (below or above center),
+ * then scale to 20000 range (if center is an actual center, -10000..10000,
+ * if parameters only support half range, scale to 10000 range, e.g. if
+ * center == min 0..10000, if center == max -10000..0).
+ *
+ * As the min and max bounds were enforced in step 1), division by zero
+ * cannot occur, as for the case of center == min or center == max the if
+ * statement is mutually exclusive with the arithmetic NaN case.
+ *
+ * DO NOT REMOVE OR ALTER STEP 1!
+ */
+ if (raw > (conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
+ scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_MAX] - conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE]));
+
+ } else if (raw < (conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE])) {
+ scaled = 10000.0f * ((raw - conf[PX4IO_P_RC_CONFIG_CENTER] + conf[PX4IO_P_RC_CONFIG_DEADZONE]) / (float)(conf[PX4IO_P_RC_CONFIG_CENTER] - conf[PX4IO_P_RC_CONFIG_DEADZONE] - conf[PX4IO_P_RC_CONFIG_MIN]));
+
+ } else {
+ /* in the configured dead zone, output zero */
+ scaled = 0;
+ }
+
+ /* invert channel if requested */
+ if (conf[PX4IO_P_RC_CONFIG_OPTIONS] & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE)
+ scaled = -scaled;
- /* and update the scaled/mapped version */
- unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
- if (mapped < PX4IO_CONTROL_CHANNELS) {
+ /* and update the scaled/mapped version */
+ unsigned mapped = conf[PX4IO_P_RC_CONFIG_ASSIGNMENT];
+ if (mapped < PX4IO_CONTROL_CHANNELS) {
- /* invert channel if pitch - pulling the lever down means pitching up by convention */
- if (mapped == 1) /* roll, pitch, yaw, throttle, override is the standard order */
- scaled = -scaled;
+ /* invert channel if pitch - pulling the lever down means pitching up by convention */
+ if (mapped == 1) /* roll, pitch, yaw, throttle, override is the standard order */
+ scaled = -scaled;
- r_rc_values[mapped] = SIGNED_TO_REG(scaled);
- assigned_channels |= (1 << mapped);
+ r_rc_values[mapped] = SIGNED_TO_REG(scaled);
+ assigned_channels |= (1 << mapped);
+ }
}
}
- }
- /* set un-assigned controls to zero */
- for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) {
- if (!(assigned_channels & (1 << i)))
- r_rc_values[i] = 0;
- }
+ /* set un-assigned controls to zero */
+ for (unsigned i = 0; i < PX4IO_CONTROL_CHANNELS; i++) {
+ if (!(assigned_channels & (1 << i)))
+ r_rc_values[i] = 0;
+ }
- /*
- * If we got an update with zero channels, treat it as
- * a loss of input.
- *
- * This might happen if a protocol-based receiver returns an update
- * that contains no channels that we have mapped.
- */
- if (assigned_channels == 0 || rssi == 0) {
- rc_input_lost = true;
- } else {
- /* set RC OK flag */
+ /* set RC OK flag, as we got an update */
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
+
+ /* if we have enough channels (5) to control the vehicle, the mapping is ok */
+ if (assigned_channels > 4) {
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_MAPPING_OK;
+ } else {
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_MAPPING_OK);
+ }
}
/*
@@ -253,7 +301,7 @@ controls_tick() {
* If we haven't seen any new control data in 200ms, assume we
* have lost input.
*/
- if (hrt_elapsed_time(&system_state.rc_channels_timestamp) > 200000) {
+ if (hrt_elapsed_time(&system_state.rc_channels_timestamp_received) > 200000) {
rc_input_lost = true;
/* clear the input-kind flags here */
@@ -261,24 +309,32 @@ controls_tick() {
PX4IO_P_STATUS_FLAGS_RC_PPM |
PX4IO_P_STATUS_FLAGS_RC_DSM |
PX4IO_P_STATUS_FLAGS_RC_SBUS);
+
}
/*
* Handle losing RC input
*/
- if (rc_input_lost) {
+ /* this kicks in if the receiver is gone or the system went to failsafe */
+ if (rc_input_lost || (r_raw_rc_flags & PX4IO_P_RAW_RC_FLAGS_FAILSAFE)) {
/* Clear the RC input status flag, clear manual override flag */
r_status_flags &= ~(
PX4IO_P_STATUS_FLAGS_OVERRIDE |
PX4IO_P_STATUS_FLAGS_RC_OK);
+ /* Mark all channels as invalid, as we just lost the RX */
+ r_rc_valid = 0;
+
/* Set the RC_LOST alarm */
r_status_alarms |= PX4IO_P_STATUS_ALARMS_RC_LOST;
+ }
- /* Mark the arrays as empty */
+ /* this kicks in if the receiver is completely gone */
+ if (rc_input_lost) {
+
+ /* Set channel count to zero */
r_raw_rc_count = 0;
- r_rc_valid = 0;
}
/*
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index e55ef784a..f39fcf7ec 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -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
@@ -71,6 +71,7 @@ extern "C" {
static bool mixer_servos_armed = false;
static bool should_arm = false;
static bool should_always_enable_pwm = false;
+static volatile bool in_mixer = false;
/* selected control values and count for mixing */
enum mixer_source {
@@ -95,6 +96,7 @@ static void mixer_set_failsafe();
void
mixer_tick(void)
{
+
/* check that we are receiving fresh data from the FMU */
if (hrt_elapsed_time(&system_state.fmu_data_received_time) > FMU_INPUT_DROP_LIMIT_US) {
@@ -199,13 +201,17 @@ mixer_tick(void)
}
- } else if (source != MIX_NONE) {
+ } else if (source != MIX_NONE && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
float outputs[PX4IO_SERVO_COUNT];
unsigned mixed;
/* mix */
+
+ /* poor mans mutex */
+ in_mixer = true;
mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
+ in_mixer = false;
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
@@ -217,14 +223,25 @@ mixer_tick(void)
}
}
- if ((should_arm || should_always_enable_pwm) && !mixer_servos_armed) {
+ /* set arming */
+ bool needs_to_arm = (should_arm || should_always_enable_pwm);
+
+ /* check any conditions that prevent arming */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) {
+ needs_to_arm = false;
+ }
+ if (!should_arm && !should_always_enable_pwm) {
+ needs_to_arm = false;
+ }
+
+ if (needs_to_arm && !mixer_servos_armed) {
/* need to arm, but not armed */
up_pwm_servo_arm(true);
mixer_servos_armed = true;
r_status_flags |= PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED;
isr_debug(5, "> PWM enabled");
- } else if ((!should_arm && !should_always_enable_pwm) && mixer_servos_armed) {
+ } else if (!needs_to_arm && mixer_servos_armed) {
/* armed but need to disarm */
up_pwm_servo_arm(false);
mixer_servos_armed = false;
@@ -297,12 +314,17 @@ mixer_callback(uintptr_t handle,
static char mixer_text[256]; /* large enough for one mixer */
static unsigned mixer_text_length = 0;
-void
+int
mixer_handle_text(const void *buffer, size_t length)
{
/* do not allow a mixer change while safety off */
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
- return;
+ return 1;
+ }
+
+ /* abort if we're in the mixer */
+ if (in_mixer) {
+ return 1;
}
px4io_mixdata *msg = (px4io_mixdata *)buffer;
@@ -310,7 +332,7 @@ mixer_handle_text(const void *buffer, size_t length)
isr_debug(2, "mix txt %u", length);
if (length < sizeof(px4io_mixdata))
- return;
+ return 0;
unsigned text_length = length - sizeof(px4io_mixdata);
@@ -328,13 +350,16 @@ mixer_handle_text(const void *buffer, size_t length)
case F2I_MIXER_ACTION_APPEND:
isr_debug(2, "append %d", length);
+ /* disable mixing during the update */
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
+
/* check for overflow - this would be really fatal */
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
- return;
+ return 0;
}
- /* append mixer text and nul-terminate */
+ /* append mixer text and nul-terminate, guard against overflow */
memcpy(&mixer_text[mixer_text_length], msg->text, text_length);
mixer_text_length += text_length;
mixer_text[mixer_text_length] = '\0';
@@ -369,6 +394,8 @@ mixer_handle_text(const void *buffer, size_t length)
break;
}
+
+ return 0;
}
static void
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index e5bef6eb3..d48c6c529 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -111,7 +111,6 @@
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
#define PX4IO_P_STATUS_FLAGS_SAFETY_OFF (1 << 12) /* safety is off */
-#define PX4IO_P_STATUS_FLAGS_RC_DSM11 (1 << 13) /* DSM input is 11 bit data */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* [1] VBatt is very close to regulator dropout */
@@ -128,8 +127,6 @@
#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */
#define PX4IO_P_STATUS_VRSSI 7 /* [2] RSSI voltage */
#define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */
-#define PX4IO_P_STATUS_NRSSI 9 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
-#define PX4IO_P_STATUS_RC_DATA 10 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
/* array of post-mix actuator outputs, -10000..10000 */
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
@@ -140,7 +137,17 @@
/* array of raw RC input values, microseconds */
#define PX4IO_PAGE_RAW_RC_INPUT 4
#define PX4IO_P_RAW_RC_COUNT 0 /* number of valid channels */
-#define PX4IO_P_RAW_RC_BASE 1 /* CONFIG_RC_INPUT_COUNT channels from here */
+#define PX4IO_P_RAW_RC_FLAGS 1 /* RC detail status flags */
+#define PX4IO_P_RAW_RC_FLAGS_FRAME_DROP (1 << 0) /* single frame drop */
+#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */
+#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */
+#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */
+
+#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
+#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
+#define PX4IO_P_RAW_FRAME_COUNT 4 /* Number of total received frames (wrapping counter) */
+#define PX4IO_P_RAW_LOST_FRAME_COUNT 5 /* Number of total dropped frames (wrapping counter) */
+#define PX4IO_P_RAW_RC_BASE 6 /* CONFIG_RC_INPUT_COUNT channels from here */
/* array of scaled RC input values, -10000..10000 */
#define PX4IO_PAGE_RC_INPUT 5
@@ -157,6 +164,10 @@
/* setup page */
#define PX4IO_PAGE_SETUP 50
#define PX4IO_P_SETUP_FEATURES 0
+#define PX4IO_P_SETUP_FEATURES_SBUS1_OUT (1 << 0) /* enable S.Bus v1 output */
+#define PX4IO_P_SETUP_FEATURES_SBUS2_OUT (1 << 1) /* enable S.Bus v2 output */
+#define PX4IO_P_SETUP_FEATURES_PWM_RSSI (1 << 2) /* enable PWM RSSI parsing */
+#define PX4IO_P_SETUP_FEATURES_ADC_RSSI (1 << 3) /* enable ADC RSSI parsing */
#define PX4IO_P_SETUP_ARMING 1 /* arming controls */
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
@@ -166,6 +177,7 @@
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
#define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */
#define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */
+#define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index 0b8c4a6a8..d4c25911e 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,11 +295,12 @@ user_start(int argc, char *argv[])
check_reboot();
-#if 0
- /* check for debug activity */
+ /* check for debug activity (default: none) */
show_debug_messages();
- /* post debug state at ~1Hz */
+ /* post debug state at ~1Hz - this is via an auxiliary serial port
+ * DEFAULTS TO OFF!
+ */
if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) {
struct mallinfo minfo = mallinfo();
@@ -287,7 +313,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..bb224f388 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -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
@@ -96,8 +96,9 @@ extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
#define r_raw_rc_count r_page_raw_rc_input[PX4IO_P_RAW_RC_COUNT]
#define r_raw_rc_values (&r_page_raw_rc_input[PX4IO_P_RAW_RC_BASE])
+#define r_raw_rc_flags r_page_raw_rc_input[PX4IO_P_RAW_RC_FLAGS]
#define r_rc_valid r_page_rc_input[PX4IO_P_RC_VALID]
-#define r_rc_values (&r_page_rc_input[PX4IO_P_RAW_RC_BASE])
+#define r_rc_values (&r_page_rc_input[PX4IO_P_RC_BASE])
#define r_setup_features r_page_setup[PX4IO_P_SETUP_FEATURES]
#define r_setup_arming r_page_setup[PX4IO_P_SETUP_ARMING]
@@ -115,7 +116,8 @@ extern uint16_t r_page_servo_disarmed[]; /* PX4IO_PAGE_DISARMED_PWM */
*/
struct sys_state_s {
- volatile uint64_t rc_channels_timestamp;
+ volatile uint64_t rc_channels_timestamp_received;
+ volatile uint64_t rc_channels_timestamp_valid;
/**
* Last FMU receive time, in microseconds since system boot
@@ -160,6 +162,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))
@@ -177,12 +180,13 @@ extern pwm_limit_t pwm_limit;
* Mixer
*/
extern void mixer_tick(void);
-extern void mixer_handle_text(const void *buffer, size_t length);
+extern int 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
@@ -213,7 +217,7 @@ extern int dsm_init(const char *device);
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
-extern bool sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels);
+extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
/** global debug level for isr_debug() */
extern volatile uint8_t debug_level;
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index ad4473073..1335f52e1 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -90,8 +90,6 @@ uint16_t r_page_status[] = {
[PX4IO_P_STATUS_VSERVO] = 0,
[PX4IO_P_STATUS_VRSSI] = 0,
[PX4IO_P_STATUS_PRSSI] = 0,
- [PX4IO_P_STATUS_NRSSI] = 0,
- [PX4IO_P_STATUS_RC_DATA] = 0
};
/**
@@ -116,6 +114,12 @@ uint16_t r_page_servos[PX4IO_SERVO_COUNT];
uint16_t r_page_raw_rc_input[] =
{
[PX4IO_P_RAW_RC_COUNT] = 0,
+ [PX4IO_P_RAW_RC_FLAGS] = 0,
+ [PX4IO_P_RAW_RC_NRSSI] = 0,
+ [PX4IO_P_RAW_RC_DATA] = 0,
+ [PX4IO_P_RAW_FRAME_COUNT] = 0,
+ [PX4IO_P_RAW_LOST_FRAME_COUNT] = 0,
+ [PX4IO_P_RAW_RC_DATA] = 0,
[PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_RC_INPUT_CHANNELS)] = 0
};
@@ -144,7 +148,12 @@ uint16_t r_page_scratch[32];
*/
volatile uint16_t r_page_setup[] =
{
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+ /* default to RSSI ADC functionality */
+ [PX4IO_P_SETUP_FEATURES] = PX4IO_P_SETUP_FEATURES_ADC_RSSI,
+#else
[PX4IO_P_SETUP_FEATURES] = 0,
+#endif
[PX4IO_P_SETUP_ARMING] = 0,
[PX4IO_P_SETUP_PWM_RATES] = 0,
[PX4IO_P_SETUP_PWM_DEFAULTRATE] = 50,
@@ -162,14 +171,22 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_CRC ... (PX4IO_P_SETUP_CRC+1)] = 0,
};
-#define PX4IO_P_SETUP_FEATURES_VALID (0)
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
+#define PX4IO_P_SETUP_FEATURES_VALID (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | \
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT | \
+ PX4IO_P_SETUP_FEATURES_ADC_RSSI | \
+ PX4IO_P_SETUP_FEATURES_PWM_RSSI)
+#else
+#define PX4IO_P_SETUP_FEATURES_VALID 0
+#endif
#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_FMU_ARMED | \
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | \
PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | \
PX4IO_P_SETUP_ARMING_IO_ARM_OK | \
PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM | \
PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \
- PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED)
+ PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \
+ PX4IO_P_SETUP_ARMING_LOCKDOWN)
#define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1)
#define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1)
@@ -382,7 +399,10 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* handle text going to the mixer parser */
case PX4IO_PAGE_MIXERLOAD:
- mixer_handle_text(values, num_values * sizeof(*values));
+ if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
+ return mixer_handle_text(values, num_values * sizeof(*values));
+ }
break;
default:
@@ -435,9 +455,35 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
case PX4IO_P_SETUP_FEATURES:
value &= PX4IO_P_SETUP_FEATURES_VALID;
- r_setup_features = value;
- /* no implemented feature selection at this point */
+ /* some of the options conflict - give S.BUS out precedence, then ADC RSSI, then PWM RSSI */
+
+ /* switch S.Bus output pin as needed */
+ #ifdef ENABLE_SBUS_OUT
+ ENABLE_SBUS_OUT(value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT));
+
+ /* disable the conflicting options */
+ if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | PX4IO_P_SETUP_FEATURES_ADC_RSSI);
+ }
+ #endif
+
+ /* disable the conflicting options with ADC RSSI */
+ if (value & (PX4IO_P_SETUP_FEATURES_ADC_RSSI)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS1_OUT |
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ }
+
+ /* disable the conflicting options with PWM RSSI (without effect here, but for completeness) */
+ if (value & (PX4IO_P_SETUP_FEATURES_PWM_RSSI)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_ADC_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS1_OUT |
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ }
+
+ /* apply changes */
+ r_setup_features = value;
break;
@@ -453,11 +499,6 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
* lockup of the IO arming state.
*/
- // XXX do not reset IO's safety state by FMU for now
- // if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && !(value & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
- // r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED;
- // }
-
if (value & PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_INIT_OK;
}
@@ -509,8 +550,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
case PX4IO_P_SETUP_REBOOT_BL:
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
- (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ||
- (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
// don't allow reboot while armed
break;
}
@@ -540,8 +580,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
* do not allow a RC config change while outputs armed
*/
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
- (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ||
- (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
break;
}
diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c
index cdb54a80a..ff2e4af6e 100644
--- a/src/modules/px4iofirmware/safety.c
+++ b/src/modules/px4iofirmware/safety.c
@@ -45,7 +45,6 @@
#include "px4io.h"
static struct hrt_call arming_call;
-static struct hrt_call heartbeat_call;
static struct hrt_call failsafe_call;
/*
@@ -84,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);
}
@@ -165,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;
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 11ccd7356..f6ec542eb 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.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
@@ -87,7 +87,7 @@ static unsigned partial_frame_count;
unsigned sbus_frame_drops;
-static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels);
+static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
int
sbus_init(const char *device)
@@ -118,7 +118,7 @@ sbus_init(const char *device)
}
bool
-sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels)
+sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels)
{
ssize_t ret;
hrt_abstime now;
@@ -175,7 +175,7 @@ sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_
* decode it.
*/
partial_frame_count = 0;
- return sbus_decode(now, values, num_values, rssi, max_channels);
+ return sbus_decode(now, values, num_values, sbus_failsafe, sbus_frame_drop, max_channels);
}
/*
@@ -215,14 +215,36 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
};
static bool
-sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_values)
+sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
{
/* check frame boundary markers to avoid out-of-sync cases */
- if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
+ if ((frame[0] != 0x0f)) {
sbus_frame_drops++;
return false;
}
+ switch (frame[24]) {
+ case 0x00:
+ /* this is S.BUS 1 */
+ break;
+ case 0x03:
+ /* S.BUS 2 SLOT0: RX battery and external voltage */
+ break;
+ case 0x83:
+ /* S.BUS 2 SLOT1 */
+ break;
+ case 0x43:
+ case 0xC3:
+ case 0x23:
+ case 0xA3:
+ case 0x63:
+ case 0xE3:
+ break;
+ default:
+ /* we expect one of the bits above, but there are some we don't know yet */
+ break;
+ }
+
/* we have received something we think is a frame */
last_frame_time = frame_time;
@@ -267,20 +289,22 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
/* decode and handle failsafe and frame-lost flags */
if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
/* report that we failed to read anything valid off the receiver */
- *rssi = 0;
- return false;
+ *sbus_failsafe = true;
+ *sbus_frame_drop = true;
}
else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
- /* set a special warning flag or try to calculate some kind of RSSI information - to be implemented
+ /* set a special warning flag
*
* Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
* condition as fail-safe greatly reduces the reliability and range of the radio link,
* e.g. by prematurely issueing return-to-launch!!! */
- *rssi = 100; // XXX magic number indicating bad signal, but not a signal loss (yet)
+ *sbus_failsafe = false;
+ *sbus_frame_drop = true;
+ } else {
+ *sbus_failsafe = false;
+ *sbus_frame_drop = false;
}
- *rssi = 255;
-
return true;
}
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 06b1eddaa..c4fafb5a6 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -85,13 +85,13 @@
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <version/version.h>
#include <mavlink/mavlink_log.h>
#include "logbuffer.h"
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
-#include "sdlog2_version.h"
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
@@ -108,13 +108,13 @@ static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
-static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */
+static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
-static const char *mountpoint = "/fs/microsd";
+static const char *log_root = "/fs/microsd/log";
static int mavlink_fd = -1;
struct logbuffer_s lb;
@@ -122,14 +122,17 @@ struct logbuffer_s lb;
static pthread_mutex_t logbuffer_mutex;
static pthread_cond_t logbuffer_cond;
-static char folder_path[64];
+static char log_dir[32];
/* statistics counters */
-static unsigned long log_bytes_written = 0;
static uint64_t start_time = 0;
+static unsigned long log_bytes_written = 0;
static unsigned long log_msgs_written = 0;
static unsigned long log_msgs_skipped = 0;
+/* GPS time, used for log files naming */
+static uint64_t gps_time = 0;
+
/* current state of logging */
static bool logging_enabled = false;
/* enable logging on start (-e option) */
@@ -138,11 +141,14 @@ static bool log_on_start = false;
static bool log_when_armed = false;
/* delay = 1 / rate (rate defined by -r option) */
static useconds_t sleep_delay = 0;
+/* use date/time for naming directories and files (-t option) */
+static bool log_name_timestamp = false;
/* helper flag to track system state changes */
static bool flag_system_armed = false;
static pthread_t logwriter_pthread = 0;
+static pthread_attr_t logwriter_attr;
/**
* Log buffer writing thread. Open and close file here.
@@ -203,14 +209,14 @@ static void handle_command(struct vehicle_command_s *cmd);
static void handle_status(struct vehicle_status_s *cmd);
/**
- * Create folder for current logging session. Store folder name in 'log_folder'.
+ * Create dir for current logging session. Store dir name in 'log_dir'.
*/
-static int create_logfolder(void);
+static int create_log_dir(void);
/**
* Select first free log file name and open it.
*/
-static int open_logfile(void);
+static int open_log_file(void);
static void
sdlog2_usage(const char *reason)
@@ -218,11 +224,12 @@ sdlog2_usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a\n"
+ errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
- "\t-a\tLog only when armed (can be still overriden by command)\n");
+ "\t-a\tLog only when armed (can be still overriden by command)\n"
+ "\t-t\tUse date/time for naming log directories and files\n");
}
/**
@@ -280,82 +287,112 @@ int sdlog2_main(int argc, char *argv[])
exit(1);
}
-int create_logfolder()
+int create_log_dir()
{
- /* make folder on sdcard */
- uint16_t folder_number = 1; // start with folder sess001
+ /* create dir on sdcard if needed */
+ uint16_t dir_number = 1; // start with dir sess001
int mkdir_ret;
- /* look for the next folder that does not exist */
- while (folder_number <= MAX_NO_LOGFOLDER) {
- /* set up folder path: e.g. /fs/microsd/sess001 */
- sprintf(folder_path, "%s/sess%03u", mountpoint, folder_number);
- mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO);
- /* the result is -1 if the folder exists */
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS date for log dir naming: e.g. /fs/microsd/2014-01-19 */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ int n = snprintf(log_dir, sizeof(log_dir), "%s/", log_root);
+ strftime(log_dir + n, sizeof(log_dir) - n, "%Y-%m-%d", &t);
+ mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
- if (mkdir_ret == 0) {
- /* folder does not exist, success */
- break;
+ if (mkdir_ret == OK) {
+ warnx("log dir created: %s", log_dir);
+
+ } else if (errno != EEXIST) {
+ warn("failed creating new dir: %s", log_dir);
+ return -1;
+ }
+
+ } else {
+ /* look for the next dir that does not exist */
+ while (dir_number <= MAX_NO_LOGFOLDER) {
+ /* format log dir: e.g. /fs/microsd/sess001 */
+ sprintf(log_dir, "%s/sess%03u", log_root, dir_number);
+ mkdir_ret = mkdir(log_dir, S_IRWXU | S_IRWXG | S_IRWXO);
- } else if (mkdir_ret == -1) {
- /* folder exists already */
- folder_number++;
+ if (mkdir_ret == 0) {
+ warnx("log dir created: %s", log_dir);
+ break;
+
+ } else if (errno != EEXIST) {
+ warn("failed creating new dir: %s", log_dir);
+ return -1;
+ }
+
+ /* dir exists already */
+ dir_number++;
continue;
+ }
- } else {
- warn("failed creating new folder");
+ if (dir_number >= MAX_NO_LOGFOLDER) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
+ warnx("all %d possible dirs exist already", MAX_NO_LOGFOLDER);
return -1;
}
}
- if (folder_number >= MAX_NO_LOGFOLDER) {
- /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
- warnx("all %d possible folders exist already.", MAX_NO_LOGFOLDER);
- return -1;
- }
-
+ /* print logging path, important to find log file later */
+ warnx("log dir: %s", log_dir);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log dir: %s", log_dir);
return 0;
}
-int open_logfile()
+int open_log_file()
{
- /* make folder on sdcard */
- uint16_t file_number = 1; // start with file log001
-
/* string to hold the path to the log */
- char path_buf[64] = "";
-
- int fd = 0;
-
- /* look for the next file that does not exist */
- while (file_number <= MAX_NO_LOGFILE) {
- /* set up file path: e.g. /fs/microsd/sess001/log001.bin */
- sprintf(path_buf, "%s/log%03u.bin", folder_path, file_number);
+ char log_file_name[16] = "";
+ char log_file_path[48] = "";
+
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ strftime(log_file_name, sizeof(log_file_name), "%H_%M_%S.bin", &t);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
+
+ } else {
+ uint16_t file_number = 1; // start with file log001
+
+ /* look for the next file that does not exist */
+ while (file_number <= MAX_NO_LOGFILE) {
+ /* format log file path: e.g. /fs/microsd/sess001/log001.bin */
+ snprintf(log_file_name, sizeof(log_file_name), "log%03u.bin", file_number);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s", log_dir, log_file_name);
+
+ if (!file_exist(log_file_path)) {
+ break;
+ }
- if (file_exist(path_buf)) {
file_number++;
- continue;
}
- fd = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC);
-
- if (fd == 0) {
- warn("opening %s failed", path_buf);
+ if (file_number > MAX_NO_LOGFILE) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
+ warnx("all %d possible files exist already", MAX_NO_LOGFILE);
+ return -1;
}
+ }
- warnx("logging to: %s.", path_buf);
- mavlink_log_info(mavlink_fd, "[sdlog2] log: %s", path_buf);
+ int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
- return fd;
- }
+ if (fd < 0) {
+ warn("failed opening log: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
- if (file_number > MAX_NO_LOGFILE) {
- /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
- warnx("all %d possible files exist already.", MAX_NO_LOGFILE);
- return -1;
+ } else {
+ warnx("log file: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name);
}
- return 0;
+ return fd;
}
static void *logwriter_thread(void *arg)
@@ -363,9 +400,12 @@ static void *logwriter_thread(void *arg)
/* set name */
prctl(PR_SET_NAME, "sdlog2_writer", 0);
- struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
+ int log_fd = open_log_file();
- int log_fd = open_logfile();
+ if (log_fd < 0)
+ return;
+
+ struct logbuffer_s *logbuf = (struct logbuffer_s *)arg;
/* write log messages formats, version and parameters */
log_bytes_written += write_formats(log_fd);
@@ -443,14 +483,20 @@ static void *logwriter_thread(void *arg)
fsync(log_fd);
close(log_fd);
- return OK;
+ return;
}
void sdlog2_start_log()
{
- warnx("start logging.");
+ warnx("start logging");
mavlink_log_info(mavlink_fd, "[sdlog2] start logging");
+ /* create log dir if needed */
+ if (create_log_dir() != 0) {
+ mavlink_log_critical(mavlink_fd, "[sdlog2] error creating log dir");
+ errx(1, "error creating log dir");
+ }
+
/* initialize statistics counter */
log_bytes_written = 0;
start_time = hrt_absolute_time();
@@ -458,30 +504,28 @@ void sdlog2_start_log()
log_msgs_skipped = 0;
/* initialize log buffer emptying thread */
- pthread_attr_t receiveloop_attr;
- pthread_attr_init(&receiveloop_attr);
+ pthread_attr_init(&logwriter_attr);
struct sched_param param;
/* low priority, as this is expensive disk I/O */
param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
- (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+ (void)pthread_attr_setschedparam(&logwriter_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 2048);
+ pthread_attr_setstacksize(&logwriter_attr, 2048);
logwriter_should_exit = false;
/* start log buffer emptying thread */
- if (0 != pthread_create(&logwriter_pthread, &receiveloop_attr, logwriter_thread, &lb)) {
+ if (0 != pthread_create(&logwriter_pthread, &logwriter_attr, logwriter_thread, &lb)) {
errx(1, "error creating logwriter thread");
}
logging_enabled = true;
- // XXX we have to destroy the attr at some point
}
void sdlog2_stop_log()
{
- warnx("stop logging.");
+ warnx("stop logging");
mavlink_log_info(mavlink_fd, "[sdlog2] stop logging");
logging_enabled = false;
@@ -501,6 +545,7 @@ void sdlog2_stop_log()
}
logwriter_pthread = 0;
+ pthread_attr_destroy(&logwriter_attr);
sdlog2_status();
}
@@ -569,8 +614,8 @@ int write_parameters(int fd)
}
case PARAM_TYPE_FLOAT:
- param_get(param, &value);
- break;
+ param_get(param, &value);
+ break;
default:
break;
@@ -588,18 +633,25 @@ int sdlog2_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
if (mavlink_fd < 0) {
- warnx("failed to open MAVLink log stream, start mavlink app first.");
+ warnx("failed to open MAVLink log stream, start mavlink app first");
}
/* log buffer size */
int log_buffer_size = LOG_BUFFER_SIZE_DEFAULT;
+ logging_enabled = false;
+ log_on_start = false;
+ log_when_armed = false;
+ log_name_timestamp = false;
+
+ flag_system_armed = false;
+
/* work around some stupidity in task_create's argv handling */
argc -= 2;
argv += 2;
int ch;
- while ((ch = getopt(argc, argv, "r:b:ea")) != EOF) {
+ while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
@@ -632,49 +684,52 @@ int sdlog2_thread_main(int argc, char *argv[])
log_when_armed = true;
break;
+ case 't':
+ log_name_timestamp = true;
+ break;
+
case '?':
if (optopt == 'c') {
- warnx("Option -%c requires an argument.", optopt);
+ warnx("option -%c requires an argument", optopt);
} else if (isprint(optopt)) {
- warnx("Unknown option `-%c'.", optopt);
+ warnx("unknown option `-%c'", optopt);
} else {
- warnx("Unknown option character `\\x%x'.", optopt);
+ warnx("unknown option character `\\x%x'", optopt);
}
default:
sdlog2_usage("unrecognized flag");
- errx(1, "exiting.");
+ errx(1, "exiting");
}
}
- if (!file_exist(mountpoint)) {
- errx(1, "logging mount point %s not present, exiting.", mountpoint);
- }
+ gps_time = 0;
+
+ /* create log root dir */
+ int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
- if (create_logfolder()) {
- errx(1, "unable to create logging folder, exiting.");
+ if (mkdir_ret != 0 && errno != EEXIST) {
+ err("failed creating log root dir: %s", log_root);
}
+ /* copy conversion scripts */
const char *converter_in = "/etc/logging/conv.zip";
- char *converter_out = malloc(120);
- sprintf(converter_out, "%s/conv.zip", folder_path);
+ char *converter_out = malloc(64);
+ snprintf(converter_out, 64, "%s/conv.zip", log_root);
- if (file_copy(converter_in, converter_out)) {
- errx(1, "unable to copy conversion scripts, exiting.");
+ if (file_copy(converter_in, converter_out) != OK) {
+ warn("unable to copy conversion scripts");
}
free(converter_out);
- /* only print logging path, important to find log file later */
- warnx("logging to directory: %s", folder_path);
-
/* initialize log buffer with specified size */
- warnx("log buffer size: %i bytes.", log_buffer_size);
+ warnx("log buffer size: %i bytes", log_buffer_size);
if (OK != logbuffer_init(&lb, log_buffer_size)) {
- errx(1, "can't allocate log buffer, exiting.");
+ errx(1, "can't allocate log buffer, exiting");
}
struct vehicle_status_s buf_status;
@@ -895,7 +950,7 @@ int sdlog2_thread_main(int argc, char *argv[])
* differs from the number of messages in the above list.
*/
if (fdsc_count > fdsc) {
- warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.", __FILE__, __LINE__);
+ warn("WARNING: Not enough space for poll fds allocated. Check %s:%d", __FILE__, __LINE__);
fdsc_count = fdsc;
}
@@ -919,19 +974,27 @@ int sdlog2_thread_main(int argc, char *argv[])
uint16_t differential_pressure_counter = 0;
/* enable logging on start if needed */
- if (log_on_start)
+ if (log_on_start) {
+ /* check GPS topic to get GPS time */
+ if (log_name_timestamp) {
+ if (OK == orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos)) {
+ gps_time = buf.gps_pos.time_gps_usec;
+ }
+ }
+
sdlog2_start_log();
+ }
while (!main_thread_should_exit) {
/* decide use usleep() or blocking poll() */
bool use_sleep = sleep_delay > 0 && logging_enabled;
/* poll all topics if logging enabled or only management (first 2) if not */
- int poll_ret = poll(fds, logging_enabled ? fdsc_count : 2, use_sleep ? 0 : poll_timeout);
+ int poll_ret = poll(fds, logging_enabled ? fdsc_count : 3, use_sleep ? 0 : poll_timeout);
/* handle the poll result */
if (poll_ret < 0) {
- warnx("ERROR: poll error, stop logging.");
+ warnx("ERROR: poll error, stop logging");
main_thread_should_exit = true;
} else if (poll_ret > 0) {
@@ -960,6 +1023,17 @@ int sdlog2_thread_main(int argc, char *argv[])
handled_topics++;
}
+ /* --- GPS POSITION - LOG MANAGEMENT --- */
+ if (fds[ifds++].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
+
+ if (log_name_timestamp) {
+ gps_time = buf.gps_pos.time_gps_usec;
+ }
+
+ handled_topics++;
+ }
+
if (!logging_enabled || !check_data || handled_topics >= poll_ret) {
continue;
}
@@ -988,7 +1062,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GPS POSITION --- */
if (fds[ifds++].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
+ // Don't orb_copy, it's already done few lines above
log_msg.msg_type = LOG_GPS_MSG;
log_msg.body.log_GPS.gps_time = buf.gps_pos.time_gps_usec;
log_msg.body.log_GPS.fix_type = buf.gps_pos.fix_type;
@@ -1279,7 +1353,7 @@ int sdlog2_thread_main(int argc, char *argv[])
free(lb.data);
- warnx("exiting.");
+ warnx("exiting");
thread_running = false;
@@ -1292,8 +1366,8 @@ void sdlog2_status()
float mebibytes = kibibytes / 1024.0f;
float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
- warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs.", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
- mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs.", log_msgs_written, log_msgs_skipped);
+ warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
}
/**
@@ -1312,7 +1386,7 @@ int file_copy(const char *file_old, const char *file_new)
int ret = 0;
if (source == NULL) {
- warnx("failed opening input file to copy.");
+ warnx("failed opening input file to copy");
return 1;
}
@@ -1320,7 +1394,7 @@ int file_copy(const char *file_old, const char *file_new)
if (target == NULL) {
fclose(source);
- warnx("failed to open output file to copy.");
+ warnx("failed to open output file to copy");
return 1;
}
@@ -1331,7 +1405,7 @@ int file_copy(const char *file_old, const char *file_new)
ret = fwrite(buf, 1, nread, target);
if (ret <= 0) {
- warnx("error writing file.");
+ warnx("error writing file");
ret = 1;
break;
}
diff --git a/src/modules/sdlog2/sdlog2_version.h b/src/modules/sdlog2/sdlog2_version.h
deleted file mode 100644
index c6a9ba638..000000000
--- a/src/modules/sdlog2/sdlog2_version.h
+++ /dev/null
@@ -1,62 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file sdlog2_version.h
- *
- * Tools for system version detection.
- *
- * @author Anton Babushkin <anton.babushkin@me.com>
- */
-
-#ifndef SDLOG2_VERSION_H_
-#define SDLOG2_VERSION_H_
-
-/*
- GIT_VERSION is defined at build time via a Makefile call to the
- git command line.
- */
-#define FREEZE_STR(s) #s
-#define STRINGIFY(s) FREEZE_STR(s)
-#define FW_GIT STRINGIFY(GIT_VERSION)
-
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
-#define HW_ARCH "PX4FMU_V1"
-#endif
-
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
-#define HW_ARCH "PX4FMU_V2"
-#endif
-
-#endif /* SDLOG2_VERSION_H_ */
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index bbc84ef93..30659fd3a 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -381,14 +381,73 @@ PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f);
#endif
PARAM_DEFINE_FLOAT(BAT_C_SCALING, 0.0124); /* scaling for 3DR power brick */
+/**
+ * Roll control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading roll inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
+
+/**
+ * Pitch control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading pitch inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
+
+/**
+ * Throttle control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading throttle inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_THROTTLE, 3);
+
+/**
+ * Yaw control channel mapping.
+ *
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for reading yaw inputs from.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
PARAM_DEFINE_INT32(RC_MAP_YAW, 4);
-PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5);
+/**
+ * Mode switch channel mapping.
+ *
+ * This is the main flight mode selector.
+ * The channel index (starting from 1 for channel 1) indicates
+ * which channel should be used for deciding about the main mode.
+ * A value of zero indicates the switch is not assigned.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
-PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 6);
+PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index ff6c5882e..b50a694eb 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -797,7 +797,6 @@ Sensors::accel_init()
#endif
- warnx("using system accel");
close(fd);
}
}
@@ -837,7 +836,6 @@ Sensors::gyro_init()
#endif
- warnx("using system gyro");
close(fd);
}
}
@@ -1278,6 +1276,9 @@ Sensors::rc_poll()
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+ if (rc_input.rc_lost)
+ return;
+
struct manual_control_setpoint_s manual_control;
struct actuator_controls_s actuator_group_3;
@@ -1322,7 +1323,7 @@ Sensors::rc_poll()
channel_limit = _rc_max_chan_count;
/* we are accepting this message */
- _rc_last_valid = rc_input.timestamp;
+ _rc_last_valid = rc_input.timestamp_last_signal;
/* Read out values from raw message */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1371,9 +1372,9 @@ Sensors::rc_poll()
}
_rc.chan_count = rc_input.channel_count;
- _rc.timestamp = rc_input.timestamp;
+ _rc.timestamp = rc_input.timestamp_last_signal;
- manual_control.timestamp = rc_input.timestamp;
+ manual_control.timestamp = rc_input.timestamp_last_signal;
/* roll input - rolling right is stick-wise and rotation-wise positive */
manual_control.roll = limit_minus_one_to_one(_rc.chan[_rc.function[ROLL]].scaled);
@@ -1404,18 +1405,6 @@ Sensors::rc_poll()
manual_control.yaw *= _parameters.rc_scale_yaw;
}
- /* mode switch input */
- manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
-
- /* land switch input */
- manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
-
- /* assisted switch input */
- manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
-
- /* mission switch input */
- manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
-
/* flaps */
if (_rc.function[FLAPS] >= 0) {
@@ -1434,6 +1423,16 @@ Sensors::rc_poll()
manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}
+ /* land switch input */
+ if (_rc.function[RETURN] >= 0) {
+ manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
+ }
+
+ /* assisted switch input */
+ if (_rc.function[ASSISTED] >= 0) {
+ manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
+ }
+
// if (_rc.function[OFFBOARD_MODE] >= 0) {
// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
// }
@@ -1507,9 +1506,6 @@ void
Sensors::task_main()
{
- /* inform about start */
- warnx("Initializing..");
-
/* start individual sensors */
accel_init();
gyro_init();
@@ -1548,8 +1544,8 @@ Sensors::task_main()
raw.adc_voltage_v[3] = 0.0f;
memset(&_battery_status, 0, sizeof(_battery_status));
- _battery_status.voltage_v = 0.0f;
- _battery_status.voltage_filtered_v = 0.0f;
+ _battery_status.voltage_v = -1.0f;
+ _battery_status.voltage_filtered_v = -1.0f;
_battery_status.current_a = -1.0f;
_battery_status.discharged_mah = -1.0f;
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index afc5b072c..ccc516f39 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -93,8 +93,7 @@ void cpuload_initialize_once()
#endif /* CONFIG_SCHED_WORKQUEUE */
// perform static initialization of "system" threads
- for (system_load.total_count = 0; system_load.total_count < static_tasks_count; system_load.total_count++)
- {
+ for (system_load.total_count = 0; system_load.total_count < static_tasks_count; system_load.total_count++) {
system_load.tasks[system_load.total_count].start_time = now;
system_load.tasks[system_load.total_count].total_runtime = 0;
system_load.tasks[system_load.total_count].curr_start_time = 0;
diff --git a/src/modules/systemlib/cpuload.h b/src/modules/systemlib/cpuload.h
index c7aa18d3c..16d132fdb 100644
--- a/src/modules/systemlib/cpuload.h
+++ b/src/modules/systemlib/cpuload.h
@@ -40,15 +40,15 @@ __BEGIN_DECLS
#include <nuttx/sched.h>
struct system_load_taskinfo_s {
- uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
- uint64_t curr_start_time; ///< Start time of the current scheduling slot
- uint64_t start_time; ///< FIRST start time of task
- FAR struct tcb_s *tcb; ///<
- bool valid; ///< Task is currently active / valid
+ uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
+ uint64_t curr_start_time; ///< Start time of the current scheduling slot
+ uint64_t start_time; ///< FIRST start time of task
+ FAR struct tcb_s *tcb; ///<
+ bool valid; ///< Task is currently active / valid
};
struct system_load_s {
- uint64_t start_time; ///< Global start time of measurements
+ uint64_t start_time; ///< Global start time of measurements
struct system_load_taskinfo_s tasks[CONFIG_MAX_TASKS];
uint8_t initialized;
int total_count;
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 8c6c300d6..3953b757d 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -51,5 +51,6 @@ SRCS = err.c \
mavlink_log.c \
rc_check.c \
otp.c \
- board_serial.c
+ board_serial.c \
+ pwm_limit/pwm_limit.c
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
index cac3dc82a..190b315f1 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.c
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
* Author: Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
@@ -44,38 +44,53 @@
#include <math.h>
#include <stdbool.h>
#include <drivers/drv_hrt.h>
+#include <stdio.h>
void pwm_limit_init(pwm_limit_t *limit)
{
- limit->state = LIMIT_STATE_OFF;
+ limit->state = PWM_LIMIT_STATE_INIT;
limit->time_armed = 0;
return;
}
-void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
+void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit)
{
+
/* first evaluate state changes */
switch (limit->state) {
- case LIMIT_STATE_OFF:
- if (armed)
- limit->state = LIMIT_STATE_RAMP;
- limit->time_armed = hrt_absolute_time();
+ case PWM_LIMIT_STATE_INIT:
+
+ if (armed) {
+
+ /* set arming time for the first call */
+ if (limit->time_armed == 0) {
+ limit->time_armed = hrt_absolute_time();
+ }
+
+ if (hrt_elapsed_time(&limit->time_armed) >= INIT_TIME_US) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ }
+ }
break;
- case LIMIT_STATE_INIT:
- if (!armed)
- limit->state = LIMIT_STATE_OFF;
- else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US)
- limit->state = LIMIT_STATE_RAMP;
+ case PWM_LIMIT_STATE_OFF:
+ if (armed) {
+ limit->state = PWM_LIMIT_STATE_RAMP;
+
+ /* reset arming time, used for ramp timing */
+ limit->time_armed = hrt_absolute_time();
+ }
break;
- case LIMIT_STATE_RAMP:
- if (!armed)
- limit->state = LIMIT_STATE_OFF;
- else if (hrt_absolute_time() - limit->time_armed >= INIT_TIME_US + RAMP_TIME_US)
- limit->state = LIMIT_STATE_ON;
+ case PWM_LIMIT_STATE_RAMP:
+ if (!armed) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ } else if (hrt_elapsed_time(&limit->time_armed) >= RAMP_TIME_US) {
+ limit->state = PWM_LIMIT_STATE_ON;
+ }
break;
- case LIMIT_STATE_ON:
- if (!armed)
- limit->state = LIMIT_STATE_OFF;
+ case PWM_LIMIT_STATE_ON:
+ if (!armed) {
+ limit->state = PWM_LIMIT_STATE_OFF;
+ }
break;
default:
break;
@@ -86,44 +101,47 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
/* then set effective_pwm based on state */
switch (limit->state) {
- case LIMIT_STATE_OFF:
- case LIMIT_STATE_INIT:
+ case PWM_LIMIT_STATE_OFF:
+ case PWM_LIMIT_STATE_INIT:
for (unsigned i=0; i<num_channels; i++) {
effective_pwm[i] = disarmed_pwm[i];
- output[i] = 0.0f;
}
break;
- case LIMIT_STATE_RAMP:
+ case PWM_LIMIT_STATE_RAMP:
+ {
+ hrt_abstime diff = hrt_elapsed_time(&limit->time_armed);
- progress = (hrt_absolute_time() - INIT_TIME_US - limit->time_armed)*10000 / RAMP_TIME_US;
- for (unsigned i=0; i<num_channels; i++) {
-
- uint16_t ramp_min_pwm;
-
- /* if a disarmed pwm value was set, blend between disarmed and min */
- if (disarmed_pwm[i] > 0) {
-
- /* safeguard against overflows */
- uint16_t disarmed = disarmed_pwm[i];
- if (disarmed > min_pwm[i])
- disarmed = min_pwm[i];
-
- uint16_t disarmed_min_diff = min_pwm[i] - disarmed;
- ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000;
- } else {
-
- /* no disarmed pwm value set, choose min pwm */
- ramp_min_pwm = min_pwm[i];
- }
+ progress = diff * 10000 / RAMP_TIME_US;
+
+ for (unsigned i=0; i<num_channels; i++) {
+
+ uint16_t ramp_min_pwm;
+
+ /* if a disarmed pwm value was set, blend between disarmed and min */
+ if (disarmed_pwm[i] > 0) {
- effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
- output[i] = (float)progress/10000.0f * output[i];
+ /* safeguard against overflows */
+ unsigned disarmed = disarmed_pwm[i];
+ if (disarmed > min_pwm[i]) {
+ disarmed = min_pwm[i];
+ }
+
+ unsigned disarmed_min_diff = min_pwm[i] - disarmed;
+ ramp_min_pwm = disarmed + (disarmed_min_diff * progress) / 10000;
+
+ } else {
+
+ /* no disarmed pwm value set, choose min pwm */
+ ramp_min_pwm = min_pwm[i];
+ }
+
+ effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
+ }
}
break;
- case LIMIT_STATE_ON:
+ case PWM_LIMIT_STATE_ON:
for (unsigned i=0; i<num_channels; i++) {
effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
- /* effective_output stays the same */
}
break;
default:
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.h b/src/modules/systemlib/pwm_limit/pwm_limit.h
index 9974770be..6a667ac6f 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.h
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.h
@@ -46,6 +46,8 @@
#include <stdint.h>
#include <stdbool.h>
+__BEGIN_DECLS
+
/*
* time for the ESCs to initialize
* (this is not actually needed if PWM is sent right after boot)
@@ -56,21 +58,21 @@
*/
#define RAMP_TIME_US 2500000
+enum pwm_limit_state {
+ PWM_LIMIT_STATE_OFF = 0,
+ PWM_LIMIT_STATE_INIT,
+ PWM_LIMIT_STATE_RAMP,
+ PWM_LIMIT_STATE_ON
+};
+
typedef struct {
- enum {
- LIMIT_STATE_OFF = 0,
- LIMIT_STATE_INIT,
- LIMIT_STATE_RAMP,
- LIMIT_STATE_ON
- } state;
+ enum pwm_limit_state state;
uint64_t time_armed;
} pwm_limit_t;
-__BEGIN_DECLS
-
__EXPORT void pwm_limit_init(pwm_limit_t *limit);
-__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
+__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
__END_DECLS
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1c184d3a7..6ea48a680 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -206,6 +206,7 @@ struct vehicle_status_s
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
+ bool rc_input_blocked; /**< set if RC input should be ignored */
bool offboard_control_signal_found_once;
bool offboard_control_signal_lost;