Apollo 10.0
自动驾驶开放平台
driver64.cc
浏览该文件的文档.
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#include <cmath>
18#include <ctime>
19#include <string>
20
23// #include "ros/ros.h"
24
25namespace apollo {
26namespace drivers {
27namespace velodyne {
29 if (poll_thread_.joinable()) {
30 poll_thread_.join();
31 }
32}
33
35 const double frequency = config_.rpm() / 60.0; // expected Hz rate
36
37 // default number of packets for each scan is a single revolution
38 // (fractions rounded up)
39 config_.set_npackets(static_cast<int>(ceil(packet_rate_ / frequency)));
40 AINFO << "publishing " << config_.npackets() << " packets per scan";
41
42 input_.reset(new SocketInput());
44
45 if (node_ == NULL) {
46 AERROR << "node is NULL";
47 return false;
48 }
49 writer_ = node_->CreateWriter<VelodyneScan>(config_.scan_channel());
50 poll_thread_ = std::thread(&Velodyne64Driver::DevicePoll, this);
51 return true;
52}
53
58bool Velodyne64Driver::Poll(const std::shared_ptr<VelodyneScan>& scan) {
59 // Allocate a new shared pointer for zero-copy sharing with other nodelets.
60 int poll_result =
61 config_.use_sensor_sync() ? PollStandardSync(scan) : PollStandard(scan);
62
63 if (poll_result == SOCKET_TIMEOUT || poll_result == RECEIVE_FAIL) {
64 return false; // poll again
65 }
66
67 if (scan->firing_pkts().empty()) {
68 AINFO << "Get an empty scan from port: " << config_.firing_data_port();
69 return false;
70 }
71
72 // publish message using time of last packet read
73 ADEBUG << "Publishing a full Velodyne scan.";
74 scan->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond());
75 scan->mutable_header()->set_frame_id(config_.frame_id());
76 scan->set_model(config_.model());
77 scan->set_mode(config_.mode());
78 scan->set_basetime(basetime_);
79
80 return true;
81}
82
83bool Velodyne64Driver::CheckAngle(const VelodynePacket& packet) {
84 // check the angle in every packet
85 // for each model of velodyne 64 the data struct is same , so we don't need to
86 // check the lidar model
87 const unsigned char* raw_ptr = (const unsigned char*)packet.data().c_str();
88 for (int i = 0; i < BLOCKS_PER_PACKET; ++i) {
89 uint16_t angle = static_cast<uint16_t>(raw_ptr[i * BLOCK_SIZE + 3] * 256 +
90 raw_ptr[i * BLOCK_SIZE + 2]);
91 // for the velodyne64 angle resolution is 0.17~0.2 , so take the angle diff
92 // at 0.3 degree should be a good choice
93 // prefix_angle default = 18000
94 if (angle > config_.prefix_angle() &&
95 std::abs(angle - config_.prefix_angle()) < 30) {
96 return true;
97 }
98 }
99 return false;
100}
101
102int Velodyne64Driver::PollStandardSync(std::shared_ptr<VelodyneScan> scan) {
103 // Since the velodyne delivers data at a very high rate, keep
104 // reading and publishing scans as fast as possible.
105 while (true) {
106 while (true) {
107 // keep reading until full packet received
108 VelodynePacket* packet = scan->add_firing_pkts();
109 int rc = input_->get_firing_data_packet(packet);
110
111 if (rc == 0) {
112 // check the angle for every packet if a packet has an angle
113 if (CheckAngle(*packet) &&
114 (scan->firing_pkts_size() > 0.5 * config_.npackets())) {
115 return 0;
116 } else {
117 break; // got a full packet?
118 }
119 }
120 if (rc < 0) {
121 return rc;
122 }
123 }
124 // if the only UDP packet lost then recv 1.5*config_.npackets packets at
125 // most
126 if (scan->firing_pkts_size() > 1.5 * config_.npackets()) {
127 return 0;
128 }
129 }
130 return 0;
131}
132
134 while (!apollo::cyber::IsShutdown()) {
135 // poll device until end of file
136 std::shared_ptr<VelodyneScan> scan = std::make_shared<VelodyneScan>();
137 bool ret = Poll(scan);
138 if (ret) {
139 apollo::common::util::FillHeader("velodyne", scan.get());
140 writer_->Write(scan);
141 } else {
142 AWARN << "device poll failed";
143 }
144 }
145
146 AERROR << "CompVelodyneDriver thread exit";
147}
148
149} // namespace velodyne
150} // namespace drivers
151} // namespace apollo
Cyber has builtin time type Time.
Definition time.h:31
std::shared_ptr< cyber::Node > node_
Definition driver_base.h:66
Live Velodyne input from socket.
bool Poll(const std::shared_ptr< VelodyneScan > &scan) override
poll the device
Definition driver64.cc:58
bool Init() override
Initialize the lidar driver.
Definition driver64.cc:34
std::unique_ptr< Input > input_
Definition driver.h:65
std::shared_ptr< apollo::cyber::Writer< VelodyneScan > > writer_
Definition driver.h:64
virtual int PollStandard(std::shared_ptr< VelodyneScan > scan)
Definition driver.cc:144
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
Some string util functions.
bool IsShutdown()
Definition state.h:46
constexpr int BLOCK_SIZE
Raw Velodyne packet constants and structures.
Definition driver.h:34
constexpr int BLOCKS_PER_PACKET
Definition driver.h:33
class register implement
Definition arena_queue.h:37