Apollo 10.0
自动驾驶开放平台
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#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
28namespace apollo {
29namespace drivers {
30namespace velodyne {
31
32static const size_t FIRING_DATA_PACKET_SIZE = 1206;
33static const size_t POSITIONING_DATA_PACKET_SIZE = 512;
34static const size_t ETHERNET_HEADER_SIZE = 42;
35static const int SOCKET_TIMEOUT = -2;
36static const int RECEIVE_FAIL = -3;
37
38struct 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};
46typedef std::shared_ptr<NMEATime> NMEATimePtr;
47
49class Input {
50 public:
51 Input() {}
52 virtual ~Input() {}
53
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:
69 const uint8_t* bytes);
70};
71
72} // namespace velodyne
73} // namespace drivers
74} // namespace apollo
Pure virtual Velodyne input base class
Definition input.h:49
bool exract_nmea_time_from_packet(NMEATimePtr nmea_time, const uint8_t *bytes)
Definition input.cc:23
virtual int get_firing_data_packet(VelodynePacket *pkt)=0
Read one Velodyne packet.
virtual int get_positioning_data_packet(NMEATimePtr nmea_time)=0
virtual void init(const int &port)
Definition input.h:65
std::shared_ptr< NMEATime > NMEATimePtr
Definition input.h:46
class register implement
Definition arena_queue.h:37