mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: RCInput_RPI: fix use of uninitiliazed value
../../libraries/AP_HAL_Linux/RCInput_RPI.cpp: In member function ‘virtual void Linux::RCInput_RPI::_timer_tick()’: ../../libraries/AP_HAL_Linux/RCInput_RPI.cpp:489:127: warning: ‘x’ may be used uninitialized in this function [-Wmaybe-uninitialized] counter = circle_buffer->bytes_available(curr_pointer, circle_buffer->get_offset(circle_buffer->_virt_pages, (uintptr_t)x)); ^
This commit is contained in:
parent
45d668df47
commit
5629f38b2c
|
@ -476,7 +476,7 @@ void RCInput_RPI::init()
|
|||
void RCInput_RPI::_timer_tick()
|
||||
{
|
||||
int j;
|
||||
void *x;
|
||||
void *x = nullptr;
|
||||
uint64_t signal_states(0);
|
||||
|
||||
//Now we are getting address in which DMAC is writing at current moment
|
||||
|
|
Loading…
Reference in New Issue