aboutsummaryrefslogtreecommitdiff
path: root/apps/px4io
diff options
context:
space:
mode:
Diffstat (limited to 'apps/px4io')
-rw-r--r--apps/px4io/controls.c4
-rw-r--r--apps/px4io/px4io.c7
-rw-r--r--apps/px4io/registers.c8
3 files changed, 11 insertions, 8 deletions
diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c
index 2d99116f8..b507078a1 100644
--- a/apps/px4io/controls.c
+++ b/apps/px4io/controls.c
@@ -213,7 +213,9 @@ controls_tick() {
if (assigned_channels == 0) {
rc_input_lost = true;
} else {
+ /* set RC OK flag and clear RC lost alarm */
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
+ r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_RC_LOST;
}
/*
@@ -274,7 +276,7 @@ controls_tick() {
* requested override.
*
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (r_rc_values[4] > RC_CHANNEL_HIGH_THRESH))
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) > RC_CHANNEL_HIGH_THRESH))
override = true;
if (override) {
diff --git a/apps/px4io/px4io.c b/apps/px4io/px4io.c
index 0c4838523..9de37e118 100644
--- a/apps/px4io/px4io.c
+++ b/apps/px4io/px4io.c
@@ -64,8 +64,7 @@ struct sys_state_s system_state;
static struct hrt_call serial_dma_call;
-/* global debug level for isr_debug() */
-volatile uint8_t debug_level = 0;
+/* store i2c reset count XXX this should be a register, together with other error counters */
volatile uint32_t i2c_loop_resets = 0;
/*
@@ -90,7 +89,7 @@ static char msg[NUM_MSG][40];
void
isr_debug(uint8_t level, const char *fmt, ...)
{
- if (level > debug_level) {
+ if (level > r_page_setup[PX4IO_P_SETUP_SET_DEBUG]) {
return;
}
va_list ap;
@@ -219,7 +218,7 @@ user_start(int argc, char *argv[])
struct mallinfo minfo = mallinfo();
isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x r=%u m=%u",
- (unsigned)debug_level,
+ (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG],
(unsigned)r_status_flags,
(unsigned)r_setup_arming,
(unsigned)r_setup_features,
diff --git a/apps/px4io/registers.c b/apps/px4io/registers.c
index 511a47f8d..645c1565d 100644
--- a/apps/px4io/registers.c
+++ b/apps/px4io/registers.c
@@ -137,7 +137,8 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_RELAYS] = 0,
[PX4IO_P_SETUP_VBATT_SCALE] = 10000,
[PX4IO_P_SETUP_IBATT_SCALE] = 0,
- [PX4IO_P_SETUP_IBATT_BIAS] = 0
+ [PX4IO_P_SETUP_IBATT_BIAS] = 0,
+ [PX4IO_P_SETUP_SET_DEBUG] = 0,
};
#define PX4IO_P_SETUP_FEATURES_VALID (0)
@@ -201,6 +202,7 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
system_state.fmu_data_received_time = hrt_absolute_time();
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
+ r_status_alarms &= ~PX4IO_P_STATUS_ALARMS_FMU_LOST;
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RAW_PWM;
break;
@@ -351,8 +353,8 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_SET_DEBUG:
- debug_level = value;
- isr_debug(0, "set debug %u\n", (unsigned)debug_level);
+ r_page_setup[PX4IO_P_SETUP_SET_DEBUG] = value;
+ isr_debug(0, "set debug %u\n", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG]);
break;
default: