50 #include <sys/socket.h> 51 #include <arpa/inet.h> 62 sizeof(velodyne_msgs::VelodynePacket().data);
74 private_nh_(private_nh),
94 Input(private_nh, port)
104 sockfd_ = socket(PF_INET, SOCK_DGRAM, 0);
112 memset(&my_addr, 0,
sizeof(my_addr));
113 my_addr.sin_family = AF_INET;
114 my_addr.sin_port = htons(port);
115 my_addr.sin_addr.s_addr = INADDR_ANY;
117 if (bind(
sockfd_, (sockaddr *)&my_addr,
sizeof(sockaddr)) == -1)
123 if (fcntl(
sockfd_,F_SETFL, O_NONBLOCK|FASYNC) < 0)
143 struct pollfd fds[1];
145 fds[0].events = POLLIN;
146 static const int POLL_TIMEOUT = 1000;
148 sockaddr_in sender_address;
149 socklen_t sender_address_len =
sizeof(sender_address);
173 int retval = poll(fds, 1, POLL_TIMEOUT);
177 ROS_ERROR(
"poll() error: %s", strerror(errno));
182 ROS_WARN(
"Velodyne poll() timeout");
185 if ((fds[0].revents & POLLERR)
186 || (fds[0].revents & POLLHUP)
187 || (fds[0].revents & POLLNVAL))
189 ROS_ERROR(
"poll() reports Velodyne error");
192 }
while ((fds[0].revents & POLLIN) == 0);
196 ssize_t nbytes = recvfrom(
sockfd_, &pkt->data[0],
198 (sockaddr*) &sender_address,
199 &sender_address_len);
203 if (errno != EWOULDBLOCK)
210 else if ((
size_t) nbytes == packet_size)
216 && sender_address.sin_addr.s_addr !=
devip_.s_addr)
223 << nbytes <<
" bytes");
230 pkt->stamp =
ros::Time((time2 + time1) / 2.0 + time_offset);
252 double packet_rate, std::string filename,
253 bool read_once,
bool read_fast,
double repeat_delay):
254 Input(private_nh, port),
255 packet_rate_(packet_rate),
267 ROS_INFO(
"Read input file only once.");
269 ROS_INFO(
"Read input file as quickly as possible.");
271 ROS_INFO(
"Delay %.3f seconds before repeating input file.",
278 ROS_FATAL(
"Error opening Velodyne socket dump file.");
282 std::stringstream filter;
285 filter <<
"src host " <<
devip_str_ <<
" && ";
287 filter <<
"udp dst port " << port;
289 filter.str().c_str(), 1, PCAP_NETMASK_UNKNOWN);
301 struct pcap_pkthdr *header;
302 const u_char *pkt_data;
307 if ((res = pcap_next_ex(
pcap_, &header, &pkt_data)) >= 0)
319 memcpy(&pkt->data[0], pkt_data+42, packet_size);
327 ROS_WARN(
"Error %d reading Velodyne packet: %s",
328 res, pcap_geterr(
pcap_));
334 ROS_INFO(
"end of file reached -- done reading.");
340 ROS_INFO(
"end of file reached -- delaying %.3f seconds.",
345 ROS_DEBUG(
"replaying Velodyne dump file");
static const size_t packet_size
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
ros::Time rosTimeFromGpsTimestamp(const uint8_t *const data)