lslidar_c16_driver.h
Go to the documentation of this file.
1 /*
2  * This file is part of lslidar_c16 driver.
3  *
4  * The driver is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * The driver is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License
15  * along with the driver. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #ifndef LSLIDAR_C16_DRIVER_H
19 #define LSLIDAR_C16_DRIVER_H
20 
21 #include <unistd.h>
22 #include <stdio.h>
23 #include <netinet/in.h>
24 #include <string>
25 
26 #include <boost/shared_ptr.hpp>
27 
28 #include <ros/ros.h>
31 
32 #include <lslidar_c16_msgs/LslidarC16Packet.h>
33 #include <lslidar_c16_msgs/LslidarC16ScanUnified.h>
34 
35 namespace lslidar_c16_driver {
36 
37 //static uint16_t UDP_PORT_NUMBER = 8080;
38 static uint16_t PACKET_SIZE = 1206;
39 
41 public:
42 
45 
46  bool initialize();
47  bool polling();
48 
49  void initTimeStamp(void);
50  void getFPGA_GPSTimeStamp(lslidar_c16_msgs::LslidarC16PacketPtr &packet);
51 
54 
55 private:
56 
57  bool loadParameters();
58  bool createRosIO();
59  bool openUDPPort();
60  int getPacket(lslidar_c16_msgs::LslidarC16PacketPtr& msg);
61 
62  // Ethernet relate variables
63  std::string lidar_ip_string;
64  std::string group_ip_string;
65  in_addr lidar_ip;
67  int socket_id;
69  bool use_gps_;
71  // ROS related variables
75 
76  // Diagnostics updater
79  double diag_min_freq;
80  double diag_max_freq;
81 
83  uint64_t GPSStableTS;
84  uint64_t GPSCountingTS;
85  uint64_t last_FPGA_ts;
86  uint64_t GPS_ts;
87  unsigned char packetTimeStamp[10];
88  struct tm cur_time;
89  unsigned short int us;
90  unsigned short int ms;
92 };
93 
96 
97 } // namespace lslidar_driver
98 
99 #endif // _LSLIDAR_C16_DRIVER_H_
boost::shared_ptr< LslidarC16Driver > LslidarC16DriverPtr
int getPacket(lslidar_c16_msgs::LslidarC16PacketPtr &msg)
static uint16_t PACKET_SIZE
diagnostic_updater::Updater diagnostics
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic
boost::shared_ptr< const LslidarC16Driver > LslidarC16DriverConstPtr
void getFPGA_GPSTimeStamp(lslidar_c16_msgs::LslidarC16PacketPtr &packet)
LslidarC16Driver(ros::NodeHandle &n, ros::NodeHandle &pn)


lslidar_c16_driver
Author(s): Yutong
autogenerated on Thu Aug 22 2019 03:51:43