Apollo 10.0
自动驾驶开放平台
socket_input.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
17#pragma once
18
19#include <unistd.h>
20#include <cstdio>
21
23
24namespace apollo {
25namespace drivers {
26namespace velodyne {
27
29
30// static int FIRING_DATA_PORT = 2368;
31// static int POSITIONING_DATA_PORT = 8308;
32static const int POLL_TIMEOUT = 1000; // one second (in msec)
33
35class SocketInput : public Input {
36 public:
38 virtual ~SocketInput();
39 void init(const int& port) override;
42
43 private:
44 int sockfd_;
45 int port_;
46 bool input_available(int timeout);
47};
48
49} // namespace velodyne
50} // namespace drivers
51} // namespace apollo
Pure virtual Velodyne input base class
Definition input.h:49
Live Velodyne input from socket.
int get_positioning_data_packet(NMEATimePtr nmea_time)
int get_firing_data_packet(VelodynePacket *pkt)
Get one velodyne packet.
std::shared_ptr< NMEATime > NMEATimePtr
Definition input.h:46
class register implement
Definition arena_queue.h:37
@ POLL_TIMEOUT