AP_HAL_Linux: RCInput_RPI: fix coding style

- Remove trailing whitespaces
 - Remove some uneeded comments
 - Fix indentation
 - Replace some breaks inside the loop by checking in the loop itself
This commit is contained in:
Lucas De Marchi 2016-01-13 11:08:30 -02:00
parent 79d56073f7
commit 51fd0b3d55

View File

@ -52,7 +52,7 @@ static uint16_t RcChnGpioTbl[RCIN_RPI_CHN_NUM] = {
static uint16_t RcChnGpioTbl[RCIN_RPI_CHN_NUM] = { static uint16_t RcChnGpioTbl[RCIN_RPI_CHN_NUM] = {
RPI_GPIO_4 RPI_GPIO_4
}; };
#endif // CONFIG_HAL_BOARD_SUBTYPE #endif
//Memory Addresses //Memory Addresses
#define RCIN_RPI_RPI1_DMA_BASE 0x20007000 #define RCIN_RPI_RPI1_DMA_BASE 0x20007000
@ -162,7 +162,8 @@ Memory_table::~Memory_table()
free(_phys_pages); free(_phys_pages);
} }
// This function returns physical address with help of pointer, which is offset from the beginning of the buffer. /* Return physical address with help of pointer, which is offset from the
* beginning of the buffer. */
void* Memory_table::get_page(void** const pages, uint32_t addr) const void* Memory_table::get_page(void** const pages, uint32_t addr) const
{ {
if (addr >= PAGE_SIZE * _page_count) { if (addr >= PAGE_SIZE * _page_count) {
@ -171,11 +172,9 @@ void* Memory_table::get_page(void** const pages, uint32_t addr) const
return (uint8_t*)pages[(uint32_t) addr / 4096] + addr % 4096; return (uint8_t*)pages[(uint32_t) addr / 4096] + addr % 4096;
} }
//Get virtual address from the corresponding physical address from memory_table. // Get virtual address from the corresponding physical address from memory_table.
void* Memory_table::get_virt_addr(const uint32_t phys_addr) const void *Memory_table::get_virt_addr(const uint32_t phys_addr) const
{ {
// FIXME: Can't the address be calculated directly?
// FIXME: if the address room in _phys_pages is not fragmented one may avoid a complete loop ..
uint32_t i = 0; uint32_t i = 0;
for (; i < _page_count; i++) { for (; i < _page_count; i++) {
if ((uintptr_t) _phys_pages[i] == (((uintptr_t) phys_addr) & 0xFFFFF000)) { if ((uintptr_t) _phys_pages[i] == (((uintptr_t) phys_addr) & 0xFFFFF000)) {
@ -185,14 +184,13 @@ void* Memory_table::get_virt_addr(const uint32_t phys_addr) const
return NULL; return NULL;
} }
// FIXME: in-congruent function style see above // Return offset from the beginning of the buffer using virtual address and memory_table.
// This function returns offset from the beginning of the buffer using virtual address and memory_table.
uint32_t Memory_table::get_offset(void ** const pages, const uint32_t addr) const uint32_t Memory_table::get_offset(void ** const pages, const uint32_t addr) const
{ {
uint32_t i = 0; uint32_t i = 0;
for (; i < _page_count; i++) { for (; i < _page_count; i++) {
if ((uintptr_t) pages[i] == (addr & 0xFFFFF000) ) { if ((uintptr_t) pages[i] == (addr & 0xFFFFF000) ) {
return (i*PAGE_SIZE + (addr & 0xFFF)); return (i * PAGE_SIZE + (addr & 0xFFF));
} }
} }
return -1; return -1;
@ -203,8 +201,7 @@ uint32_t Memory_table::bytes_available(const uint32_t read_addr, const uint32_t
{ {
if (write_addr > read_addr) { if (write_addr > read_addr) {
return (write_addr - read_addr); return (write_addr - read_addr);
} } else {
else {
return _page_count * PAGE_SIZE - (read_addr - write_addr); return _page_count * PAGE_SIZE - (read_addr - write_addr);
} }
} }
@ -221,8 +218,7 @@ void RCInput_RPI::set_physical_addresses(int version)
dma_base = RCIN_RPI_RPI1_DMA_BASE; dma_base = RCIN_RPI_RPI1_DMA_BASE;
clk_base = RCIN_RPI_RPI1_CLK_BASE; clk_base = RCIN_RPI_RPI1_CLK_BASE;
pcm_base = RCIN_RPI_RPI1_PCM_BASE; pcm_base = RCIN_RPI_RPI1_PCM_BASE;
} } else if (version == 2) {
else if (version == 2) {
dma_base = RCIN_RPI_RPI2_DMA_BASE; dma_base = RCIN_RPI_RPI2_DMA_BASE;
clk_base = RCIN_RPI_RPI2_CLK_BASE; clk_base = RCIN_RPI_RPI2_CLK_BASE;
pcm_base = RCIN_RPI_RPI2_PCM_BASE; pcm_base = RCIN_RPI_RPI2_PCM_BASE;
@ -299,10 +295,9 @@ void RCInput_RPI::init_ctrl_data()
// fprintf(stderr, "ERROR SEARCH1\n"); // fprintf(stderr, "ERROR SEARCH1\n");
uint32_t i = 0; uint32_t i = 0;
for (i = 0; i < 7 * 128 * RCIN_RPI_BUFFER_LENGTH; i++) // 7 * 128 * 8 == 7168 for (i = 0; i < 7 * 128 * RCIN_RPI_BUFFER_LENGTH; i++) {
{
//Transfer timer every 7th sample //Transfer timer every 7th sample
if(i % 7 == 0) { if (i % 7 == 0) {
cbp_curr = (dma_cb_t*)con_blocks->get_page(con_blocks->_virt_pages, cbp); cbp_curr = (dma_cb_t*)con_blocks->get_page(con_blocks->_virt_pages, cbp);
init_dma_cb(&cbp_curr, RCIN_RPI_DMA_NO_WIDE_BURSTS | RCIN_RPI_DMA_WAIT_RESP | RCIN_RPI_DMA_DEST_INC | RCIN_RPI_DMA_SRC_INC, RCIN_RPI_TIMER_BASE, init_dma_cb(&cbp_curr, RCIN_RPI_DMA_NO_WIDE_BURSTS | RCIN_RPI_DMA_WAIT_RESP | RCIN_RPI_DMA_DEST_INC | RCIN_RPI_DMA_SRC_INC, RCIN_RPI_TIMER_BASE,
@ -442,7 +437,7 @@ void RCInput_RPI::init_registers()
void RCInput_RPI::init() void RCInput_RPI::init()
{ {
uint64_t signal_states(0); uint64_t signal_states = 0;
init_registers(); init_registers();
@ -481,15 +476,13 @@ void RCInput_RPI::init()
void RCInput_RPI::_timer_tick() void RCInput_RPI::_timer_tick()
{ {
int j; int j;
void* x; void *x;
uint64_t signal_states(0); uint64_t signal_states(0);
//Now we are getting address in which DMAC is writing at current moment //Now we are getting address in which DMAC is writing at current moment
dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8]); dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8]);
for(j = 1; j >= -1; j--){ for (j = 1; j >= -1 && x == nullptr; j--) {
x = circle_buffer->get_virt_addr((ad + j)->dst); x = circle_buffer->get_virt_addr((ad + j)->dst);
if(x != NULL) {
break;}
} }
//How many bytes have DMA transfered (and we can process)? //How many bytes have DMA transfered (and we can process)?
@ -525,11 +518,8 @@ void RCInput_RPI::_timer_tick()
if (rc_channels[i].curr_signal == 0) { if (rc_channels[i].curr_signal == 0) {
rc_channels[i].width_s0 = (uint16_t)rc_channels[i].delta_time; rc_channels[i].width_s0 = (uint16_t)rc_channels[i].delta_time;
rc_channels[i].state = RCIN_RPI_ONE_STATE; rc_channels[i].state = RCIN_RPI_ONE_STATE;
break;
} }
else {
break; break;
}
case RCIN_RPI_ONE_STATE: case RCIN_RPI_ONE_STATE:
if (rc_channels[i].curr_signal == 1) { if (rc_channels[i].curr_signal == 1) {
rc_channels[i].width_s1 = (uint16_t)rc_channels[i].delta_time; rc_channels[i].width_s1 = (uint16_t)rc_channels[i].delta_time;
@ -540,14 +530,11 @@ void RCInput_RPI::_timer_tick()
#else #else
_process_rc_pulse(rc_channels[i].width_s0, _process_rc_pulse(rc_channels[i].width_s0,
rc_channels[i].width_s1); rc_channels[i].width_s1);
#endif // CONFIG_HAL_BOARD_SUBTYPE #endif
break;
} }
else{
break; break;
} }
} }
}
rc_channels[i].last_signal = rc_channels[i].curr_signal; rc_channels[i].last_signal = rc_channels[i].curr_signal;
} }
curr_pointer += 8; curr_pointer += 8;
@ -555,7 +542,7 @@ void RCInput_RPI::_timer_tick()
if (curr_pointer >= circle_buffer->get_page_count()*PAGE_SIZE) { if (curr_pointer >= circle_buffer->get_page_count()*PAGE_SIZE) {
curr_pointer = 0; curr_pointer = 0;
} }
curr_tick+=curr_tick_inc; curr_tick += curr_tick_inc;
} }
} }
#endif // CONFIG_HAL_BOARD_SUBTYPE #endif