os1.cpp
Go to the documentation of this file.
1 #include <cerrno>
2 #include <chrono>
3 #include <cstdio>
4 #include <cstring>
5 #include <iostream>
6 #include <memory>
7 #include <vector>
8 #include <algorithm>
9 
10 #include <arpa/inet.h>
11 #include <netdb.h>
12 #include <sys/socket.h>
13 #include <sys/types.h>
14 #include <unistd.h>
15 
16 #include "ouster/os1.h"
17 
18 namespace ouster {
19 namespace OS1 {
20 
21 using ns = std::chrono::nanoseconds;
22 
28 static bool _window_rejection = true;
29 static std::string _operation_mode_str = "";
30 static std::string _pulse_mode_str = "";
31 static std::string _window_rejection_str = "";
32 //----------------
33 
34 struct client {
35  int lidar_fd;
36  int imu_fd;
37  ~client() {
38  close(lidar_fd);
39  close(imu_fd);
40  }
41 };
42 
43 static int udp_data_socket(int port) {
44  int sock_fd = socket(PF_INET, SOCK_DGRAM, 0);
45  if (sock_fd < 0) {
46  std::cerr << "socket: " << std::strerror(errno) << std::endl;
47  return -1;
48  }
49 
50  struct sockaddr_in my_addr;
51  memset((char*)&my_addr, 0, sizeof(my_addr));
52  my_addr.sin_family = AF_INET;
53  my_addr.sin_port = htons(port);
54  my_addr.sin_addr.s_addr = INADDR_ANY;
55 
56  if (bind(sock_fd, (struct sockaddr*)&my_addr, sizeof(my_addr)) < 0) {
57  std::cerr << "bind: " << std::strerror(errno) << std::endl;
58  return -1;
59  }
60 
61  struct timeval timeout;
62  timeout.tv_sec = 1;
63  timeout.tv_usec = 0;
64  if (setsockopt(sock_fd, SOL_SOCKET, SO_RCVTIMEO, &timeout,
65  sizeof(timeout)) < 0) {
66  std::cerr << "setsockopt: " << std::strerror(errno) << std::endl;
67  return -1;
68  }
69 
70  return sock_fd;
71 }
72 
73 static int cfg_socket(const char* addr) {
74  struct addrinfo hints, *info_start, *ai;
75 
76  memset(&hints, 0, sizeof hints);
77  hints.ai_family = AF_UNSPEC;
78  hints.ai_socktype = SOCK_STREAM;
79 
80  int ret = getaddrinfo(addr, "7501", &hints, &info_start);
81  if (ret != 0) {
82  std::cerr << "getaddrinfo: " << gai_strerror(ret) << std::endl;
83  return -1;
84  }
85  if (info_start == NULL) {
86  std::cerr << "getaddrinfo: empty result" << std::endl;
87  return -1;
88  }
89 
90  int sock_fd;
91  for (ai = info_start; ai != NULL; ai = ai->ai_next) {
92  sock_fd = socket(ai->ai_family, ai->ai_socktype, ai->ai_protocol);
93  if (sock_fd < 0) {
94  std::cerr << "socket: " << std::strerror(errno) << std::endl;
95  continue;
96  }
97 
98  if (connect(sock_fd, ai->ai_addr, ai->ai_addrlen) == -1) {
99  close(sock_fd);
100  continue;
101  }
102 
103  break;
104  }
105 
106  freeaddrinfo(info_start);
107  if (ai == NULL) {
108  return -1;
109  }
110 
111  return sock_fd;
112 }
113 
114 std::shared_ptr<client> init_client(const std::string& hostname,
115  const std::string& udp_dest_host,
116  int lidar_port, int imu_port) {
117  int sock_fd = cfg_socket(hostname.c_str());
118 
119  if (sock_fd < 0) return std::shared_ptr<client>();
120 
121  std::string cmd;
122 
123  auto do_cmd = [&](const std::string& op, const std::string& val) {
124  const size_t max_res_len = 4095;
125  char read_buf[max_res_len + 1];
126 
127  ssize_t len;
128  std::string cmd = op + " " + val + "\n";
129 
130  len = write(sock_fd, cmd.c_str(), cmd.length());
131  if (len != (ssize_t)cmd.length()) {
132  //std::cerr << "init_client: failed to send command" << std::endl;
133  return std::string("[error] init_client: failed to send command");
134  }
135 
136  len = read(sock_fd, read_buf, max_res_len);
137  if (len < 0) {
138  //std::cerr << "read: " << std::strerror(errno) << std::endl;
139  return std::string("[error] read: ") + std::strerror(errno);
140  }
141  read_buf[len] = '\0';
142 
143  auto res = std::string(read_buf);
144  res.erase(res.find_last_not_of(" \r\n\t") + 1);
145 
146  return res;
147  };
148 
149  auto do_cmd_chk = [&](const std::string& op, const std::string& val) {
150  auto res = do_cmd(op, val);
151  if (res.find("[error]") != std::string::npos) {
152  std::cerr << res << std::endl;
153  return false;
154  } else if (res != op) {
155  std::cerr << "init_client: command \"" << op << " " << val << "\" failed with \""
156  << res << "\"" << std::endl;
157  return false;
158  }
159  return true;
160  };
161 
162  auto get_cmd = [&](const std::string& op, const std::string& val) {
163  auto res = do_cmd(op, val);
164  if (res.find("error") != std::string::npos) {
165  std::cerr << res << std::endl;
166  return std::string("");
167  }
168  return res;
169  };
170 
171  auto str_tok = [&](const std::string &str, const std::string delim) {
172  auto start = str.find_first_not_of(delim);
173  auto end = start;
174  std::vector<std::string> tokens;
175 
176  while (start != std::string::npos){
177  end = str.find_first_of(delim, start);
178  tokens.push_back(str.substr(start, end-start));
179  start = str.find_first_not_of(delim, end);
180  }
181 
182  return tokens;
183  };
184 
185  bool success = true;
186  success &= do_cmd_chk("set_udp_port_lidar", std::to_string(lidar_port));
187  success &= do_cmd_chk("set_udp_port_imu", std::to_string(imu_port));
188  success &= do_cmd_chk("set_udp_ip", udp_dest_host);
189 
190  if (!success) return std::shared_ptr<client>();
191 
195  //read the sensor information
196  std::string version_str = std::string("");
197  std::string product_str = std::string("");
198  bool has_pulsemode = true;
199  auto sensor_info_str = get_cmd("get_sensor_info", "");
200  auto tokens = str_tok(sensor_info_str, std::string(",: \""));
201  auto pos = std::find(tokens.begin(), tokens.end(), "build_rev");
202  if (pos != tokens.end()) {
203  version_str = *(pos+1);
204  }
205  pos = std::find(tokens.begin(), tokens.end(), "prod_line");
206  if (pos != tokens.end()) {
207  product_str = *(pos+1);
208  }
209  if (product_str == std::string("") || version_str == std::string("")) {
210  std::cout << "Error: Failed to read product name and firmware version." << std::endl;
211  return std::shared_ptr<client>();
212  }
213  std::cout << "Ouster model \"" << product_str << "\", firmware version \"" << version_str << "\"" << std::endl;
214  //TODO: support OS-1-16 and OS-1-128
215  if (product_str != std::string("OS-1-64")) {
216  std::cout << "Error: this driver currently only supports Ouster model \"OS-1-64\"." << std::endl;
217  return std::shared_ptr<client>();
218  }
219 
220  auto ver_numbers = str_tok(version_str, std::string("v."));
221  //check the minor version
222  auto ver_major = std::stoi(ver_numbers[0], nullptr);
223  auto ver_minor = std::stoi(ver_numbers[1], nullptr);
224  if (ver_major < 1 || ver_minor < 7) {
225  std::cout << "Error: Firmware version \"" << version_str << "\" is not supported, please upgrade" << std::endl;
226  return std::shared_ptr<client>();
227  }
228  if (std::stoi(ver_numbers[1], nullptr) >= 10) {
229  std::cout << "On firmware version \"" << version_str << "\" the \"pulse_mode\" parameter is no longer available, will ignore it." << std::endl;
230  has_pulsemode = false;
231  }
232 
233  //read the current settings
234  auto curr_operation_mode_str = get_cmd("get_config_param", "active lidar_mode");
235  auto curr_pulse_mode_str = std::string("");
236  if (has_pulsemode) {
237  curr_pulse_mode_str = get_cmd("get_config_param", "active pulse_mode");
238  }
239  auto curr_window_rejection_str = get_cmd("get_config_param", "active window_rejection_enable");
240  bool do_configure = false;
241  success = true;
242 
243  //setting advanced mode parameters (if necessary)
244  if (curr_operation_mode_str != _operation_mode_str) {
245  success &= do_cmd_chk("set_config_param", "lidar_mode " + _operation_mode_str);
246  do_configure = true;
247  }
248  if (has_pulsemode && (curr_pulse_mode_str != _pulse_mode_str)) {
249  success &= do_cmd_chk("set_config_param", "pulse_mode " + _pulse_mode_str);
250  do_configure = true;
251  }
252  if (curr_window_rejection_str != _window_rejection_str) {
253  success &= do_cmd_chk("set_config_param", "window_rejection_enable " + _window_rejection_str);
254  do_configure = true;
255  }
256 
257  if (!success) return std::shared_ptr<client>();
258 
259  //reinitialize to take effect (if necessary)
260  if (do_configure) {
261  success &= do_cmd_chk("reinitialize", "");
262  if (!success) return std::shared_ptr<client>();
263  std::cout << "Parameters configured, reinitializing sensor" << std::endl;
264  } else {
265  std::cout << "Parameters already configured, no need to reinitialize" << std::endl;
266  }
267  //----------------
268 
269  close(sock_fd);
270 
271  int lidar_fd = udp_data_socket(lidar_port);
272  int imu_fd = udp_data_socket(imu_port);
273  auto cli = std::make_shared<client>();
274  cli->lidar_fd = lidar_fd;
275  cli->imu_fd = imu_fd;
276  return cli;
277 }
278 
280  fd_set rfds;
281  FD_ZERO(&rfds);
282  FD_SET(c.lidar_fd, &rfds);
283  FD_SET(c.imu_fd, &rfds);
284 
285  int max_fd = std::max(c.lidar_fd, c.imu_fd);
286 
287  int retval = select(max_fd + 1, &rfds, NULL, NULL, NULL);
288 
289  client_state res = client_state(0);
290  if (retval == -1) {
291  std::cerr << "select: " << std::strerror(errno) << std::endl;
292  res = client_state(res | ERROR);
293  } else if (retval) {
294  if (FD_ISSET(c.lidar_fd, &rfds)) res = client_state(res | LIDAR_DATA);
295  if (FD_ISSET(c.imu_fd, &rfds)) res = client_state(res | IMU_DATA);
296  }
297  return res;
298 }
299 
300 static bool recv_fixed(int fd, void* buf, size_t len) {
301  ssize_t n = recvfrom(fd, buf, len + 1, 0, NULL, NULL);
302  if (n == (ssize_t)len)
303  return true;
304  else if (n == -1)
305  std::cerr << "recvfrom: " << std::strerror(errno) << std::endl;
306  else
307  std::cerr << "Unexpected udp packet length: " << n << std::endl;
308  return false;
309 }
310 
311 bool read_lidar_packet(const client& cli, uint8_t* buf) {
312  return recv_fixed(cli.lidar_fd, buf, lidar_packet_bytes);
313 }
314 
315 bool read_imu_packet(const client& cli, uint8_t* buf) {
316  return recv_fixed(cli.imu_fd, buf, imu_packet_bytes);
317 }
318 
322 //----------------
323 void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str, bool window_rejection)
324 {
325  _operation_mode_str = operation_mode_str;
326  _pulse_mode_str = pulse_mode_str;
327  _window_rejection = window_rejection;
328 
329  _operation_mode = ouster::OS1::MODE_1024x10;
330  if (_operation_mode_str == std::string("512x10")) {
331  _operation_mode = ouster::OS1::MODE_512x10;
332  } else if (_operation_mode_str == std::string("1024x10")) {
333  _operation_mode = ouster::OS1::MODE_1024x10;
334  } else if (_operation_mode_str == std::string("2048x10")) {
335  _operation_mode = ouster::OS1::MODE_2048x10;
336  } else if (_operation_mode_str == std::string("512x20")) {
337  _operation_mode = ouster::OS1::MODE_512x20;
338  } else if (_operation_mode_str == std::string("1024x20")) {
339  _operation_mode = ouster::OS1::MODE_1024x20;
340  } else {
341  std::cout << "Selected operation mode " << _operation_mode_str << " is invalid, using default mode \"1024x10\"" << std::endl;
342  }
343 
344  _pulse_mode = ouster::OS1::PULSE_STANDARD;
345  if (_pulse_mode_str == std::string("STANDARD")) {
346  _pulse_mode = ouster::OS1::PULSE_STANDARD;
347  } else if (_pulse_mode_str == std::string("NARROW")) {
348  _pulse_mode = ouster::OS1::PULSE_NARROW;
349  } else {
350  std::cout << "Selected pulse mode " << _pulse_mode_str << " is invalid, using default mode \"STANDARD\"" << std::endl;
351  }
352 
353  _window_rejection_str = ((_window_rejection) ? std::string("1") : std::string("0"));
354 }
355 //----------------
356 
357 }
358 }
string cmd
const size_t imu_packet_bytes
Definition: os1.h:15
std::shared_ptr< client > init_client(const std::string &hostname, const std::string &udp_dest_host, int lidar_port, int imu_port)
Definition: os1.cpp:114
std::chrono::nanoseconds ns
Definition: os1.cpp:21
void set_advanced_params(std::string operation_mode_str, std::string pulse_mode_str, bool window_rejection)
Definition: os1.cpp:323
bool read_imu_packet(const client &cli, uint8_t *buf)
Definition: os1.cpp:315
static std::string _window_rejection_str
Definition: os1.cpp:31
static std::string _operation_mode_str
Definition: os1.cpp:29
static bool recv_fixed(int fd, void *buf, size_t len)
Definition: os1.cpp:300
operation_mode_t
Definition: os1.h:65
client_state
Definition: os1.h:19
static bool _window_rejection
Definition: os1.cpp:28
const size_t lidar_packet_bytes
Definition: os1.h:14
static int udp_data_socket(int port)
Definition: os1.cpp:43
static std::string _pulse_mode_str
Definition: os1.cpp:30
client_state poll_client(const client &cli)
Definition: os1.cpp:279
bool read_lidar_packet(const client &cli, uint8_t *buf)
Definition: os1.cpp:311
static PulseMode _pulse_mode
Definition: os1.cpp:27
pulse_mode_t
Definition: os1.h:77
Definition: os1.h:11
static int cfg_socket(const char *addr)
Definition: os1.cpp:73
static OperationMode _operation_mode
Definition: os1.cpp:26


ouster
Author(s): ouster developers
autogenerated on Mon Jun 10 2019 14:16:21