forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'upstream/master' into fw_autoland_att_tecs_navigator_termination_controlgroups
Conflicts: src/modules/px4iofirmware/registers.c
This commit is contained in:
commit
a2cee83e57
|
@ -89,7 +89,7 @@ struct rc_input_values {
|
|||
/** number of channels actually being seen */
|
||||
uint32_t channel_count;
|
||||
|
||||
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 1000: full reception */
|
||||
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 255: full reception */
|
||||
int32_t rssi;
|
||||
|
||||
/** Input source */
|
||||
|
|
|
@ -1801,6 +1801,16 @@ PX4IO::print_status()
|
|||
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + i));
|
||||
|
||||
printf("\n");
|
||||
|
||||
if (raw_inputs > 0) {
|
||||
int frame_len = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_RC_DATA);
|
||||
printf("RC data (PPM frame len) %u us\n", frame_len);
|
||||
|
||||
if ((frame_len - raw_inputs * 2000 - 3000) < 0) {
|
||||
printf("WARNING WARNING WARNING! This RC receiver does not allow safe frame detection.\n");
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t mapped_inputs = io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_VALID);
|
||||
printf("mapped R/C inputs 0x%04x", mapped_inputs);
|
||||
|
||||
|
|
|
@ -282,6 +282,10 @@ static void hrt_call_invoke(void);
|
|||
* Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
|
||||
*/
|
||||
# ifdef CONFIG_ARCH_CORTEXM3
|
||||
# undef GTIM_CCER_CC1NP
|
||||
# undef GTIM_CCER_CC2NP
|
||||
# undef GTIM_CCER_CC3NP
|
||||
# undef GTIM_CCER_CC4NP
|
||||
# define GTIM_CCER_CC1NP 0
|
||||
# define GTIM_CCER_CC2NP 0
|
||||
# define GTIM_CCER_CC3NP 0
|
||||
|
@ -332,10 +336,10 @@ static void hrt_call_invoke(void);
|
|||
/*
|
||||
* PPM decoder tuning parameters
|
||||
*/
|
||||
# define PPM_MAX_PULSE_WIDTH 550 /* maximum width of a valid pulse */
|
||||
# define PPM_MAX_PULSE_WIDTH 700 /* maximum width of a valid pulse */
|
||||
# define PPM_MIN_CHANNEL_VALUE 800 /* shortest valid channel signal */
|
||||
# define PPM_MAX_CHANNEL_VALUE 2200 /* longest valid channel signal */
|
||||
# define PPM_MIN_START 2500 /* shortest valid start gap */
|
||||
# define PPM_MIN_START 2400 /* shortest valid start gap (only 2nd part of pulse) */
|
||||
|
||||
/* decoded PPM buffer */
|
||||
#define PPM_MIN_CHANNELS 5
|
||||
|
@ -345,6 +349,7 @@ static void hrt_call_invoke(void);
|
|||
#define PPM_CHANNEL_LOCK 4 /* should be less than the input timeout */
|
||||
|
||||
__EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS];
|
||||
__EXPORT uint16_t ppm_frame_length = 0;
|
||||
__EXPORT unsigned ppm_decoded_channels = 0;
|
||||
__EXPORT uint64_t ppm_last_valid_decode = 0;
|
||||
|
||||
|
@ -362,7 +367,8 @@ static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
|
|||
struct {
|
||||
uint16_t last_edge; /* last capture time */
|
||||
uint16_t last_mark; /* last significant edge */
|
||||
unsigned next_channel;
|
||||
uint16_t frame_start; /* the frame width */
|
||||
unsigned next_channel; /* next channel index */
|
||||
enum {
|
||||
UNSYNCH = 0,
|
||||
ARM,
|
||||
|
@ -447,7 +453,6 @@ hrt_ppm_decode(uint32_t status)
|
|||
|
||||
/* how long since the last edge? - this handles counter wrapping implicitely. */
|
||||
width = count - ppm.last_edge;
|
||||
ppm.last_edge = count;
|
||||
|
||||
ppm_edge_history[ppm_edge_next++] = width;
|
||||
|
||||
|
@ -491,6 +496,7 @@ hrt_ppm_decode(uint32_t status)
|
|||
ppm_buffer[i] = ppm_temp_buffer[i];
|
||||
|
||||
ppm_last_valid_decode = hrt_absolute_time();
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -500,13 +506,14 @@ hrt_ppm_decode(uint32_t status)
|
|||
/* next edge is the reference for the first channel */
|
||||
ppm.phase = ARM;
|
||||
|
||||
ppm.last_edge = count;
|
||||
return;
|
||||
}
|
||||
|
||||
switch (ppm.phase) {
|
||||
case UNSYNCH:
|
||||
/* we are waiting for a start pulse - nothing useful to do here */
|
||||
return;
|
||||
break;
|
||||
|
||||
case ARM:
|
||||
|
||||
|
@ -515,14 +522,23 @@ hrt_ppm_decode(uint32_t status)
|
|||
goto error; /* pulse was too long */
|
||||
|
||||
/* record the mark timing, expect an inactive edge */
|
||||
ppm.last_mark = count;
|
||||
ppm.phase = INACTIVE;
|
||||
return;
|
||||
ppm.last_mark = ppm.last_edge;
|
||||
|
||||
/* frame length is everything including the start gap */
|
||||
ppm_frame_length = (uint16_t)(ppm.last_edge - ppm.frame_start);
|
||||
ppm.frame_start = ppm.last_edge;
|
||||
ppm.phase = ACTIVE;
|
||||
break;
|
||||
|
||||
case INACTIVE:
|
||||
|
||||
/* we expect a short pulse */
|
||||
if (width > PPM_MAX_PULSE_WIDTH)
|
||||
goto error; /* pulse was too long */
|
||||
|
||||
/* this edge is not interesting, but now we are ready for the next mark */
|
||||
ppm.phase = ACTIVE;
|
||||
return;
|
||||
break;
|
||||
|
||||
case ACTIVE:
|
||||
/* determine the interval from the last mark */
|
||||
|
@ -543,10 +559,13 @@ hrt_ppm_decode(uint32_t status)
|
|||
ppm_temp_buffer[ppm.next_channel++] = interval;
|
||||
|
||||
ppm.phase = INACTIVE;
|
||||
return;
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
ppm.last_edge = count;
|
||||
return;
|
||||
|
||||
/* the state machine is corrupted; reset it */
|
||||
|
||||
error:
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
#define RC_CHANNEL_HIGH_THRESH 5000
|
||||
#define RC_CHANNEL_LOW_THRESH -5000
|
||||
|
||||
static bool ppm_input(uint16_t *values, uint16_t *num_values);
|
||||
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
|
||||
|
||||
static perf_counter_t c_gather_dsm;
|
||||
static perf_counter_t c_gather_sbus;
|
||||
|
@ -94,7 +94,7 @@ controls_tick() {
|
|||
* other. Don't do that.
|
||||
*/
|
||||
|
||||
/* receive signal strenght indicator (RSSI). 0 = no connection, 1000: perfect connection */
|
||||
/* receive signal strenght indicator (RSSI). 0 = no connection, 255: perfect connection */
|
||||
uint16_t rssi = 0;
|
||||
|
||||
perf_begin(c_gather_dsm);
|
||||
|
@ -108,7 +108,7 @@ controls_tick() {
|
|||
else
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
||||
|
||||
rssi = 1000;
|
||||
rssi = 255;
|
||||
}
|
||||
perf_end(c_gather_dsm);
|
||||
|
||||
|
@ -125,11 +125,11 @@ 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);
|
||||
bool ppm_updated = ppm_input(r_raw_rc_values, &r_raw_rc_count, &r_page_status[PX4IO_P_STATUS_RC_DATA]);
|
||||
if (ppm_updated) {
|
||||
|
||||
/* XXX sample RSSI properly here */
|
||||
rssi = 1000;
|
||||
rssi = 255;
|
||||
|
||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
|
||||
}
|
||||
|
@ -321,7 +321,7 @@ controls_tick() {
|
|||
}
|
||||
|
||||
static bool
|
||||
ppm_input(uint16_t *values, uint16_t *num_values)
|
||||
ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
|
||||
{
|
||||
bool result = false;
|
||||
|
||||
|
@ -345,6 +345,10 @@ ppm_input(uint16_t *values, uint16_t *num_values)
|
|||
/* clear validity */
|
||||
ppm_last_valid_decode = 0;
|
||||
|
||||
/* store PPM frame length */
|
||||
if (num_values)
|
||||
*frame_len = ppm_frame_length;
|
||||
|
||||
/* good if we got any channels */
|
||||
result = (*num_values > 0);
|
||||
}
|
||||
|
|
|
@ -128,7 +128,8 @@
|
|||
#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, 1000: perfect reception */
|
||||
#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 */
|
||||
|
|
|
@ -89,7 +89,9 @@ uint16_t r_page_status[] = {
|
|||
[PX4IO_P_STATUS_IBATT] = 0,
|
||||
[PX4IO_P_STATUS_VSERVO] = 0,
|
||||
[PX4IO_P_STATUS_VRSSI] = 0,
|
||||
[PX4IO_P_STATUS_PRSSI] = 0
|
||||
[PX4IO_P_STATUS_PRSSI] = 0,
|
||||
[PX4IO_P_STATUS_NRSSI] = 0,
|
||||
[PX4IO_P_STATUS_RC_DATA] = 0
|
||||
};
|
||||
|
||||
/**
|
||||
|
|
|
@ -280,7 +280,7 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
|
|||
*rssi = 100; // XXX magic number indicating bad signal, but not a signal loss (yet)
|
||||
}
|
||||
|
||||
*rssi = 1000;
|
||||
*rssi = 255;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -57,6 +57,7 @@ __BEGIN_DECLS
|
|||
* PPM decoder state
|
||||
*/
|
||||
__EXPORT extern uint16_t ppm_buffer[PPM_MAX_CHANNELS]; /**< decoded PPM channel values */
|
||||
__EXPORT extern uint16_t ppm_frame_length; /**< length of the decoded PPM frame (includes gap) */
|
||||
__EXPORT extern unsigned ppm_decoded_channels; /**< count of decoded channels */
|
||||
__EXPORT extern hrt_abstime ppm_last_valid_decode; /**< timestamp of the last valid decode */
|
||||
|
||||
|
|
Loading…
Reference in New Issue