aboutsummaryrefslogtreecommitdiff
path: root/src/modules/px4iofirmware/controls.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/px4iofirmware/controls.c')
-rw-r--r--src/modules/px4iofirmware/controls.c91
1 files changed, 75 insertions, 16 deletions
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 185cb20dd..58c9429b6 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -41,8 +41,10 @@
#include <stdbool.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_rc_input.h>
#include <systemlib/perf_counter.h>
#include <systemlib/ppm_decode.h>
+#include <rc/st24.h>
#include "px4io.h"
@@ -51,11 +53,62 @@
#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
+static bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated);
static perf_counter_t c_gather_dsm;
static perf_counter_t c_gather_sbus;
static perf_counter_t c_gather_ppm;
+static int _dsm_fd;
+
+static uint16_t rc_value_override = 0;
+
+bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated)
+{
+ perf_begin(c_gather_dsm);
+ uint16_t temp_count = r_raw_rc_count;
+ uint8_t n_bytes = 0;
+ uint8_t *bytes;
+ *dsm_updated = dsm_input(r_raw_rc_values, &temp_count, &n_bytes, &bytes);
+ if (*dsm_updated) {
+ r_raw_rc_count = temp_count & 0x7fff;
+ if (temp_count & 0x8000)
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
+ else
+ 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);
+
+ }
+ perf_end(c_gather_dsm);
+
+ /* get data from FD and attempt to parse with DSM and ST24 libs */
+ uint8_t st24_rssi, rx_count;
+ uint16_t st24_channel_count = 0;
+
+ *st24_updated = false;
+
+ for (unsigned i = 0; i < n_bytes; i++) {
+ /* set updated flag if one complete packet was parsed */
+ st24_rssi = RC_INPUT_RSSI_MAX;
+ *st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &rx_count,
+ &st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS));
+ }
+
+ if (*st24_updated) {
+
+ *rssi = st24_rssi;
+ r_raw_rc_count = st24_channel_count;
+
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_ST24;
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FRAME_DROP);
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ }
+
+ return (*dsm_updated | *st24_updated);
+}
+
void
controls_init(void)
{
@@ -65,7 +118,7 @@ controls_init(void)
system_state.rc_channels_timestamp_valid = 0;
/* DSM input (USART1) */
- dsm_init("/dev/ttyS0");
+ _dsm_fd = dsm_init("/dev/ttyS0");
/* S.bus input (USART3) */
sbus_init("/dev/ttyS2");
@@ -116,19 +169,13 @@ controls_tick() {
#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);
+ bool dsm_updated, st24_updated;
+ (void)dsm_port_input(&rssi, &dsm_updated, &st24_updated);
if (dsm_updated) {
- r_raw_rc_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
- r_raw_rc_count = temp_count & 0x7fff;
- if (temp_count & 0x8000)
- r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11;
- else
- 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);
-
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM;
+ }
+ if (st24_updated) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_ST24;
}
perf_end(c_gather_dsm);
@@ -191,7 +238,7 @@ controls_tick() {
/*
* If we received a new frame from any of the RC sources, process it.
*/
- if (dsm_updated || sbus_updated || ppm_updated) {
+ if (dsm_updated || sbus_updated || ppm_updated || st24_updated) {
/* record a bitmask of channels assigned */
unsigned assigned_channels = 0;
@@ -278,6 +325,9 @@ controls_tick() {
r_rc_values[mapped] = SIGNED_TO_REG(scaled);
assigned_channels |= (1 << mapped);
+ } else if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH) {
+ /* pick out override channel, indicated by special mapping */
+ rc_value_override = SIGNED_TO_REG(scaled);
}
}
}
@@ -371,15 +421,24 @@ controls_tick() {
* requested override.
*
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) < RC_CHANNEL_LOW_THRESH))
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(rc_value_override) < RC_CHANNEL_LOW_THRESH))
override = true;
+ /*
+ if the FMU is dead then enable override if we have a
+ mixer and OVERRIDE_IMMEDIATE is set
+ */
+ if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
+ (r_setup_arming & PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))
+ override = true;
+
if (override) {
r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE;
/* mix new RC input control values to servos */
- if (dsm_updated || sbus_updated || ppm_updated)
+ if (dsm_updated || sbus_updated || ppm_updated || st24_updated)
mixer_tick();
} else {