Apollo 10.0
自动驾驶开放平台
socket_input.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/* -*- mode: C++ -*-
18 *
19 * Copyright (C) 2007 Austin Robot Technology, Yaxin Liu, Patrick Beeson
20 * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
21 * Copyright (C) 2015, Jack O'Quin
22 *
23 * License: Modified BSD Software License Agreement
24 *
25 * $Id$
26 */
27
28#include <arpa/inet.h>
29#include <fcntl.h>
30#include <poll.h>
31#include <sys/file.h>
32#include <sys/socket.h>
33#include <unistd.h>
34#include <cerrno>
35
37
38namespace apollo {
39namespace drivers {
40namespace velodyne {
41
43// InputSocket class implementation
45
51SocketInput::SocketInput() : sockfd_(-1), port_(0) {}
52
54SocketInput::~SocketInput(void) { (void)close(sockfd_); }
55
56void SocketInput::init(const int &port) {
57 if (sockfd_ != -1) {
58 (void)close(sockfd_);
59 }
60
61 // connect to Velodyne UDP port
62 AINFO << "Opening UDP socket: port " << uint16_t(port);
63 port_ = port;
64 sockfd_ = socket(AF_INET, SOCK_DGRAM, 0);
65
66 if (sockfd_ == -1) {
67 AERROR << "Init socket failed, UDP port is " << port;
68 return;
69 }
70
71 sockaddr_in my_addr; // my address information
72 memset(&my_addr, 0, sizeof(my_addr)); // initialize to zeros
73 my_addr.sin_family = AF_INET; // host byte order
74 my_addr.sin_port = htons(uint16_t(port)); // short, in network byte order
75 my_addr.sin_addr.s_addr = INADDR_ANY; // automatically fill in my IP
76 // my_addr.sin_addr.s_addr = inet_addr("192.168.1.100");
77
78 if (bind(sockfd_, reinterpret_cast<sockaddr *>(&my_addr), sizeof(sockaddr)) ==
79 -1) {
80 AERROR << "Socket bind failed! Port " << port_;
81 return;
82 }
83
84 if (fcntl(sockfd_, F_SETFL, O_NONBLOCK | FASYNC) < 0) {
85 AERROR << "non-block! Port " << port_;
86 return;
87 }
88
89 AINFO << "Velodyne socket fd is " << sockfd_ << ", port " << port_;
90}
91
94 // double time1 = ros::Time::now().toSec();
95 double time1 = apollo::cyber::Time().Now().ToSecond();
96 while (true) {
97 if (!input_available(POLL_TIMEOUT)) {
98 return SOCKET_TIMEOUT;
99 }
100 // Receive packets that should now be available from the
101 // socket using a blocking read.
102 uint8_t bytes[FIRING_DATA_PACKET_SIZE];
103 ssize_t nbytes =
104 recvfrom(sockfd_, bytes, FIRING_DATA_PACKET_SIZE, 0, nullptr, nullptr);
105
106 if (nbytes < 0) {
107 if (errno != EWOULDBLOCK) {
108 AERROR << "recvfail from port " << port_;
109 return RECEIVE_FAIL;
110 }
111 }
112
113 if ((size_t)nbytes == FIRING_DATA_PACKET_SIZE) {
114 // read successful, done now
115 pkt->set_data(bytes, FIRING_DATA_PACKET_SIZE);
116 break;
117 }
118
119 AERROR << "Incomplete Velodyne rising data packet read: " << nbytes
120 << " bytes from port " << port_;
121 }
122 double time2 = apollo::cyber::Time().Now().ToSecond();
123 pkt->set_stamp(apollo::cyber::Time((time2 + time1) / 2.0).ToNanosecond());
124
125 return 0;
126}
127
129 while (true) {
130 if (!input_available(POLL_TIMEOUT)) {
131 return 1;
132 }
133 // Receive packets that should now be available from the
134 // socket using a blocking read.
135 // Last 234 bytes not use
136 uint8_t bytes[POSITIONING_DATA_PACKET_SIZE];
137 ssize_t nbytes = recvfrom(sockfd_, bytes, POSITIONING_DATA_PACKET_SIZE, 0,
138 nullptr, nullptr);
139
140 if (nbytes < 0) {
141 if (errno != EWOULDBLOCK) {
142 AERROR << "recvfail from port " << port_;
143 return 1;
144 }
145 }
146
147 if ((size_t)nbytes == POSITIONING_DATA_PACKET_SIZE) {
148 // read successful, exract nmea time
149 if (exract_nmea_time_from_packet(nmea_time, bytes)) {
150 break;
151 } else {
152 return 1;
153 }
154 }
155
156 AINFO << "incomplete Velodyne packet read: " << nbytes
157 << " bytes from port " << port_;
158 }
159
160 return 0;
161}
162
163bool SocketInput::input_available(int timeout) {
164 struct pollfd fds[1];
165 fds[0].fd = sockfd_;
166 fds[0].events = POLLIN;
167 // Unfortunately, the Linux kernel recvfrom() implementation
168 // uses a non-interruptible sleep() when waiting for data,
169 // which would cause this method to hang if the device is not
170 // providing data. We poll() the device first to make sure
171 // the recvfrom() will not block.
172 //
173 // Note, however, that there is a known Linux kernel bug:
174 //
175 // Under Linux, select() may report a socket file descriptor
176 // as "ready for reading", while nevertheless a subsequent
177 // read blocks. This could for example happen when data has
178 // arrived but upon examination has wrong checksum and is
179 // discarded. There may be other circumstances in which a
180 // file descriptor is spuriously reported as ready. Thus it
181 // may be safer to use O_NONBLOCK on sockets that should not
182 // block.
183
184 // poll() until input available
185 do {
186 int retval = poll(fds, 1, POLL_TIMEOUT);
187
188 if (retval < 0) { // poll() error?
189 if (errno != EINTR) {
190 AWARN << "Velodyne port " << port_
191 << "poll() error: " << strerror(errno);
192 }
193 return false;
194 }
195
196 if (retval == 0) { // poll() timeout?
197 AWARN << "Velodyne port " << port_ << " poll() timeout";
198 return false;
199 }
200
201 if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) ||
202 (fds[0].revents & POLLNVAL)) { // device error?
203 AERROR << "Velodyne port " << port_ << "poll() reports Velodyne error";
204 return false;
205 }
206 } while ((fds[0].revents & POLLIN) == 0);
207 return true;
208}
209
210} // namespace velodyne
211} // namespace drivers
212} // namespace apollo
Cyber has builtin time type Time.
Definition time.h:31
static Time Now()
get the current time.
Definition time.cc:57
double ToSecond() const
convert time to second.
Definition time.cc:77
bool exract_nmea_time_from_packet(NMEATimePtr nmea_time, const uint8_t *bytes)
Definition input.cc:23
int get_positioning_data_packet(NMEATimePtr nmea_time)
int get_firing_data_packet(VelodynePacket *pkt)
Get one velodyne packet.
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
#define AWARN
Definition log.h:43
std::shared_ptr< NMEATime > NMEATimePtr
Definition input.h:46
class register implement
Definition arena_queue.h:37
@ POLL_TIMEOUT