forked from Archive/PX4-Autopilot
First stab at implementing better RSSI based connection status estimation, still needs some work and testing
This commit is contained in:
parent
a673fa3926
commit
9883a346a0
|
@ -89,6 +89,9 @@ struct rc_input_values {
|
||||||
/** number of channels actually being seen */
|
/** number of channels actually being seen */
|
||||||
uint32_t channel_count;
|
uint32_t channel_count;
|
||||||
|
|
||||||
|
/** receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 1000: full reception */
|
||||||
|
int32_t rssi;
|
||||||
|
|
||||||
/** Input source */
|
/** Input source */
|
||||||
enum RC_INPUT_SOURCE input_source;
|
enum RC_INPUT_SOURCE input_source;
|
||||||
|
|
||||||
|
|
|
@ -94,6 +94,9 @@ controls_tick() {
|
||||||
* other. Don't do that.
|
* other. Don't do that.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/* receive signal strenght indicator (RSSI). 0 = no connection, 1000: perfect connection */
|
||||||
|
uint16_t rssi = 0;
|
||||||
|
|
||||||
perf_begin(c_gather_dsm);
|
perf_begin(c_gather_dsm);
|
||||||
uint16_t temp_count = r_raw_rc_count;
|
uint16_t temp_count = r_raw_rc_count;
|
||||||
bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count);
|
bool dsm_updated = dsm_input(r_raw_rc_values, &temp_count);
|
||||||
|
@ -104,14 +107,15 @@ controls_tick() {
|
||||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
||||||
else
|
else
|
||||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_RC_DSM11;
|
||||||
|
|
||||||
|
rssi = 1000;
|
||||||
}
|
}
|
||||||
perf_end(c_gather_dsm);
|
perf_end(c_gather_dsm);
|
||||||
|
|
||||||
perf_begin(c_gather_sbus);
|
perf_begin(c_gather_sbus);
|
||||||
bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, PX4IO_CONTROL_CHANNELS /* XXX this should be INPUT channels, once untangled */);
|
bool sbus_updated = sbus_input(r_raw_rc_values, &r_raw_rc_count, &rssi, PX4IO_CONTROL_CHANNELS /* XXX this should be INPUT channels, once untangled */);
|
||||||
if (sbus_updated) {
|
if (sbus_updated) {
|
||||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
|
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_SBUS;
|
||||||
r_raw_rc_count = 8;
|
|
||||||
}
|
}
|
||||||
perf_end(c_gather_sbus);
|
perf_end(c_gather_sbus);
|
||||||
|
|
||||||
|
@ -122,10 +126,19 @@ controls_tick() {
|
||||||
*/
|
*/
|
||||||
perf_begin(c_gather_ppm);
|
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);
|
||||||
if (ppm_updated)
|
if (ppm_updated) {
|
||||||
|
|
||||||
|
/* XXX sample RSSI properly here */
|
||||||
|
rssi = 1000;
|
||||||
|
|
||||||
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
|
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_PPM;
|
||||||
|
}
|
||||||
perf_end(c_gather_ppm);
|
perf_end(c_gather_ppm);
|
||||||
|
|
||||||
|
/* limit number of channels to allowable data size */
|
||||||
|
if (r_raw_rc_count > PX4IO_INPUT_CHANNELS)
|
||||||
|
r_raw_rc_count = PX4IO_INPUT_CHANNELS;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* In some cases we may have received a frame, but input has still
|
* In some cases we may have received a frame, but input has still
|
||||||
* been lost.
|
* been lost.
|
||||||
|
@ -221,7 +234,7 @@ controls_tick() {
|
||||||
* This might happen if a protocol-based receiver returns an update
|
* This might happen if a protocol-based receiver returns an update
|
||||||
* that contains no channels that we have mapped.
|
* that contains no channels that we have mapped.
|
||||||
*/
|
*/
|
||||||
if (assigned_channels == 0) {
|
if (assigned_channels == 0 || rssi == 0) {
|
||||||
rc_input_lost = true;
|
rc_input_lost = true;
|
||||||
} else {
|
} else {
|
||||||
/* set RC OK flag */
|
/* set RC OK flag */
|
||||||
|
|
|
@ -124,6 +124,7 @@
|
||||||
#define PX4IO_P_STATUS_VSERVO 6 /* [2] servo rail voltage in mV */
|
#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_VRSSI 7 /* [2] RSSI voltage */
|
||||||
#define PX4IO_P_STATUS_PRSSI 8 /* [2] RSSI PWM value */
|
#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 */
|
||||||
|
|
||||||
/* array of post-mix actuator outputs, -10000..10000 */
|
/* array of post-mix actuator outputs, -10000..10000 */
|
||||||
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
#define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */
|
||||||
|
|
|
@ -209,7 +209,7 @@ extern int dsm_init(const char *device);
|
||||||
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
|
extern bool dsm_input(uint16_t *values, uint16_t *num_values);
|
||||||
extern void dsm_bind(uint16_t cmd, int pulses);
|
extern void dsm_bind(uint16_t cmd, int pulses);
|
||||||
extern int sbus_init(const char *device);
|
extern int sbus_init(const char *device);
|
||||||
extern bool sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels);
|
extern bool sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels);
|
||||||
|
|
||||||
/** global debug level for isr_debug() */
|
/** global debug level for isr_debug() */
|
||||||
extern volatile uint8_t debug_level;
|
extern volatile uint8_t debug_level;
|
||||||
|
|
|
@ -114,7 +114,7 @@ uint16_t r_page_servos[PX4IO_SERVO_COUNT];
|
||||||
uint16_t r_page_raw_rc_input[] =
|
uint16_t r_page_raw_rc_input[] =
|
||||||
{
|
{
|
||||||
[PX4IO_P_RAW_RC_COUNT] = 0,
|
[PX4IO_P_RAW_RC_COUNT] = 0,
|
||||||
[PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_CONTROL_CHANNELS)] = 0
|
[PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + 24)] = 0 // XXX ensure we have enough space to decode beefy RX, will be replaced by patch soon
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -87,7 +87,7 @@ static unsigned partial_frame_count;
|
||||||
|
|
||||||
unsigned sbus_frame_drops;
|
unsigned sbus_frame_drops;
|
||||||
|
|
||||||
static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t max_channels);
|
static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels);
|
||||||
|
|
||||||
int
|
int
|
||||||
sbus_init(const char *device)
|
sbus_init(const char *device)
|
||||||
|
@ -118,7 +118,7 @@ sbus_init(const char *device)
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels)
|
sbus_input(uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_channels)
|
||||||
{
|
{
|
||||||
ssize_t ret;
|
ssize_t ret;
|
||||||
hrt_abstime now;
|
hrt_abstime now;
|
||||||
|
@ -175,7 +175,7 @@ sbus_input(uint16_t *values, uint16_t *num_values, uint16_t max_channels)
|
||||||
* decode it.
|
* decode it.
|
||||||
*/
|
*/
|
||||||
partial_frame_count = 0;
|
partial_frame_count = 0;
|
||||||
return sbus_decode(now, values, num_values, max_channels);
|
return sbus_decode(now, values, num_values, rssi, max_channels);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -215,7 +215,7 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static bool
|
static bool
|
||||||
sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t max_values)
|
sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint16_t *rssi, uint16_t max_values)
|
||||||
{
|
{
|
||||||
/* check frame boundary markers to avoid out-of-sync cases */
|
/* check frame boundary markers to avoid out-of-sync cases */
|
||||||
if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
|
if ((frame[0] != 0x0f) || (frame[24] != 0x00)) {
|
||||||
|
@ -266,8 +266,9 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
|
||||||
|
|
||||||
/* decode and handle failsafe and frame-lost flags */
|
/* decode and handle failsafe and frame-lost flags */
|
||||||
if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
|
if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
|
||||||
/* emulate throttle failsafe for maximum compatibility and do not destroy any channel data */
|
/* report that we failed to read anything valid off the receiver */
|
||||||
values[2] = 900;
|
*rssi = 0;
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
|
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 or try to calculate some kind of RSSI information - to be implemented
|
||||||
|
@ -276,8 +277,10 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, uint
|
||||||
* condition as fail-safe greatly reduces the reliability and range of the radio link,
|
* condition as fail-safe greatly reduces the reliability and range of the radio link,
|
||||||
* e.g. by prematurely issueing return-to-launch!!! */
|
* e.g. by prematurely issueing return-to-launch!!! */
|
||||||
|
|
||||||
// values[2] = 888; // marker for debug purposes
|
*rssi = 100; // XXX magic number indicating bad signal, but not a signal loss (yet)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
*rssi = 1000;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue