Browse Source

AP_HAL_Linux: encapsulated LinuxUARTDriver::_deallocate_buffers

master
Staroselskii Georgii 10 years ago committed by Andrew Tridgell
parent
commit
656399541f
  1. 34
      libraries/AP_HAL_Linux/UARTDriver.cpp
  2. 1
      libraries/AP_HAL_Linux/UARTDriver.h

34
libraries/AP_HAL_Linux/UARTDriver.cpp

@ -175,6 +175,25 @@ void LinuxUARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS) @@ -175,6 +175,25 @@ void LinuxUARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
}
}
void LinuxUARTDriver::_deallocate_buffers()
{
if (_readbuf) {
free(_readbuf);
_readbuf = NULL;
}
if (_writebuf) {
free(_writebuf);
_writebuf = NULL;
}
_readbuf_size = _writebuf_size = 0;
_writebuf_head = 0;
_writebuf_tail = 0;
_readbuf_head = 0;
_readbuf_tail = 0;
}
/*
Device path accepts the following syntaxes:
- /dev/ttyO1
@ -396,19 +415,8 @@ void LinuxUARTDriver::end() @@ -396,19 +415,8 @@ void LinuxUARTDriver::end()
}
_rd_fd = -1;
_wr_fd = -1;
if (_readbuf) {
free(_readbuf);
_readbuf = NULL;
}
if (_writebuf) {
free(_writebuf);
_writebuf = NULL;
}
_readbuf_size = _writebuf_size = 0;
_writebuf_head = 0;
_writebuf_tail = 0;
_readbuf_head = 0;
_readbuf_tail = 0;
_deallocate_buffers();
}

1
libraries/AP_HAL_Linux/UARTDriver.h

@ -48,6 +48,7 @@ private: @@ -48,6 +48,7 @@ private:
enum flow_control _flow_control;
void _allocate_buffers(uint16_t rxS, uint16_t txS);
void _deallocate_buffers();
void _tcp_start_connection(bool wait_for_connection);
void _udp_start_connection(void);
bool _serial_start_connection(void);

Loading…
Cancel
Save