Apollo  6.0
Open source self driving car software
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 #include <memory>
22 
23 #include "cyber/cyber.h"
24 
25 // #include "velodyne_msgs/VelodyneScanUnified.h"
26 #include "modules/drivers/lidar/proto/velodyne.pb.h"
27 
28 namespace apollo {
29 namespace drivers {
30 namespace velodyne {
31 
32 static const size_t FIRING_DATA_PACKET_SIZE = 1206;
33 static const size_t POSITIONING_DATA_PACKET_SIZE = 512;
34 static const size_t ETHERNET_HEADER_SIZE = 42;
35 static const int SOCKET_TIMEOUT = -2;
36 static const int RECEIVE_FAIL = -3;
37 
38 struct NMEATime {
39  uint16_t year;
40  uint16_t mon;
41  uint16_t day;
42  uint16_t hour;
43  uint16_t min;
44  uint16_t sec;
45 };
46 typedef std::shared_ptr<NMEATime> NMEATimePtr;
47 
49 class Input {
50  public:
51  Input() {}
52  virtual ~Input() {}
53 
62  virtual int get_firing_data_packet(VelodynePacket* pkt) = 0;
63  virtual int get_positioning_data_packet(NMEATimePtr nmea_time) = 0;
64  virtual void init() {}
65  virtual void init(const int& port) {}
66 
67  protected:
68  bool exract_nmea_time_from_packet(NMEATimePtr nmea_time,
69  const uint8_t* bytes);
70 };
71 
72 } // namespace velodyne
73 } // namespace drivers
74 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
uint16_t mon
Definition: input.h:40
Pure virtual Velodyne input base class.
Definition: input.h:49
uint16_t sec
Definition: input.h:44
uint16_t hour
Definition: input.h:42
Input()
Definition: input.h:51
uint16_t min
Definition: input.h:43
std::shared_ptr< NMEATime > NMEATimePtr
Definition: input.h:46
uint16_t day
Definition: input.h:41
virtual ~Input()
Definition: input.h:52
virtual void init()
Definition: input.h:64
virtual void init(const int &port)
Definition: input.h:65
uint16_t year
Definition: input.h:39