Apollo  6.0
Open source self driving car software
input.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2020 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 #pragma once
17 #include <netdb.h>
18 #include <unistd.h>
19 
20 #include <algorithm>
21 #include <chrono>
22 #include <cmath>
23 #include <cstdint>
24 #include <cstring>
25 #include <iostream>
26 #include <memory>
27 #include <vector>
28 namespace apollo {
29 namespace drivers {
30 namespace robosense {
31 const int RSLIDAR_PKT_LEN = 1248;
32 enum InputState {
33  INPUT_OK = 0,
39 };
40 
41 class Input {
42  public:
43  Input(const uint16_t &msop_port, const uint16_t &difop_port);
44  ~Input();
45  InputState getPacket(uint8_t *pkt, uint32_t timeout);
46 
47  private:
48  int setUpSocket(uint16_t port);
49  int msop_fd_;
50  int difop_fd_;
51 };
52 } // namespace robosense
53 } // namespace drivers
54 } // namespace apollo
InputState getPacket(uint8_t *pkt, uint32_t timeout)
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
InputState
Definition: input.h:32
Input(const uint16_t &msop_port, const uint16_t &difop_port)
const int RSLIDAR_PKT_LEN
Definition: input.h:31
Definition: input.h:41