Main MRPT website > C++ reference for MRPT 1.4.0
CVelodyneScanner.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2016, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 
10 #ifndef CVelodyneScanner_H
11 #define CVelodyneScanner_H
12 
17 #include <mrpt/utils/TEnumType.h>
18 
19 namespace mrpt
20 {
21  namespace hwdrivers
22  {
23  /** A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Windows and Linux.
24  * It can receive data from real devices via an Ethernet connection or parse a WireShark PCAP file for offline processing.
25  * The choice of online vs. offline operation is taken upon calling \a initialize(): if a PCAP input file has been defined,
26  * offline operation takes place and network is not listened for incomming packets.
27  *
28  * Parsing dual return scans requires a VLP-16 with firmware version 3.0.23 or newer. While converting the scan into a
29  * point cloud in mrpt::obs::CObservationVelodyneScan you can select whether to keep the strongest, the last or both laser returns.
30  *
31  * XML calibration files are not mandatory for VLP-16 and HDL-32, but they are for HDL-64.
32  *
33  * <h2>Grabbing live data (as a user)</h2> <hr>
34  * - Use the application [velodyne-view](http://www.mrpt.org/list-of-mrpt-apps/application-velodyne-view/) to visualize the LIDAR output in real-time (optionally saving to a PCAP file) or to playback a PCAP file.
35  * - Use [rawlog-grabber](http://www.mrpt.org/list-of-mrpt-apps/application-rawlog-grabber/) to record a dataset in MRPT's format together with any other set of sensors. See example config file: [MRPT\share\mrpt\config_files\rawlog-grabber\velodyne.ini](https://github.com/MRPT/mrpt/blob/master/share/mrpt/config_files/rawlog-grabber/velodyne.ini)
36  *
37  * <h2>Grabbing live data (programmatically)</h2> <hr>
38  * - See CGenericSensor for a general overview of the sequence of methods to be called: loadConfig(), initialize(), doProcess().
39  * - Or use this class inside the application [rawlog-grabber](http://www.mrpt.org/list-of-mrpt-apps/application-rawlog-grabber/). See example config files: [MRPT\share\mrpt\config_files\rawlog-grabber\velodyne.ini](https://github.com/MRPT/mrpt/blob/master/share/mrpt/config_files/rawlog-grabber/velodyne.ini)
40  *
41  * See the source code of the example application `[MRPT]/apps/velodyne-view` ([velodyne-view web page](http://www.mrpt.org/list-of-mrpt-apps/application-velodyne-view/)) for more details.
42  *
43  * <h2>Playing back a PCAP file:</h2><hr>
44  * It is common to save Velodyne datasets as Wireshark's PCAP files.
45  * These files can be played back with tools like [bittwist](http://bittwist.sourceforge.net/), which emit all UDP packets in the PCAP log.
46  * Then, use this class to receive the packets as if they come from the real sensor.
47  *
48  * Alternatively, if MRPT is linked against libpcap, this class can directly parse a PCAP file to simulate reading from a device offline.
49  * See method setPCAPInputFile() and config file parameter ``
50  *
51  * To compile with PCAP support: In Debian/Ubuntu, install libpcap-dev. In Windows, install WinPCap developer packages + the regular WinPCap driver.
52  *
53  * <h2>Configuration and usage:</h2> <hr>
54  * Data is returned as observations of type:
55  * - mrpt::obs::CObservationVelodyneScan for one or more "data packets" (refer to Velodyne usage manual)
56  * - mrpt::obs::CObservationGPS for GPS (GPRMC) packets, if available via the synchronization interface of the device.
57  * See those classes for documentation on their fields.
58  *
59  * Configuration includes setting the device IP (optional) and sensor model (mandatory only if a calibration file is not provided).
60  * These parameters can be set programatically (see methods of this class), or via a configuration file with CGenericSensor::loadConfig() (see example config file section below).
61  *
62  * <h2>About timestamps:</h2><hr>
63  * Each gathered observation of type mrpt::obs::CObservationVelodyneScan is populated with two timestamps, one for the local PC timestamp and,
64  * if available, another one for the GPS-stamped timestamp. Refer to the observation docs for details.
65  *
66  * <h2>Format of parameters for loading from a .ini file</h2><hr>
67  * \code
68  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
69  * -------------------------------------------------------
70  * [supplied_section_name]
71  * # ---- Sensor description ----
72  * #calibration_file = PUT_HERE_FULL_PATH_TO_CALIB_FILE.xml // Optional but recommended: put here your vendor-provided calibration file
73  * model = VLP16 // Can be any of: `VLP16`, `HDL32`, `HDL64` (It is used to load default calibration file. Parameter not required if `calibration_file` is provided.
74  * #pos_packets_min_period = 0.5 // (Default=0.5 seconds) Minimum period to leave between reporting position packets. Used to decimate the large number of packets of this type.
75  * # How long to wait, after loss of GPS signal, to report timestamps as "not based on satellite time". 30 secs, with typical velodyne clock drifts, means a ~1.7 ms typical drift.
76  * #pos_packets_timing_timeout = 30 // (Default=30 seconds)
77  * # ---- Online operation ----
78  *
79  * # IP address of the device. UDP packets from other IPs will be ignored. Leave commented or blank
80  * # if only one scanner is present (no IP filtering)
81  * #device_ip = XXX.XXX.XXX.XXX
82  *
83  * # ---- Offline operation ----
84  * # If uncommented, this class will read from the PCAP instead of connecting and listeling
85  * # for online network packets.
86  * # pcap_input = PUT_FULL_PATH_TO_PCAP_LOG_FILE.pcap
87  * # pcap_read_once = false // Do not loop
88  * # pcap_read_fast = false // fast forward skipping non-velodyne packets
89  * # pcap_read_full_scan_delay_ms = 100 // Used to simulate a reasonable number of full scans / second
90  * # pcap_repeat_delay = 0.0 // seconds
91  *
92  * # ---- Save to PCAP file ----
93  * # If uncommented, a PCAP file named `[pcap_output_prefix]_[DATE_TIME].pcap` will be
94  * # written simultaneously to the normal operation of this class.
95  * # pcap_output = velodyne_log
96  *
97  * # 3D position of the sensor on the vehicle:
98  * pose_x = 0 // 3D position (meters)
99  * pose_y = 0
100  * pose_z = 0
101  * pose_yaw = 0 // 3D orientation (degrees)
102  * pose_pitch = 0
103  * pose_roll = 0
104  *
105  * \endcode
106  *
107  *
108  * <h2>Copyright notice</h2><hr>
109  * Portions of this class are based on code from velodyne ROS node in https://github.com/ros-drivers/velodyne
110  * Copyright (C) 2007 Austin Robot Technology, Patrick Beeson
111  * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
112  * License: Modified BSD Software License Agreement
113  *
114  * \note New in MRPT 1.4.0
115  * \ingroup mrpt_hwdrivers_grp
116  */
118  {
120  public:
121  static short int VELODYNE_DATA_UDP_PORT; //!< Default: 2368. Change it if required.
122  static short int VELODYNE_POSITION_UDP_PORT; //!< Default: 8308. Change it if required.
123 
124  /** LIDAR model types */
125  enum model_t {
126  VLP16 = 1,
127  HDL32 = 2,
128  HDL64 = 3
129  };
130  /** Hard-wired properties of LIDARs depending on the model */
132  double maxRange;
133  };
134  typedef std::map<model_t,TModelProperties> model_properties_list_t;
135  /** Access to default sets of parameters for Velodyne LIDARs */
137  static const model_properties_list_t & get(); //!< Singleton access
138  static std::string getListKnownModels(); //!< Return human-readable string: "`VLP16`,`XXX`,..."
139  };
140 
141  protected:
143  model_t m_model; //!< Default: "VLP16"
144  double m_pos_packets_min_period; //!< Default: 0.5 seconds
145  double m_pos_packets_timing_timeout; //!< Default: 30 seconds
146  std::string m_device_ip; //!< Default: "" (no IP-based filtering)
147  bool m_pcap_verbose; //!< Default: true Output PCAP Info msgs
148  std::string m_pcap_input_file; //!< Default: "" (do not operate from an offline file)
149  std::string m_pcap_output_file; //!< Default: "" (do not dump to an offline file)
151  mrpt::obs:: VelodyneCalibration m_velodyne_calib; //!< Device calibration file (supplied by vendor in an XML file)
153 
154  // offline operation:
155  void * m_pcap; //!< opaque ptr: "pcap_t*"
156  void * m_pcap_out; //!< opaque ptr: "pcap_t*"
157  void * m_pcap_dumper; //!< opaque ptr: "pcap_dumper_t *"
158  void * m_pcap_bpf_program; //!< opaque ptr: bpf_program*
160  unsigned int m_pcap_read_count; //!< number of pkts read from the file so far (for debugging)
161  bool m_pcap_read_once; //!< Default: false
162  bool m_pcap_read_fast; //!< (Default: false) If false, will use m_pcap_read_full_scan_delay_ms
163  double m_pcap_read_full_scan_delay_ms; //!< (Default:100 ms) delay after each full scan read from a PCAP log
164  double m_pcap_repeat_delay; //!< Default: 0 (in seconds)
165 
166 
167  /** See the class documentation at the top for expected parameters */
169  const mrpt::utils::CConfigFileBase &configSource,
170  const std::string &section );
171 
172  public:
174  virtual ~CVelodyneScanner();
175 
176  /** @name Change configuration parameters; to be called BEFORE initialize(); see above for the list of parameters and their meaning
177  * @{ */
178  /** See supported model names in the general discussion docs for mrpt::hwdrivers::CVelodyneScanner */
179  void setModelName(const model_t model) { m_model = model; }
180  model_t getModelName() const { return m_model; }
181 
182  /** Set the minimum period between the generation of mrpt::obs::CObservationGPS observations from Velodyne Position RMC GPS packets */
183  void setPosPacketsMinPeriod(double period_seconds) { m_pos_packets_min_period = period_seconds; }
184  double getPosPacketsMinPeriod() const { return m_pos_packets_min_period; }
185 
186  /** Set how long to wait, after loss of GPS signal, to report timestamps as "not based on satellite time". 30 secs, with typical velodyne clock drifts, means a ~1.7 ms typical drift. */
187  void setPosPacketsTimingTimeout(double timeout) { m_pos_packets_timing_timeout = timeout; }
188  double getPosPacketsTimingTimeout() const { return m_pos_packets_timing_timeout; }
189 
190  /** UDP packets from other IPs will be ignored. Default: empty string, means do not filter by IP */
191  void setDeviceIP(const std::string & ip) { m_device_ip = ip; }
192  const std::string &getDeviceIP() const { return m_device_ip; }
193 
194  /** Enables/disables PCAP info messages to console (default: true) */
195  void setPCAPVerbosity(const bool verbose) { m_pcap_verbose = verbose; }
196 
197  /** Enables reading from a PCAP file instead of live UDP packet listening */
198  void setPCAPInputFile(const std::string &pcap_file) { m_pcap_input_file = pcap_file; }
199  const std::string & getPCAPInputFile() const { return m_pcap_input_file; }
200 
201  /** Enables dumping to a PCAP file in parallel to returning regular MRPT objects. Default="": no pcap log. */
202  void setPCAPOutputFile(const std::string &out_pcap_file) { m_pcap_output_file = out_pcap_file; }
203  const std::string & getPCAPOutputFile() const { return m_pcap_output_file; }
204 
205  void setPCAPInputFileReadOnce(bool read_once) { m_pcap_read_once=read_once; }
206  bool getPCAPInputFileReadOnce() const { return m_pcap_read_once; }
207 
208  const mrpt::obs:: VelodyneCalibration & getCalibration() const { return m_velodyne_calib; }
209  void setCalibration(const mrpt::obs::VelodyneCalibration & calib) { m_velodyne_calib=calib; }
210  bool loadCalibrationFile(const std::string & velodyne_xml_calib_file_path ); //!< Returns false on error. \sa mrpt::obs::VelodyneCalibration::loadFromXMLFile()
211  /** @} */
212 
213  /** Polls the UDP port for incoming data packets. The user *must* call this method in a timely fashion to grab data as it it generated by the device.
214  * The minimum call rate should be the expected number of data packets/second (!=scans/second). Checkout Velodyne user manual if in doubt.
215  *
216  * \param[out] outScan Upon return, an empty smart pointer will be found here if no new data was available. Otherwise, a valid scan.
217  * \param[out] outGPS Upon return, an empty smart pointer will be found here if no new GPS data was available. Otherwise, a valid GPS reading.
218  * \return true if no error ocurred (even if there was no new observation). false if any communication error occurred.
219  */
221  mrpt::obs::CObservationVelodyneScanPtr & outScan,
222  mrpt::obs::CObservationGPSPtr & outGPS
223  );
224 
225  // See docs in parent class
226  void doProcess();
227 
228  /** Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig.
229  * Velodyne specifics: this method sets up the UDP listening sockets, so all relevant params MUST BE SET BEFORE calling this.
230  * \exception This method must throw an exception with a descriptive message if some critical error is found.
231  */
232  virtual void initialize();
233 
234  /** Close the UDP sockets set-up in \a initialize(). This is called automatically upon destruction */
235  void close();
236 
237  /** Users normally would prefer calling \a getNextObservation() instead.
238  * This method polls the UDP data port and returns one Velodyne DATA packet (1206 bytes) and/or one POSITION packet. Refer to Velodyne users manual.
239  * Approximate timestamps (based on this computer clock) are returned for each kind of packets, or INVALID_TIMESTAMP if timeout ocurred waiting for a packet.
240  * \return true on all ok. false only for pcap reading EOF
241  */
243  mrpt::system::TTimeStamp &data_pkt_timestamp,
245  mrpt::system::TTimeStamp &pos_pkt_timestamp,
247  );
248 
249  private:
250  /** Handles for the UDP sockets, or INVALID_SOCKET (-1) */
251  typedef
252 #ifdef MRPT_OS_WINDOWS
253 # if MRPT_WORD_SIZE==64
254  uint64_t
255 # else
256  uint32_t
257 # endif
258 #else
259  int
260 #endif
262 
264 
265  static mrpt::system::TTimeStamp internal_receive_UDP_packet(platform_socket_t hSocket, uint8_t *out_buffer, const size_t expected_packet_size,const std::string &filter_only_from_IP);
266 
268  mrpt::system::TTimeStamp & data_pkt_time, uint8_t *out_data_buffer,
269  mrpt::system::TTimeStamp & pos_pkt_time, uint8_t *out_pos_buffer
270  );
271 
272  mrpt::obs::CObservationVelodyneScanPtr m_rx_scan; //!< In progress RX scan
273 
276 
277  }; // end of class
278  } // end of namespace
279 
280  namespace utils // Specializations MUST occur at the same namespace:
281  {
282  template <>
283  struct TEnumTypeFiller<hwdrivers::CVelodyneScanner::model_t>
284  {
286  static void fill(bimap<enum_t,std::string> &m_map)
287  {
291  }
292  };
293  } // End of namespace
294 } // end of namespace
295 
296 
297 #endif
298 
299 
mrpt::hwdrivers::CVelodyneScanner::TModelProperties
Hard-wired properties of LIDARs depending on the model.
Definition: CVelodyneScanner.h:131
mrpt::hwdrivers::CVelodyneScanner::m_pcap_dumper
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
Definition: CVelodyneScanner.h:157
mrpt::hwdrivers::CVelodyneScanner::setPCAPInputFile
void setPCAPInputFile(const std::string &pcap_file)
Enables reading from a PCAP file instead of live UDP packet listening.
Definition: CVelodyneScanner.h:198
mrpt::hwdrivers::CVelodyneScanner::m_last_gps_rmc
mrpt::obs::gnss::Message_NMEA_RMC m_last_gps_rmc
Definition: CVelodyneScanner.h:274
mrpt::hwdrivers::CVelodyneScanner::VELODYNE_DATA_UDP_PORT
static short int VELODYNE_DATA_UDP_PORT
Default: 2368. Change it if required.
Definition: CVelodyneScanner.h:121
mrpt::hwdrivers::CVelodyneScanner::HDL64
@ HDL64
Definition: CVelodyneScanner.h:128
mrpt::hwdrivers::CVelodyneScanner::model_properties_list_t
std::map< model_t, TModelProperties > model_properties_list_t
Definition: CVelodyneScanner.h:134
mrpt::hwdrivers::CVelodyneScanner::m_last_gps_rmc_age
mrpt::system::TTimeStamp m_last_gps_rmc_age
Definition: CVelodyneScanner.h:275
mrpt::hwdrivers::CVelodyneScanner::loadCalibrationFile
bool loadCalibrationFile(const std::string &velodyne_xml_calib_file_path)
Returns false on error.
mrpt::hwdrivers::CVelodyneScanner::m_last_pos_packet_timestamp
mrpt::system::TTimeStamp m_last_pos_packet_timestamp
Definition: CVelodyneScanner.h:152
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory
Access to default sets of parameters for Velodyne LIDARs.
Definition: CVelodyneScanner.h:136
mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket
One unit of data from the scanner (the payload of one UDP DATA packet)
Definition: CObservationVelodyneScan.h:113
mrpt::hwdrivers::CVelodyneScanner::setPosPacketsTimingTimeout
void setPosPacketsTimingTimeout(double timeout)
Set how long to wait, after loss of GPS signal, to report timestamps as "not based on satellite time"...
Definition: CVelodyneScanner.h:187
mrpt::hwdrivers::CVelodyneScanner::close
void close()
Close the UDP sockets set-up in initialize().
mrpt::hwdrivers::CVelodyneScanner::getPCAPInputFile
const std::string & getPCAPInputFile() const
Definition: CVelodyneScanner.h:199
mrpt::hwdrivers::CVelodyneScanner::m_velodyne_calib
mrpt::obs::VelodyneCalibration m_velodyne_calib
Device calibration file (supplied by vendor in an XML file)
Definition: CVelodyneScanner.h:151
mrpt::hwdrivers::CVelodyneScanner::VLP16
@ VLP16
Definition: CVelodyneScanner.h:126
mrpt::utils::bimap
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
Definition: bimap.h:29
mrpt::utils::TEnumTypeFiller< hwdrivers::CVelodyneScanner::model_t >::enum_t
hwdrivers::CVelodyneScanner::model_t enum_t
Definition: CVelodyneScanner.h:285
mrpt::hwdrivers::CVelodyneScanner::initialize
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig.
mrpt::hwdrivers::CVelodyneScanner::m_hPositionSock
platform_socket_t m_hPositionSock
Definition: CVelodyneScanner.h:263
mrpt::hwdrivers::CVelodyneScanner::setPCAPVerbosity
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
Definition: CVelodyneScanner.h:195
mrpt::hwdrivers::CVelodyneScanner::VELODYNE_POSITION_UDP_PORT
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308. Change it if required.
Definition: CVelodyneScanner.h:122
mrpt::hwdrivers::CVelodyneScanner::m_pcap_bpf_program
void * m_pcap_bpf_program
opaque ptr: bpf_program*
Definition: CVelodyneScanner.h:158
mrpt::hwdrivers::CVelodyneScanner::getDeviceIP
const std::string & getDeviceIP() const
Definition: CVelodyneScanner.h:192
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CParticleFilter.h:17
DEFINE_GENERIC_SENSOR
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
Definition: CGenericSensor.h:251
mrpt::hwdrivers::CVelodyneScanner::setModelName
void setModelName(const model_t model)
See supported model names in the general discussion docs for mrpt::hwdrivers::CVelodyneScanner.
Definition: CVelodyneScanner.h:179
mrpt::hwdrivers::CVelodyneScanner::doProcess
void doProcess()
This method will be invoked at a minimum rate of "process_rate" (Hz)
mrpt::hwdrivers::CVelodyneScanner::HDL32
@ HDL32
Definition: CVelodyneScanner.h:127
mrpt::hwdrivers::CVelodyneScanner::m_pcap_verbose
bool m_pcap_verbose
Default: true Output PCAP Info msgs.
Definition: CVelodyneScanner.h:147
mrpt::hwdrivers::CVelodyneScanner::internal_read_PCAP_packet
bool internal_read_PCAP_packet(mrpt::system::TTimeStamp &data_pkt_time, uint8_t *out_data_buffer, mrpt::system::TTimeStamp &pos_pkt_time, uint8_t *out_pos_buffer)
mrpt::hwdrivers::CVelodyneScanner::model_t
model_t
LIDAR model types.
Definition: CVelodyneScanner.h:125
mrpt::hwdrivers::CVelodyneScanner::m_pcap_read_fast
bool m_pcap_read_fast
(Default: false) If false, will use m_pcap_read_full_scan_delay_ms
Definition: CVelodyneScanner.h:162
mrpt::hwdrivers::CVelodyneScanner::m_pcap_read_once
bool m_pcap_read_once
Default: false.
Definition: CVelodyneScanner.h:161
mrpt::system::TTimeStamp
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
Definition: datetime.h:30
mrpt::hwdrivers::CVelodyneScanner::getPCAPOutputFile
const std::string & getPCAPOutputFile() const
Definition: CVelodyneScanner.h:203
mrpt::hwdrivers::CVelodyneScanner::setCalibration
void setCalibration(const mrpt::obs::VelodyneCalibration &calib)
Definition: CVelodyneScanner.h:209
mrpt::hwdrivers::CVelodyneScanner::getNextObservation
bool getNextObservation(mrpt::obs::CObservationVelodyneScanPtr &outScan, mrpt::obs::CObservationGPSPtr &outGPS)
Polls the UDP port for incoming data packets.
mrpt::utils::bimap::insert
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
Definition: bimap.h:69
mrpt::hwdrivers::CVelodyneScanner
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Windows and Linux.
Definition: CVelodyneScanner.h:118
mrpt::hwdrivers::CVelodyneScanner::m_pcap_repeat_delay
double m_pcap_repeat_delay
Default: 0 (in seconds)
Definition: CVelodyneScanner.h:164
mrpt::utils::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: CConfigFileBase.h:31
mrpt::hwdrivers::CVelodyneScanner::setPCAPOutputFile
void setPCAPOutputFile(const std::string &out_pcap_file)
Enables dumping to a PCAP file in parallel to returning regular MRPT objects.
Definition: CVelodyneScanner.h:202
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:73
mrpt::hwdrivers::CVelodyneScanner::m_pcap_output_file
std::string m_pcap_output_file
Default: "" (do not dump to an offline file)
Definition: CVelodyneScanner.h:149
CGenericSensor.h
TEnumType.h
mrpt::hwdrivers::CVelodyneScanner::m_pcap_out
void * m_pcap_out
opaque ptr: "pcap_t*"
Definition: CVelodyneScanner.h:156
mrpt::obs::VelodyneCalibration
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
Definition: VelodyneCalibration.h:31
mrpt::hwdrivers::CVelodyneScanner::getPCAPInputFileReadOnce
bool getPCAPInputFileReadOnce() const
Definition: CVelodyneScanner.h:206
mrpt::hwdrivers::CVelodyneScanner::m_pcap_read_full_scan_delay_ms
double m_pcap_read_full_scan_delay_ms
(Default:100 ms) delay after each full scan read from a PCAP log
Definition: CVelodyneScanner.h:163
mrpt::hwdrivers::CVelodyneScanner::getPosPacketsMinPeriod
double getPosPacketsMinPeriod() const
Definition: CVelodyneScanner.h:184
mrpt::hwdrivers::CVelodyneScanner::m_pcap
void * m_pcap
opaque ptr: "pcap_t*"
Definition: CVelodyneScanner.h:155
mrpt::hwdrivers::CVelodyneScanner::m_pos_packets_min_period
double m_pos_packets_min_period
Default: 0.5 seconds.
Definition: CVelodyneScanner.h:144
mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific
void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string &section)
See the class documentation at the top for expected parameters.
mrpt::hwdrivers::CVelodyneScanner::m_pos_packets_timing_timeout
double m_pos_packets_timing_timeout
Default: 30 seconds.
Definition: CVelodyneScanner.h:145
mrpt::hwdrivers::CVelodyneScanner::m_pcap_file_empty
bool m_pcap_file_empty
Definition: CVelodyneScanner.h:159
mrpt::hwdrivers::CVelodyneScanner::m_pcap_read_count
unsigned int m_pcap_read_count
number of pkts read from the file so far (for debugging)
Definition: CVelodyneScanner.h:160
mrpt::hwdrivers::CVelodyneScanner::m_pcap_input_file
std::string m_pcap_input_file
Default: "" (do not operate from an offline file)
Definition: CVelodyneScanner.h:148
mrpt::hwdrivers::CGenericSensor
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
Definition: CGenericSensor.h:64
CObservationVelodyneScan.h
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory::getListKnownModels
static std::string getListKnownModels()
Return human-readable string: "`VLP16`,`XXX`,...".
mrpt::hwdrivers::CVelodyneScanner::getPosPacketsTimingTimeout
double getPosPacketsTimingTimeout() const
Definition: CVelodyneScanner.h:188
CConfigFileBase.h
mrpt::hwdrivers::CVelodyneScanner::m_device_ip
std::string m_device_ip
Default: "" (no IP-based filtering)
Definition: CVelodyneScanner.h:146
CObservationGPS.h
mrpt::hwdrivers::CVelodyneScanner::m_initialized
bool m_initialized
Definition: CVelodyneScanner.h:142
mrpt::obs::CObservationVelodyneScan::TVelodynePositionPacket
Payload of one POSITION packet.
Definition: CObservationVelodyneScan.h:122
mrpt::hwdrivers::CVelodyneScanner::CVelodyneScanner
CVelodyneScanner()
mrpt::utils::TEnumTypeFiller< hwdrivers::CVelodyneScanner::model_t >::fill
static void fill(bimap< enum_t, std::string > &m_map)
Definition: CVelodyneScanner.h:286
mrpt::hwdrivers::CVelodyneScanner::setDeviceIP
void setDeviceIP(const std::string &ip)
UDP packets from other IPs will be ignored.
Definition: CVelodyneScanner.h:191
mrpt::hwdrivers::CVelodyneScanner::m_model
model_t m_model
Default: "VLP16".
Definition: CVelodyneScanner.h:143
mrpt::hwdrivers::CVelodyneScanner::getModelName
model_t getModelName() const
Definition: CVelodyneScanner.h:180
mrpt::obs::gnss::Message_NMEA_RMC
NMEA datum: RMC.
Definition: gnss_messages_ascii_nmea.h:94
mrpt::hwdrivers::CVelodyneScanner::m_sensorPose
mrpt::poses::CPose3D m_sensorPose
Definition: CVelodyneScanner.h:150
mrpt::hwdrivers::CVelodyneScanner::receivePackets
bool receivePackets(mrpt::system::TTimeStamp &data_pkt_timestamp, mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket &out_data_pkt, mrpt::system::TTimeStamp &pos_pkt_timestamp, mrpt::obs::CObservationVelodyneScan::TVelodynePositionPacket &out_pos_pkt)
Users normally would prefer calling getNextObservation() instead.
mrpt::hwdrivers::CVelodyneScanner::internal_receive_UDP_packet
static mrpt::system::TTimeStamp internal_receive_UDP_packet(platform_socket_t hSocket, uint8_t *out_buffer, const size_t expected_packet_size, const std::string &filter_only_from_IP)
HWDRIVERS_IMPEXP
#define HWDRIVERS_IMPEXP
Definition: hwdrivers_impexp.h:82
mrpt::hwdrivers::CVelodyneScanner::setPosPacketsMinPeriod
void setPosPacketsMinPeriod(double period_seconds)
Set the minimum period between the generation of mrpt::obs::CObservationGPS observations from Velodyn...
Definition: CVelodyneScanner.h:183
mrpt::hwdrivers::CVelodyneScanner::getCalibration
const mrpt::obs::VelodyneCalibration & getCalibration() const
Definition: CVelodyneScanner.h:208
mrpt::hwdrivers::CVelodyneScanner::setPCAPInputFileReadOnce
void setPCAPInputFileReadOnce(bool read_once)
Definition: CVelodyneScanner.h:205
mrpt::hwdrivers::CVelodyneScanner::m_rx_scan
mrpt::obs::CObservationVelodyneScanPtr m_rx_scan
In progress RX scan.
Definition: CVelodyneScanner.h:272
mrpt::hwdrivers::CVelodyneScanner::platform_socket_t
int platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
Definition: CVelodyneScanner.h:261
mrpt::hwdrivers::CVelodyneScanner::~CVelodyneScanner
virtual ~CVelodyneScanner()
mrpt::utils::TEnumTypeFiller
Only specializations of this class are defined for each enum type of interest.
Definition: TEnumType.h:24
mrpt::hwdrivers::CVelodyneScanner::TModelProperties::maxRange
double maxRange
Definition: CVelodyneScanner.h:132
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory::get
static const model_properties_list_t & get()
Singleton access.



Page generated by Doxygen 1.8.20 for MRPT 1.4.0 SVN: at Thu Aug 27 02:40:23 UTC 2020