mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: made UARTDriver use TCPServerDevice
This commit is contained in:
parent
56f760f022
commit
a3f47878a2
@ -28,6 +28,7 @@
|
|||||||
#include "UDPDevice.h"
|
#include "UDPDevice.h"
|
||||||
#include "ConsoleDevice.h"
|
#include "ConsoleDevice.h"
|
||||||
#include "TCPClientDevice.h"
|
#include "TCPClientDevice.h"
|
||||||
|
#include "TCPServerDevice.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -71,24 +72,22 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
|||||||
if (device_path == NULL) {
|
if (device_path == NULL) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (_parseDevicePath(device_path)){
|
switch (_parseDevicePath(device_path)) {
|
||||||
case DEVICE_TCP:
|
case DEVICE_TCP:
|
||||||
{
|
{
|
||||||
_device = new TCPClientDevice(_ip, _base_port);
|
_tcp_start_connection();
|
||||||
_device->open();
|
|
||||||
_connected = false;
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case DEVICE_UDP:
|
case DEVICE_UDP:
|
||||||
{
|
{
|
||||||
_udp_start_connection();
|
_udp_start_connection();
|
||||||
_flow_control = FLOW_CONTROL_ENABLE;
|
_flow_control = FLOW_CONTROL_ENABLE;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case DEVICE_SERIAL:
|
case DEVICE_SERIAL:
|
||||||
{
|
{
|
||||||
if (!_serial_start_connection()) {
|
if (!_serial_start_connection()) {
|
||||||
break; /* Whatever it might mean */
|
break; /* Whatever it might mean */
|
||||||
@ -255,6 +254,23 @@ void LinuxUARTDriver::_udp_start_connection(void)
|
|||||||
_packetise = true;
|
_packetise = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void LinuxUARTDriver::_tcp_start_connection(void)
|
||||||
|
{
|
||||||
|
if (_flag != NULL) {
|
||||||
|
if (!strcmp(_flag, "wait")) {
|
||||||
|
_device = new TCPServerDevice(_ip, _base_port);
|
||||||
|
} else {
|
||||||
|
_device = new TCPClientDevice(_ip, _base_port);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
_device = new TCPClientDevice(_ip, _base_port);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (_device->open()) {
|
||||||
|
_connected = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
shutdown a UART
|
shutdown a UART
|
||||||
*/
|
*/
|
||||||
|
@ -48,6 +48,7 @@ private:
|
|||||||
void _allocate_buffers(uint16_t rxS, uint16_t txS);
|
void _allocate_buffers(uint16_t rxS, uint16_t txS);
|
||||||
void _deallocate_buffers();
|
void _deallocate_buffers();
|
||||||
void _udp_start_connection(void);
|
void _udp_start_connection(void);
|
||||||
|
void _tcp_start_connection(void);
|
||||||
bool _serial_start_connection(void);
|
bool _serial_start_connection(void);
|
||||||
|
|
||||||
enum device_type {
|
enum device_type {
|
||||||
|
Loading…
Reference in New Issue
Block a user