tcpStream.cpp
Go to the documentation of this file.
1 #include <arpa/inet.h>
2 #include <cerrno>
3 #include <cstdint>
4 #include <cstdio>
5 #include <fcntl.h>
6 #include <netinet/in.h>
7 #include <sys/socket.h>
8 #include <sys/types.h>
9 #include <unistd.h>
10 
11 #include "osefTypes.h"
12 #include "tlvCommon.h"
13 
14 #include "tcpStream.h"
15 
16 const char *TcpStreamReader::default_ip = "192.168.2.2";
17 const uint16_t TcpStreamReader::default_port = 11120;
18 
19 // Open socket with relevant settings for our usage
20 void open_socket(int &socket_fd)
21 {
22  int fd, fd_flags;
23 
24  fd = socket(AF_INET, SOCK_STREAM, 0);
25  if (fd < 0) {
26  printf("Error: cannot create socket\n");
27  return;
28  }
29 
30  // Lose the pesky "Address already in use" error message
31  int yes = 1;
32  if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)) < 0)
33  printf("Error: failed allowing address reuse\n");
34 
35  socket_fd = fd;
36 }
37 
38 // Close socket
39 void close_socket(int &socket_fd)
40 {
41  if (socket_fd < 0)
42  return;
43 
44  while (close(socket_fd))
45  continue;
46 
47  socket_fd = -1;
48 }
49 
50 // Read specified bytes from socket and discard them
51 void emptySocket(int socket_fd, int bytes_remaining)
52 {
53  constexpr int size_temp = 1000;
54  uint8_t temp[size_temp];
55  while (bytes_remaining > 0) {
56  unsigned read_size = (bytes_remaining >= size_temp) ? size_temp : bytes_remaining;
57  int n = read(socket_fd, temp, read_size);
58  if (n >= 0)
59  bytes_remaining -= n;
60  }
61 }
62 
63 // To be repeatedly called to read socket in order to get a frame in the
64 // specified buffer
65 int readSocket(int socket_fd, uint8_t *buffer, const size_t buffer_size, int &frame_write_index)
66 {
67  // frame_write_index indicates the number of bytes already read
68  uint8_t *dest = buffer + frame_write_index;
69 
70  // If we haven't finished to read the tlv header yet, attempt to read it, else
71  // continue to read the tlv value
72  Tlv::tlv_s *tlv = (Tlv::tlv_s *)buffer;
73  int bytes_to_read =
74  (frame_write_index < (int)sizeof(Tlv::header_s)) ? sizeof(Tlv::header_s) : Tlv::getSize(*tlv);
75  int n = read(socket_fd, dest, bytes_to_read - frame_write_index);
76 
77  // Handle special return codes
78  if (n == -1 && (errno == EAGAIN || errno == ECONNREFUSED)) {
79  return 2;
80 
81  } else if (n == 0) {
82  return 0;
83 
84  } else if (n == -1) {
85  printf("Error in reading socket (errno = %d)\n", errno);
86  return -1;
87  }
88 
89  // If no error occurred, increment the write index by the number of bytes read
90  frame_write_index += n;
91 
92  // Check type to mitigate retro-compatibility issues (parsed type will be '4'
93  // if server uses former format, which is non-osef)
94  if (frame_write_index == sizeof(Tlv::header_s) && tlv->getType() != OSEF_TYPE_TIMESTAMPED_DATA) {
95  printf("Receive malformated frame: tlv type (%d) is wrong\n", tlv->getType());
96  return -1;
97  }
98 
99  // If the frame is oversized for the buffer, ignore it and delete
100  // corresponding data in incoming socket
101  if (frame_write_index == sizeof(Tlv::header_s) && Tlv::getSize(*tlv) > buffer_size) {
102  printf("Incoming frame too large : %lu (max allocated size %lu)\n", Tlv::getSize(*tlv), buffer_size);
103  emptySocket(socket_fd, (int)(Tlv::getSize(*tlv) - sizeof(Tlv::header_s)));
104  frame_write_index = 0;
105  return 2;
106  }
107 
108  // The frame is not complete yet, come back soon!
109  if (frame_write_index < (int)sizeof(Tlv::header_s) || frame_write_index < (int)Tlv::getSize(*tlv))
110  return 2;
111 
112  // The frame is complete
113  return 1;
114 }
115 
116 // Connect to the stream on the specified address and port
117 // returns:
118 // - 1 on sucess
119 // - 0 on non-fatal failure (ALB unavailable, processing is not started yet?)
120 // - -1 on fatal failure (invalid IP)
121 int TcpStreamReader::connectToALB(const char *ipv4, const uint16_t port)
122 {
123  int ret;
124  struct in_addr addr;
125 
126  if (socket_fd == -1)
128 
129  // Parse IPv4 string
130  ret = inet_pton(AF_INET, ipv4, (uint8_t *)&addr);
131  if (ret <= 0) {
132  printf("Cannot parse ALB IPv4");
133  return -1;
134  }
135 
136  // Copy result to sockaddr we want to connect
137  struct sockaddr_in alb = {};
138  alb.sin_family = AF_INET;
139  alb.sin_addr = addr;
140  alb.sin_port = htons(port);
141 
142  ret = connect(socket_fd, (struct sockaddr *)&alb, sizeof(alb));
143 
144  if (ret < 0) {
145  if (errno == ECONNREFUSED)
146  return 0; // ALB unavailable (processing not started yet?)
147  else
148  return -1; // Unhandled error
149  }
150 
151  printf("Connected to %s:%d\n", ipv4, port);
152  return 1;
153 }
154 
155 // Poll the socket until a new frame is read
156 // returns:
157 // - 1 on sucess (buffer now contains a valid frame)
158 // - -1 on fatal failure (corrupted stream)
159 int TcpStreamReader::getNextFrame(uint8_t *buffer, const size_t buffer_size)
160 {
161  int frame_write_index = 0;
162  while (true) {
163  int ret = readSocket(socket_fd, buffer, buffer_size, frame_write_index);
164  if (ret == 2) {
165  continue;
166  } else
167  return ret;
168  }
169 }
170 
171 // Disconnect from ALB
172 // returns:
173 // - 0 on success
174 // - <0 on failure (not connected or cannot close socket)
176 {
177  int ret = 0;
178 
179  if (socket_fd < 0)
180  return -1;
181 
182  ret = close(socket_fd);
183  if (ret < 0)
184  printf("Error closing socket\n");
185 
186  socket_fd = -1;
187 
188  return ret;
189 }
Tlv::getSize
static size_t getSize(const tlv_s &tlv)
Definition: tlvCommon.h:61
emptySocket
void emptySocket(int socket_fd, int bytes_remaining)
Definition: tcpStream.cpp:51
readSocket
int readSocket(int socket_fd, uint8_t *buffer, const size_t buffer_size, int &frame_write_index)
Definition: tcpStream.cpp:65
TcpStreamReader::default_port
static const uint16_t default_port
Definition: tcpStream.h:7
TcpStreamReader::connectToALB
int connectToALB(const char *ipv4=default_ip, const uint16_t port=default_port)
Definition: tcpStream.cpp:121
open_socket
void open_socket(int &socket_fd)
Definition: tcpStream.cpp:20
tcpStream.h
TcpStreamReader::default_ip
static const char * default_ip
Definition: tcpStream.h:6
TcpStreamReader::socket_fd
int socket_fd
Definition: tcpStream.h:32
OSEF_TYPE_TIMESTAMPED_DATA
#define OSEF_TYPE_TIMESTAMPED_DATA
Definition: osefTypes.h:102
TcpStreamReader::getNextFrame
int getNextFrame(uint8_t *buffer, const size_t buffer_size)
Definition: tcpStream.cpp:159
close_socket
void close_socket(int &socket_fd)
Definition: tcpStream.cpp:39
TcpStreamReader::disconnectfromALB
int disconnectfromALB()
Definition: tcpStream.cpp:175
osefTypes.h
tlvCommon.h


outsight_alb_driver
Author(s): Outsight
autogenerated on Thu Oct 13 2022 02:21:45