Browse Source

HAL_Linux: fixed safety of RCInput code

don't loop forever waiting for pulses
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
5fb2ad0068
  1. 75
      libraries/AP_HAL_Linux/RCInput.cpp
  2. 23
      libraries/AP_HAL_Linux/RCInput.h

75
libraries/AP_HAL_Linux/RCInput.cpp

@ -18,13 +18,15 @@
using namespace Linux; using namespace Linux;
LinuxRCInput::LinuxRCInput() : LinuxRCInput::LinuxRCInput() :
new_rc_input(false) new_rc_input(false),
_channel_counter(-1)
{} {}
void LinuxRCInput::init(void* machtnichts) void LinuxRCInput::init(void* machtnichts)
{ {
int mem_fd = open("/dev/mem", O_RDWR|O_SYNC); int mem_fd = open("/dev/mem", O_RDWR|O_SYNC);
ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, PRUSS_SHAREDRAM_BASE); ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
MAP_SHARED, mem_fd, RCIN_PRUSS_SHAREDRAM_BASE);
close(mem_fd); close(mem_fd);
ring_buffer->ring_head = 0; ring_buffer->ring_head = 0;
} }
@ -95,27 +97,62 @@ void LinuxRCInput::clear_overrides()
} }
} }
void LinuxRCInput::_timer_tick()
/*
process a pulse of the given width
*/
void LinuxRCInput::_process_pulse(uint16_t width_usec)
{ {
uint8_t channel_ctr; if (width_usec >= 4000) {
uint16_t s1_time, s2_time; // a long pulse indicates the end of a frame. Reset the
//scan for the latest start pulse // channel counter so next pulse is channel 0
while(ring_buffer->buffer[ring_buffer->ring_head].delta_t < 8000){ if (_channel_counter != -1) {
ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES; new_rc_input = true;
_num_channels = _channel_counter;
} }
for(channel_ctr = 0; channel_ctr < LINUX_RC_INPUT_NUM_CHANNELS; channel_ctr++){ _channel_counter = 0;
ring_buffer->ring_head = (ring_buffer->ring_head + 2) % NUM_RING_ENTRIES; return;
//wait until we receive two pulse_width(State1 & State2) values inside buffer }
while(ring_buffer->ring_head <= (ring_buffer->ring_tail)); if (_channel_counter == -1) {
s1_time = (uint32_t)ring_buffer->buffer[ring_buffer->ring_head - 1].delta_t; // we are not synchronised
s2_time = (uint32_t)ring_buffer->buffer[ring_buffer->ring_head].delta_t; return;
_pulse_capt[channel_ctr] = s1_time + s2_time; }
if(_pulse_capt[channel_ctr] > RC_INPUT_MAX_PULSEWIDTH){
_pulse_capt[channel_ctr] = RC_INPUT_MAX_PULSEWIDTH; // take a reading for the current channel
_pulse_capt[_channel_counter] = width_usec;
// move to next channel
_channel_counter++;
// if we have reached the maximum supported channels then
// mark as unsynchronised, so we wait for a wide pulse
if (_channel_counter >= LINUX_RC_INPUT_NUM_CHANNELS) {
new_rc_input = true;
_channel_counter = -1;
_num_channels = _channel_counter;
} }
else if(_pulse_capt[channel_ctr] < RC_INPUT_MIN_PULSEWIDTH){
_pulse_capt[channel_ctr] = RC_INPUT_MIN_PULSEWIDTH;
} }
/*
called at 1kHz to check for new pulse capture data from the PRU
*/
void LinuxRCInput::_timer_tick()
{
while (ring_buffer->ring_head != ring_buffer->ring_tail) {
if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) {
// invalid ring_tail from PRU - ignore RC input
return;
}
if (ring_buffer->buffer[ring_buffer->ring_head].pin_value == 1) {
// remember the time we spent in the low state
_s0_time = ring_buffer->buffer[ring_buffer->ring_head].delta_t;
} else {
// the pulse value is the sum of the time spent in the low
// and high states
_process_pulse(ring_buffer->buffer[ring_buffer->ring_head].delta_t + _s0_time);
}
// move to the next ring buffer entry
ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES;
} }
} }

23
libraries/AP_HAL_Linux/RCInput.h

@ -4,10 +4,10 @@
#include <AP_HAL_Linux.h> #include <AP_HAL_Linux.h>
#define LINUX_RC_INPUT_NUM_CHANNELS 8 #define LINUX_RC_INPUT_NUM_CHANNELS 16
#define PRUSS_SHAREDRAM_BASE 0x4a312000
#define NUM_RING_ENTRIES 200
#define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
#define NUM_RING_ENTRIES 200
class Linux::LinuxRCInput : public AP_HAL::RCInput { class Linux::LinuxRCInput : public AP_HAL::RCInput {
public: public:
@ -25,21 +25,30 @@ public:
void _timer_tick(void); void _timer_tick(void);
private: private:
bool new_rc_input; volatile bool new_rc_input;
uint16_t _pulse_capt[LINUX_RC_INPUT_NUM_CHANNELS]; uint16_t _pulse_capt[LINUX_RC_INPUT_NUM_CHANNELS];
uint8_t _num_channels; uint8_t _num_channels;
/* override state */ /* override state */
uint16_t _override[LINUX_RC_INPUT_NUM_CHANNELS]; uint16_t _override[LINUX_RC_INPUT_NUM_CHANNELS];
// shared ring buffer with the PRU which records pin transitions
struct ring_buffer { struct ring_buffer {
volatile uint16_t ring_head; volatile uint16_t ring_head; // owned by ARM CPU
volatile uint16_t ring_tail; volatile uint16_t ring_tail; // owned by the PRU
struct __attribute__((__packed__)) { struct {
uint16_t pin_value; uint16_t pin_value;
uint16_t delta_t; uint16_t delta_t;
} buffer[NUM_RING_ENTRIES]; } buffer[NUM_RING_ENTRIES];
}; };
volatile struct ring_buffer *ring_buffer; volatile struct ring_buffer *ring_buffer;
// the channel we will receive input from next, or -1 when not synchronised
int8_t _channel_counter;
// time spent in the low state
uint16_t _s0_time;
void _process_pulse(uint16_t width_usec);
}; };
#endif // __AP_HAL_LINUX_RCINPUT_H__ #endif // __AP_HAL_LINUX_RCINPUT_H__

Loading…
Cancel
Save