Merged, removed unneeded line

This commit is contained in:
Andrew Tridgell 2013-02-07 14:31:26 +11:00 committed by Lorenz Meier
parent 3b9488cc8b
commit 9f15f38e57
3 changed files with 48 additions and 9 deletions

View File

@ -44,6 +44,7 @@
#include <errno.h>
#include <string.h>
#include <poll.h>
#include <signal.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
@ -69,6 +70,9 @@ volatile uint32_t i2c_loop_resets = 0;
struct hrt_call loop_overtime_call;
// this allows wakeup of the main task via a signal
static pid_t daemon_pid;
/*
a set of debug buffers to allow us to send debug information from ISRs
@ -130,9 +134,24 @@ static void loop_overtime(void *arg)
hrt_call_after(&loop_overtime_call, 50000, (hrt_callout)loop_overtime, NULL);
}
static void wakeup_handler(int signo, siginfo_t *info, void *ucontext)
{
// nothing to do - we just want poll() to return
}
/*
wakeup the main task using a signal
*/
void daemon_wakeup(void)
{
kill(daemon_pid, SIGUSR1);
}
int user_start(int argc, char *argv[])
{
daemon_pid = getpid();
/* run C++ ctors before we go any further */
up_cxxinitialize();
@ -183,6 +202,18 @@ int user_start(int argc, char *argv[])
/* add a performance counter for mixing */
perf_counter_t mixer_perf = perf_alloc(PC_ELAPSED, "mix");
/*
* setup a null handler for SIGUSR1 - we will use this for wakeup from poll()
*/
struct sigaction sa;
memset(&sa, 0, sizeof(sa));
sa.sa_sigaction = wakeup_handler;
sigfillset(&sa.sa_mask);
sigdelset(&sa.sa_mask, SIGUSR1);
if (sigaction(SIGUSR1, &sa, NULL) != OK) {
debug("Failed to setup SIGUSR1 handler\n");
}
/* run the mixer at ~300Hz (for now...) */
/* XXX we should use CONFIG_IDLE_CUSTOM and take over the idle thread instead of running two additional tasks */
uint16_t counter=0;

View File

@ -143,30 +143,29 @@ extern struct sys_state_s system_state;
extern void mixer_tick(void);
extern void mixer_handle_text(const void *buffer, size_t length);
/*
/**
* Safety switch/LED.
*/
extern void safety_init(void);
/*
/**
* FMU communications
*/
extern void comms_main(void) __attribute__((noreturn));
extern void i2c_init(void);
/*
/**
* Register space
*/
extern void registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values);
extern int registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_values);
/*
/**
* Sensors/misc inputs
*/
extern int adc_init(void);
extern uint16_t adc_measure(unsigned channel);
/*
/**
* R/C receiver handling.
*
* Input functions return true when they receive an update from the RC controller.
@ -177,9 +176,14 @@ extern bool dsm_input(uint16_t *values, uint16_t *num_values);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values);
/* global debug level for isr_debug() */
/** global debug level for isr_debug() */
extern volatile uint8_t debug_level;
/**
* Wake up mixer.
*/
void daemon_wakeup(void);
/* send a debug message to the console */
extern void isr_debug(uint8_t level, const char *fmt, ...);

View File

@ -198,10 +198,12 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
values++;
}
/* XXX we should cause a mixer tick ASAP */
system_state.fmu_data_received_time = hrt_absolute_time();
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RAW_PWM;
// wake up daemon to trigger mixer
daemon_wakeup();
break;
/* handle raw PWM input */
@ -218,9 +220,11 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
values++;
}
/* XXX we should cause a mixer tick ASAP */
system_state.fmu_data_received_time = hrt_absolute_time();
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK | PX4IO_P_STATUS_FLAGS_RAW_PWM;
// wake up the main thread to trigger mixer
daemon_wakeup();
break;
/* handle setup for servo failsafe values */