Apollo  6.0
Open source self driving car software
socket_input.h
Go to the documentation of this file.
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 
24 namespace apollo {
25 namespace drivers {
26 namespace velodyne {
27 
28 using apollo::drivers::velodyne::VelodynePacket;
29 
30 // static int FIRING_DATA_PORT = 2368;
31 // static int POSITIONING_DATA_PORT = 8308;
32 static const int POLL_TIMEOUT = 1000; // one second (in msec)
33 
35 class SocketInput : public Input {
36  public:
37  SocketInput();
38  virtual ~SocketInput();
39  void init(const int& port) override;
40  int get_firing_data_packet(VelodynePacket* pkt);
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
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
int get_positioning_data_packet(NMEATimePtr nmea_time)
Pure virtual Velodyne input base class.
Definition: input.h:49
std::shared_ptr< NMEATime > NMEATimePtr
Definition: input.h:46
Live Velodyne input from socket.
Definition: socket_input.h:35
int get_firing_data_packet(VelodynePacket *pkt)
Read one Velodyne packet.
virtual void init()
Definition: input.h:64