Main MRPT website > C++ reference for MRPT 1.9.9
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-2018, 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 
18 
19 namespace mrpt
20 {
21 namespace hwdrivers
22 {
23 /** A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working
24  * on Linux and Windows.
25  * (Using this class requires WinPCap as a run-time dependency in Windows).
26  * It can receive data from real devices via an Ethernet connection or parse a
27  * WireShark PCAP file for offline processing.
28  * The choice of online vs. offline operation is taken upon calling \a
29  * initialize(): if a PCAP input file has been defined,
30  * offline operation takes place and network is not listened for incomming
31  * packets.
32  *
33  * Parsing dual return scans requires a VLP-16 with firmware version 3.0.23 or
34  * newer. While converting the scan into a
35  * point cloud in mrpt::obs::CObservationVelodyneScan you can select whether to
36  * keep the strongest, the last or both laser returns.
37  *
38  * XML calibration files are not mandatory for VLP-16 and HDL-32, but they are
39  * for HDL-64.
40  *
41  * <h2>Grabbing live data (as a user)</h2> <hr>
42  * - Use the application
43  * [velodyne-view](http://www.mrpt.org/list-of-mrpt-apps/application-velodyne-view/)
44  * to visualize the LIDAR output in real-time (optionally saving to a PCAP file)
45  * or to playback a PCAP file.
46  * - Use
47  * [rawlog-grabber](http://www.mrpt.org/list-of-mrpt-apps/application-rawlog-grabber/)
48  * to record a dataset in MRPT's format together with any other set of sensors.
49  * See example config file:
50  * [MRPT\share\mrpt\config_files\rawlog-grabber\velodyne.ini](https://github.com/MRPT/mrpt/blob/master/share/mrpt/config_files/rawlog-grabber/velodyne.ini)
51  *
52  * <h2>Grabbing live data (programmatically)</h2> <hr>
53  * - See CGenericSensor for a general overview of the sequence of methods to
54  * be called: loadConfig(), initialize(), doProcess().
55  * - Or use this class inside the application
56  * [rawlog-grabber](http://www.mrpt.org/list-of-mrpt-apps/application-rawlog-grabber/).
57  * See example config files:
58  * [MRPT\share\mrpt\config_files\rawlog-grabber\velodyne.ini](https://github.com/MRPT/mrpt/blob/master/share/mrpt/config_files/rawlog-grabber/velodyne.ini)
59  *
60  * See the source code of the example application `[MRPT]/apps/velodyne-view`
61  * ([velodyne-view web
62  * page](http://www.mrpt.org/list-of-mrpt-apps/application-velodyne-view/)) for
63  * more details.
64  *
65  * <h2>Playing back a PCAP file:</h2><hr>
66  * It is common to save Velodyne datasets as Wireshark's PCAP files.
67  * These files can be played back with tools like
68  * [bittwist](http://bittwist.sourceforge.net/), which emit all UDP packets in
69  * the PCAP log.
70  * Then, use this class to receive the packets as if they come from the real
71  * sensor.
72  *
73  * Alternatively, if MRPT is linked against libpcap, this class can directly
74  * parse a PCAP file to simulate reading from a device offline.
75  * See method setPCAPInputFile() and config file parameter ``
76  *
77  * To compile with PCAP support: In Debian/Ubuntu, install libpcap-dev. In
78  * Windows, install WinPCap developer packages + the regular WinPCap driver.
79  *
80  * <h2>Configuration and usage:</h2> <hr>
81  * Data is returned as observations of type:
82  * - mrpt::obs::CObservationVelodyneScan for one or more "data packets" (refer
83  * to Velodyne usage manual)
84  * - mrpt::obs::CObservationGPS for GPS (GPRMC) packets, if available via the
85  * synchronization interface of the device.
86  * See those classes for documentation on their fields.
87  *
88  * Configuration includes setting the device IP (optional) and sensor model
89  * (mandatory only if a calibration file is not provided).
90  * These parameters can be set programmatically (see methods of this class), or
91  * via a configuration file with CGenericSensor::loadConfig() (see example
92  * config file section below).
93  *
94  * <h2>About timestamps:</h2><hr>
95  * Each gathered observation of type mrpt::obs::CObservationVelodyneScan is
96  * populated with two timestamps, one for the local PC timestamp and,
97  * if available, another one for the GPS-stamped timestamp. Refer to the
98  * observation docs for details.
99  *
100  * <h2>Format of parameters for loading from a .ini file</h2><hr>
101  * \code
102  * PARAMETERS IN THE ".INI"-LIKE CONFIGURATION STRINGS:
103  * -------------------------------------------------------
104  * [supplied_section_name]
105  * # ---- Sensor description ----
106  * #calibration_file = PUT_HERE_FULL_PATH_TO_CALIB_FILE.xml //
107  * Optional but recommended: put here your vendor-provided calibration file
108  * model = VLP16 // Can be any of: `VLP16`, `HDL32`,
109  * `HDL64` (It is used to load default calibration file. Parameter not required
110  * if `calibration_file` is provided.
111  * #pos_packets_min_period = 0.5 // (Default=0.5 seconds) Minimum
112  * period to leave between reporting position packets. Used to decimate the
113  * large number of packets of this type.
114  * # How long to wait, after loss of GPS signal, to report timestamps as "not
115  * based on satellite time". 30 secs, with typical velodyne clock drifts, means
116  * a ~1.7 ms typical drift.
117  * #pos_packets_timing_timeout = 30 // (Default=30 seconds)
118  * # ---- Online operation ----
119  *
120  * # IP address of the device. UDP packets from other IPs will be ignored.
121  * Leave commented or blank
122  * # if only one scanner is present (no IP filtering)
123  * #device_ip = XXX.XXX.XXX.XXX
124  *
125  * #rpm = 600 // Sensor RPM (Default: unchanged). Requires
126  * setting `device_ip`
127  * #return_type = STRONGEST // Any of: 'STRONGEST', 'LAST', 'DUAL'
128  * (Default: unchanged). Requires setting `device_ip`
129  *
130  * # ---- Offline operation ----
131  * # If uncommented, this class will read from the PCAP instead of connecting
132  * and listeling
133  * # for online network packets.
134  * # pcap_input = PUT_FULL_PATH_TO_PCAP_LOG_FILE.pcap
135  * # pcap_read_once = false // Do not loop
136  * # pcap_read_fast = false // fast forward skipping non-velodyne packets
137  * # pcap_read_full_scan_delay_ms = 100 // Used to simulate a reasonable
138  * number of full scans / second
139  * # pcap_repeat_delay = 0.0 // seconds
140  *
141  * # ---- Save to PCAP file ----
142  * # If uncommented, a PCAP file named
143  * `[pcap_output_prefix]_[DATE_TIME].pcap` will be
144  * # written simultaneously to the normal operation of this class.
145  * # pcap_output = velodyne_log
146  *
147  * # 3D position of the sensor on the vehicle:
148  * pose_x = 0 // 3D position (meters)
149  * pose_y = 0
150  * pose_z = 0
151  * pose_yaw = 0 // 3D orientation (degrees)
152  * pose_pitch = 0
153  * pose_roll = 0
154  *
155  * \endcode
156  *
157  *
158  * <h2>Copyright notice</h2><hr>
159  * Portions of this class are based on code from velodyne ROS node in
160  * https://github.com/ros-drivers/velodyne
161  * Copyright (C) 2007 Austin Robot Technology, Patrick Beeson
162  * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
163  * License: Modified BSD Software License Agreement
164  *
165  * \note New in MRPT 1.4.0
166  * \ingroup mrpt_hwdrivers_grp
167  */
169 {
171  public:
172  /** Default: 2368. Change it if required. */
173  static short int VELODYNE_DATA_UDP_PORT;
174  /** Default: 8308. Change it if required. */
175  static short int VELODYNE_POSITION_UDP_PORT;
176 
177  /** LIDAR model types */
178  enum model_t
179  {
180  VLP16 = 1,
181  HDL32 = 2,
182  HDL64 = 3
183  };
184 
185  /** LIDAR return type */
187  {
192  };
193 
194  /** Hard-wired properties of LIDARs depending on the model */
196  {
197  double maxRange;
198  };
199  using model_properties_list_t = std::map<model_t, TModelProperties>;
200  /** Access to default sets of parameters for Velodyne LIDARs */
202  {
203  /** Singleton access */
204  static const model_properties_list_t& get();
205  /** Return human-readable string: "`VLP16`,`XXX`,..." */
207  };
208 
209  protected:
211  /** Default: "VLP16" */
213  /** Default: 0.5 seconds */
215  /** Default: 30 seconds */
217  /** Default: "" (no IP-based filtering) */
219  /** Default: true Output whole frames and not data packets */
221  /** Default: true Output PCAP Info msgs */
223  /** Default: "" (do not operate from an offline file) */
225  /** Default: "" (do not dump to an offline file) */
228  /** Device calibration file (supplied by vendor in an XML file) */
231 
232  // offline operation:
233  /** opaque ptr: "pcap_t*" */
234  void* m_pcap;
235  /** opaque ptr: "pcap_t*" */
236  void* m_pcap_out;
237  /** opaque ptr: "pcap_dumper_t *" */
239  /** opaque ptr: bpf_program* */
242  /** number of pkts read from the file so far (for debugging) */
243  unsigned int m_pcap_read_count;
244  /** Default: false */
246  /** (Default: false) If false, will use m_pcap_read_full_scan_delay_ms */
248  /** (Default:100 ms) delay after each full scan read from a PCAP log */
250  /** Default: 0 (in seconds) */
252 
253  /** See the class documentation at the top for expected parameters */
255  const mrpt::config::CConfigFileBase& configSource,
256  const std::string& section);
257 
258  public:
260  virtual ~CVelodyneScanner();
261 
262  /** @name Change configuration parameters; to be called BEFORE initialize();
263  * see above for the list of parameters and their meaning
264  * @{ */
265  /** See supported model names in the general discussion docs for
266  * mrpt::hwdrivers::CVelodyneScanner */
268  model_t getModelName() const { return m_model; }
269  /** Set the minimum period between the generation of
270  * mrpt::obs::CObservationGPS observations from Velodyne Position RMC GPS
271  * packets */
272  void setPosPacketsMinPeriod(double period_seconds)
273  {
274  m_pos_packets_min_period = period_seconds;
275  }
277  /** Set how long to wait, after loss of GPS signal, to report timestamps as
278  * "not based on satellite time". 30 secs, with typical velodyne clock
279  * drifts, means a ~1.7 ms typical drift. */
280  void setPosPacketsTimingTimeout(double timeout)
281  {
283  }
285  {
287  }
288 
289  /** UDP packets from other IPs will be ignored. Default: empty string, means
290  * do not filter by IP */
291  void setDeviceIP(const std::string& ip) { m_device_ip = ip; }
292  const std::string& getDeviceIP() const { return m_device_ip; }
293  /** Enables/disables PCAP info messages to console (default: true) */
294  void setPCAPVerbosity(const bool verbose) { m_pcap_verbose = verbose; }
295  /** Enables reading from a PCAP file instead of live UDP packet listening */
296  void setPCAPInputFile(const std::string& pcap_file)
297  {
298  m_pcap_input_file = pcap_file;
299  }
300  const std::string& getPCAPInputFile() const { return m_pcap_input_file; }
301  /** Enables dumping to a PCAP file in parallel to returning regular MRPT
302  * objects. Default="": no pcap log. */
303  void setPCAPOutputFile(const std::string& out_pcap_file)
304  {
305  m_pcap_output_file = out_pcap_file;
306  }
308  void setPCAPInputFileReadOnce(bool read_once)
309  {
310  m_pcap_read_once = read_once;
311  }
314  {
315  return m_velodyne_calib;
316  }
318  {
319  m_velodyne_calib = calib;
320  }
321  /** Returns false on error. \sa
322  * mrpt::obs::VelodyneCalibration::loadFromXMLFile() */
323  bool loadCalibrationFile(const std::string& velodyne_xml_calib_file_path);
324 
325  /** Changes among STRONGEST, LAST, DUAL return types (via HTTP post
326  * interface).
327  * Can be called at any instant, before or after initialize().
328  * Requires setting a device IP address.
329  * \return false on error */
330  bool setLidarReturnType(return_type_t ret_type);
331 
332  /** Changes Lidar RPM (valid range: 300-600) (via HTTP post interface).
333  * Can be called at any instant, before or after initialize().
334  * Requires setting a device IP address.
335  * \return false on error*/
336  bool setLidarRPM(int rpm);
337 
338  /** Switches the LASER on/off (saves energy when not measuring) (via HTTP
339  * post interface).
340  * Can be called at any instant, before or after initialize().
341  * Requires setting a device IP address.
342  * \return false on error*/
343  bool setLidarOnOff(bool on);
344 
345  /** Switches whole frame (points in a single revolution) on/off publication
346  * to data packet publication. When on, getNextObservation() will return
347  * true whenever a frame is avaliable, when off, getNextObservation() will
348  * return true whenever a data packet is avaliable. The default is on. When
349  * listening to data packets on a PCAP, pcap_read_fast is enforced.
350  */
351  void setFramePublishing(bool on);
352 
353  /** @} */
354 
355  /** Polls the UDP port for incoming data packets. The user *must* call this
356  * method in a timely fashion to grab data as it it generated by the device.
357  * The minimum call rate should be the expected number of data
358  * packets/second (!=scans/second). Checkout Velodyne user manual if in
359  * doubt.
360  *
361  * \param[out] outScan Upon return, an empty smart pointer will be found
362  * here if no new data was available. Otherwise, a valid scan.
363  * \param[out] outGPS Upon return, an empty smart pointer will be found
364  * here if no new GPS data was available. Otherwise, a valid GPS reading.
365  * \return true if no error ocurred (even if there was no new observation).
366  * false if any communication error occurred.
367  */
368  bool getNextObservation(
371 
372  // See docs in parent class
373  void doProcess();
374 
375  /** Tries to initialize the sensor driver, after setting all the parameters
376  * with a call to loadConfig.
377  * Velodyne specifics: this method sets up the UDP listening sockets, so
378  * all relevant params MUST BE SET BEFORE calling this.
379  * \exception This method must throw an exception with a descriptive
380  * message if some critical error is found.
381  */
382  virtual void initialize();
383 
384  /** Close the UDP sockets set-up in \a initialize(). This is called
385  * automatically upon destruction */
386  void close();
387 
388  /** Users normally would prefer calling \a getNextObservation() instead.
389  * This method polls the UDP data port and returns one Velodyne DATA packet
390  * (1206 bytes) and/or one POSITION packet. Refer to Velodyne users manual.
391  * Approximate timestamps (based on this computer clock) are returned for
392  * each kind of packets, or INVALID_TIMESTAMP if timeout ocurred waiting for
393  * a packet.
394  * \return true on all ok. false only for pcap reading EOF
395  */
396  bool receivePackets(
397  mrpt::system::TTimeStamp& data_pkt_timestamp,
399  mrpt::system::TTimeStamp& pos_pkt_timestamp,
401  out_pos_pkt);
402 
403  private:
404  /** Handles for the UDP sockets, or INVALID_SOCKET (-1) */
405  using platform_socket_t =
406 #ifdef _WIN32
407 #if MRPT_WORD_SIZE == 64
408  uint64_t
409 #else
410  uint32_t
411 #endif
412 #else
413  int
414 #endif
415  ;
416 
418 
420  platform_socket_t hSocket, uint8_t* out_buffer,
421  const size_t expected_packet_size,
422  const std::string& filter_only_from_IP);
423 
425  mrpt::system::TTimeStamp& data_pkt_time, uint8_t* out_data_buffer,
426  mrpt::system::TTimeStamp& pos_pkt_time, uint8_t* out_pos_buffer);
427 
428  /** In progress RX scan */
430 
435 
436  bool internal_send_http_post(const std::string& post_data);
437 
438 }; // end of class
439 } // namespace hwdrivers
440 } // namespace mrpt
441 
443 using namespace mrpt::hwdrivers;
448 
449 MRPT_ENUM_TYPE_BEGIN(mrpt::hwdrivers::CVelodyneScanner::return_type_t)
450 using namespace mrpt::hwdrivers;
456 
457 #endif
mrpt::hwdrivers::CVelodyneScanner::m_rx_scan
mrpt::obs::CObservationVelodyneScan::Ptr m_rx_scan
In progress RX scan.
Definition: CVelodyneScanner.h:429
mrpt::hwdrivers::CVelodyneScanner::TModelProperties
Hard-wired properties of LIDARs depending on the model.
Definition: CVelodyneScanner.h:195
mrpt::hwdrivers::CVelodyneScanner::m_pcap_dumper
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
Definition: CVelodyneScanner.h:238
mrpt::hwdrivers::CVelodyneScanner::m_lidar_rpm
int m_lidar_rpm
Definition: CVelodyneScanner.h:433
mrpt::hwdrivers::CVelodyneScanner::m_return_frames
bool m_return_frames
Default: true Output whole frames and not data packets
Definition: CVelodyneScanner.h:220
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)
Definition: CVelodyneScanner.cpp:800
mrpt::hwdrivers::CVelodyneScanner::model_properties_list_t
std::map< model_t, TModelProperties > model_properties_list_t
Definition: CVelodyneScanner.h:199
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:296
mrpt::hwdrivers::CVelodyneScanner::DUAL
@ DUAL
Definition: CVelodyneScanner.h:191
mrpt::hwdrivers::CVelodyneScanner::m_last_gps_rmc
mrpt::obs::gnss::Message_NMEA_RMC m_last_gps_rmc
Definition: CVelodyneScanner.h:431
mrpt::hwdrivers::CVelodyneScanner::HDL64
@ HDL64
Definition: CVelodyneScanner.h:182
MRPT_ENUM_TYPE_END
#define MRPT_ENUM_TYPE_END()
Definition: TEnumType.h:74
mrpt::hwdrivers::CVelodyneScanner::getNextObservation
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
Definition: CVelodyneScanner.cpp:211
mrpt::hwdrivers::CVelodyneScanner::m_last_gps_rmc_age
mrpt::system::TTimeStamp m_last_gps_rmc_age
Definition: CVelodyneScanner.h:432
mrpt::hwdrivers::CVelodyneScanner::VELODYNE_POSITION_UDP_PORT
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308.
Definition: CVelodyneScanner.h:175
mrpt::hwdrivers::CVelodyneScanner::m_last_pos_packet_timestamp
mrpt::system::TTimeStamp m_last_pos_packet_timestamp
Definition: CVelodyneScanner.h:230
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory
Access to default sets of parameters for Velodyne LIDARs.
Definition: CVelodyneScanner.h:201
mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket
One unit of data from the scanner (the payload of one UDP DATA packet)
Definition: CObservationVelodyneScan.h:132
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:280
mrpt::hwdrivers::CVelodyneScanner::getPCAPInputFile
const std::string & getPCAPInputFile() const
Definition: CVelodyneScanner.h:300
mrpt::hwdrivers::CVelodyneScanner::VLP16
@ VLP16
Definition: CVelodyneScanner.h:180
mrpt::hwdrivers::CVelodyneScanner::getCalibration
const mrpt::obs::VelodyneCalibration & getCalibration() const
Definition: CVelodyneScanner.h:313
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)
Definition: CVelodyneScanner.cpp:907
mrpt::hwdrivers
Contains classes for various device interfaces.
Definition: C2DRangeFinderAbstract.h:22
mrpt::hwdrivers::CVelodyneScanner::m_hPositionSock
platform_socket_t m_hPositionSock
Definition: CVelodyneScanner.h:417
mrpt::hwdrivers::CVelodyneScanner::setPCAPVerbosity
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
Definition: CVelodyneScanner.h:294
mrpt::hwdrivers::CVelodyneScanner::m_pcap_bpf_program
void * m_pcap_bpf_program
opaque ptr: bpf_program*
Definition: CVelodyneScanner.h:240
mrpt::hwdrivers::CVelodyneScanner::getDeviceIP
const std::string & getDeviceIP() const
Definition: CVelodyneScanner.h:292
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.
Definition: CVelodyneScanner.cpp:638
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory::getListKnownModels
static std::string getListKnownModels()
Return human-readable string: "`VLP16`,`XXX`,...".
Definition: CVelodyneScanner.cpp:82
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
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:314
uint8_t
unsigned char uint8_t
Definition: rptypes.h:41
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:267
mrpt::hwdrivers::CVelodyneScanner::HDL32
@ HDL32
Definition: CVelodyneScanner.h:181
MRPT_ENUM_TYPE_BEGIN
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
Definition: TEnumType.h:58
mrpt::hwdrivers::CVelodyneScanner::m_pcap_verbose
bool m_pcap_verbose
Default: true Output PCAP Info msgs.
Definition: CVelodyneScanner.h:222
CObservationGPS.h
mrpt::hwdrivers::CVelodyneScanner::model_t
model_t
LIDAR model types.
Definition: CVelodyneScanner.h:178
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:247
mrpt::hwdrivers::CVelodyneScanner::m_pcap_read_once
bool m_pcap_read_once
Default: false.
Definition: CVelodyneScanner.h:245
mrpt::hwdrivers::CVelodyneScanner::close
void close()
Close the UDP sockets set-up in initialize().
Definition: CVelodyneScanner.cpp:562
mrpt::hwdrivers::CVelodyneScanner::TModelPropertiesFactory::get
static const model_properties_list_t & get()
Singleton access.
Definition: CVelodyneScanner.cpp:69
mrpt::hwdrivers::CVelodyneScanner::m_hDataSock
platform_socket_t m_hDataSock
Definition: CVelodyneScanner.h:417
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:31
mrpt::hwdrivers::CVelodyneScanner::getPCAPOutputFile
const std::string & getPCAPOutputFile() const
Definition: CVelodyneScanner.h:307
CConfigFileBase.h
mrpt::hwdrivers::CVelodyneScanner::setCalibration
void setCalibration(const mrpt::obs::VelodyneCalibration &calib)
Definition: CVelodyneScanner.h:317
mrpt::hwdrivers::CVelodyneScanner::LAST
@ LAST
Definition: CVelodyneScanner.h:190
mrpt::hwdrivers::CVelodyneScanner::STRONGEST
@ STRONGEST
Definition: CVelodyneScanner.h:189
mrpt::hwdrivers::CVelodyneScanner::internal_send_http_post
bool internal_send_http_post(const std::string &post_data)
Definition: CVelodyneScanner.cpp:1104
mrpt::hwdrivers::CVelodyneScanner::initialize
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig.
Definition: CVelodyneScanner.cpp:401
mrpt::hwdrivers::CVelodyneScanner
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows.
Definition: CVelodyneScanner.h:168
mrpt::hwdrivers::CVelodyneScanner::m_lidar_return
return_type_t m_lidar_return
Definition: CVelodyneScanner.h:434
mrpt::obs::CObservationVelodyneScan::Ptr
std::shared_ptr< CObservationVelodyneScan > Ptr
Definition: CObservationVelodyneScan.h:77
mrpt::config::CConfigFileBase
This class allows loading and storing values and vectors of different types from a configuration text...
Definition: config/CConfigFileBase.h:44
mrpt::hwdrivers::CVelodyneScanner::m_pcap_repeat_delay
double m_pcap_repeat_delay
Default: 0 (in seconds)
Definition: CVelodyneScanner.h:251
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:229
mrpt::hwdrivers::CVelodyneScanner::setFramePublishing
void setFramePublishing(bool on)
Switches whole frame (points in a single revolution) on/off publication to data packet publication.
Definition: CVelodyneScanner.cpp:1096
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:303
mrpt::poses::CPose3D
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
mrpt::hwdrivers::CVelodyneScanner::m_pcap_output_file
std::string m_pcap_output_file
Default: "" (do not dump to an offline file)
Definition: CVelodyneScanner.h:226
CGenericSensor.h
MRPT_FILL_ENUM_MEMBER
MRPT_FILL_ENUM_MEMBER(CVelodyneScanner, VLP16)
mrpt::hwdrivers::CVelodyneScanner::CVelodyneScanner
CVelodyneScanner()
Definition: CVelodyneScanner.cpp:98
TEnumType.h
mrpt::hwdrivers::CVelodyneScanner::m_pcap_out
void * m_pcap_out
opaque ptr: "pcap_t*"
Definition: CVelodyneScanner.h:236
mrpt::obs::VelodyneCalibration
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
Definition: VelodyneCalibration.h:31
uint64_t
unsigned __int64 uint64_t
Definition: rptypes.h:50
mrpt::hwdrivers::CVelodyneScanner::getPCAPInputFileReadOnce
bool getPCAPInputFileReadOnce() const
Definition: CVelodyneScanner.h:312
mrpt::hwdrivers::CVelodyneScanner::VELODYNE_DATA_UDP_PORT
static short int VELODYNE_DATA_UDP_PORT
Default: 2368.
Definition: CVelodyneScanner.h:173
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:249
mrpt::hwdrivers::CVelodyneScanner::getPosPacketsMinPeriod
double getPosPacketsMinPeriod() const
Definition: CVelodyneScanner.h:276
mrpt::hwdrivers::CVelodyneScanner::m_pcap
void * m_pcap
opaque ptr: "pcap_t*"
Definition: CVelodyneScanner.h:234
mrpt::obs::CObservationGPS::Ptr
std::shared_ptr< CObservationGPS > Ptr
Definition: CObservationGPS.h:72
mrpt::hwdrivers::CVelodyneScanner::m_pos_packets_min_period
double m_pos_packets_min_period
Default: 0.5 seconds.
Definition: CVelodyneScanner.h:214
mrpt::hwdrivers::CVelodyneScanner::m_pos_packets_timing_timeout
double m_pos_packets_timing_timeout
Default: 30 seconds.
Definition: CVelodyneScanner.h:216
mrpt::hwdrivers::CVelodyneScanner::setLidarOnOff
bool setLidarOnOff(bool on)
Switches the LASER on/off (saves energy when not measuring) (via HTTP post interface).
Definition: CVelodyneScanner.cpp:1087
mrpt::hwdrivers::CVelodyneScanner::m_pcap_file_empty
bool m_pcap_file_empty
Definition: CVelodyneScanner.h:241
mrpt::hwdrivers::CVelodyneScanner::setLidarReturnType
bool setLidarReturnType(return_type_t ret_type)
Changes among STRONGEST, LAST, DUAL return types (via HTTP post interface).
Definition: CVelodyneScanner.cpp:1031
mrpt::hwdrivers::CVelodyneScanner::~CVelodyneScanner
virtual ~CVelodyneScanner()
Definition: CVelodyneScanner.cpp:136
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:243
mrpt::hwdrivers::CVelodyneScanner::m_pcap_input_file
std::string m_pcap_input_file
Default: "" (do not operate from an offline file)
Definition: CVelodyneScanner.h:224
mrpt::hwdrivers::CGenericSensor
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
Definition: CGenericSensor.h:70
mrpt::hwdrivers::CVelodyneScanner::UNCHANGED
@ UNCHANGED
Definition: CVelodyneScanner.h:188
CObservationVelodyneScan.h
mrpt::hwdrivers::CVelodyneScanner::getPosPacketsTimingTimeout
double getPosPacketsTimingTimeout() const
Definition: CVelodyneScanner.h:284
mrpt::hwdrivers::CVelodyneScanner::m_device_ip
std::string m_device_ip
Default: "" (no IP-based filtering)
Definition: CVelodyneScanner.h:218
mrpt::hwdrivers::CVelodyneScanner::m_initialized
bool m_initialized
Definition: CVelodyneScanner.h:210
mrpt::obs::CObservationVelodyneScan::TVelodynePositionPacket
Payload of one POSITION packet.
Definition: CObservationVelodyneScan.h:144
mrpt::hwdrivers::CVelodyneScanner::loadConfig_sensorSpecific
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string &section)
See the class documentation at the top for expected parameters.
Definition: CVelodyneScanner.cpp:155
mrpt::hwdrivers::CVelodyneScanner::platform_socket_t
uint32_t platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
Definition: CVelodyneScanner.h:415
mrpt::hwdrivers::CVelodyneScanner::return_type_t
return_type_t
LIDAR return type.
Definition: CVelodyneScanner.h:186
mrpt::hwdrivers::CVelodyneScanner::setDeviceIP
void setDeviceIP(const std::string &ip)
UDP packets from other IPs will be ignored.
Definition: CVelodyneScanner.h:291
mrpt::hwdrivers::CVelodyneScanner::m_model
model_t m_model
Default: "VLP16".
Definition: CVelodyneScanner.h:212
mrpt::hwdrivers::CVelodyneScanner::getModelName
model_t getModelName() const
Definition: CVelodyneScanner.h:268
mrpt::hwdrivers::CVelodyneScanner::loadCalibrationFile
bool loadCalibrationFile(const std::string &velodyne_xml_calib_file_path)
Returns false on error.
Definition: CVelodyneScanner.cpp:149
mrpt::hwdrivers::CVelodyneScanner::doProcess
void doProcess()
This method will be invoked at a minimum rate of "process_rate" (Hz)
Definition: CVelodyneScanner.cpp:379
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::obs::gnss::Message_NMEA_RMC
NMEA datum: RMC.
Definition: gnss_messages_ascii_nmea.h:137
mrpt::hwdrivers::CVelodyneScanner::m_sensorPose
mrpt::poses::CPose3D m_sensorPose
Definition: CVelodyneScanner.h:227
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:272
mrpt::hwdrivers::CVelodyneScanner::setLidarRPM
bool setLidarRPM(int rpm)
Changes Lidar RPM (valid range: 300-600) (via HTTP post interface).
Definition: CVelodyneScanner.cpp:1067
mrpt::hwdrivers::CVelodyneScanner::setPCAPInputFileReadOnce
void setPCAPInputFileReadOnce(bool read_once)
Definition: CVelodyneScanner.h:308
uint32_t
unsigned __int32 uint32_t
Definition: rptypes.h:47
mrpt::hwdrivers::CVelodyneScanner::TModelProperties::maxRange
double maxRange
Definition: CVelodyneScanner.h:197
model
_u8 model
Definition: rplidar_cmd.h:2



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST