62 extern volatile sig_atomic_t
flag;
65 static const size_t packet_size =
sizeof(rslidar_msgs::rslidarPacket().data);
102 sockfd_ = socket(PF_INET, SOCK_DGRAM, 0);
110 if (setsockopt(
sockfd_, SOL_SOCKET, SO_REUSEADDR, (
const void*)&opt,
sizeof(opt)))
112 perror(
"setsockopt error!\n");
117 memset(&my_addr, 0,
sizeof(my_addr));
118 my_addr.sin_family = AF_INET;
119 my_addr.sin_port = htons(port);
120 my_addr.sin_addr.s_addr = INADDR_ANY;
122 if (bind(
sockfd_, (sockaddr*)&my_addr,
sizeof(sockaddr)) == -1)
128 if (fcntl(
sockfd_, F_SETFL, O_NONBLOCK | FASYNC) < 0)
145 struct pollfd fds[1];
147 fds[0].events = POLLIN;
148 static const int POLL_TIMEOUT = 1000;
150 sockaddr_in sender_address;
151 socklen_t sender_address_len =
sizeof(sender_address);
159 int retval = poll(fds, 1, POLL_TIMEOUT);
163 ROS_ERROR(
"poll() error: %s", strerror(errno));
170 char buffer_data[8] =
"re-con";
171 memset(&sender_address, 0, sender_address_len);
172 sender_address.sin_family = AF_INET;
174 sender_address.sin_addr.s_addr =
devip_.s_addr;
175 sendto(
sockfd_, &buffer_data, strlen(buffer_data), 0, (sockaddr*)&sender_address, sender_address_len);
178 if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) || (fds[0].revents & POLLNVAL))
180 ROS_ERROR(
"poll() reports Rslidar error");
183 }
while ((fds[0].revents & POLLIN) == 0);
184 ssize_t nbytes = recvfrom(
sockfd_, &pkt->data[0], packet_size, 0, (sockaddr*)&sender_address, &sender_address_len);
188 if (errno != EWOULDBLOCK)
195 else if ((
size_t)nbytes == packet_size)
212 pkt->stamp =
ros::Time((time2 + time1) / 2.0 + time_offset);
229 bool read_once,
bool read_fast,
double repeat_delay)
230 :
Input(private_nh, port), packet_rate_(packet_rate), filename_(filename)
241 ROS_INFO(
"Read input file only once.");
243 ROS_INFO(
"Read input file as quickly as possible.");
252 ROS_FATAL(
"Error opening rslidar socket dump file.");
256 std::stringstream filter;
259 filter <<
"src host " <<
devip_str_ <<
" && ";
261 filter <<
"udp dst port " << port;
274 struct pcap_pkthdr* header;
275 const u_char* pkt_data;
280 if ((res = pcap_next_ex(
pcap_, &header, &pkt_data)) >= 0)
291 memcpy(&pkt->data[0], pkt_data + 42, packet_size);
300 ROS_WARN(
"Error %d reading rslidar packet: %s", res, pcap_geterr(
pcap_));
306 ROS_INFO(
"end of file reached -- done reading.");
316 ROS_DEBUG(
"replaying rslidar dump file");
static const size_t packet_size
static uint16_t MSOP_DATA_PORT_NUMBER
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)