Go to the documentation of this file.
10 #ifndef CVelodyneScanner_H
11 #define CVelodyneScanner_H
138 static std::string getListKnownModels();
168 void loadConfig_sensorSpecific(
170 const std::string §ion );
202 void setPCAPOutputFile(
const std::string &out_pcap_file) { m_pcap_output_file = out_pcap_file; }
210 bool loadCalibrationFile(
const std::string & velodyne_xml_calib_file_path );
220 bool getNextObservation(
221 mrpt::obs::CObservationVelodyneScanPtr & outScan,
222 mrpt::obs::CObservationGPSPtr & outGPS
232 virtual void initialize();
252 #ifdef MRPT_OS_WINDOWS
253 # if MRPT_WORD_SIZE==64
267 bool internal_read_PCAP_packet(
Hard-wired properties of LIDARs depending on the model.
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
void setPCAPInputFile(const std::string &pcap_file)
Enables reading from a PCAP file instead of live UDP packet listening.
mrpt::obs::gnss::Message_NMEA_RMC m_last_gps_rmc
static short int VELODYNE_DATA_UDP_PORT
Default: 2368. Change it if required.
std::map< model_t, TModelProperties > model_properties_list_t
mrpt::system::TTimeStamp m_last_gps_rmc_age
mrpt::system::TTimeStamp m_last_pos_packet_timestamp
Access to default sets of parameters for Velodyne LIDARs.
One unit of data from the scanner (the payload of one UDP DATA packet)
void setPosPacketsTimingTimeout(double timeout)
Set how long to wait, after loss of GPS signal, to report timestamps as "not based on satellite time"...
const std::string & getPCAPInputFile() const
mrpt::obs::VelodyneCalibration m_velodyne_calib
Device calibration file (supplied by vendor in an XML file)
A bidirectional version of std::map, declared as bimap<KEY,VALUE> and which actually contains two std...
hwdrivers::CVelodyneScanner::model_t enum_t
platform_socket_t m_hPositionSock
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308. Change it if required.
void * m_pcap_bpf_program
opaque ptr: bpf_program*
const std::string & getDeviceIP() const
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_GENERIC_SENSOR(class_name)
This declaration must be inserted in all CGenericSensor classes definition, within the class declarat...
void setModelName(const model_t model)
See supported model names in the general discussion docs for mrpt::hwdrivers::CVelodyneScanner.
bool m_pcap_verbose
Default: true Output PCAP Info msgs.
model_t
LIDAR model types.
bool m_pcap_read_fast
(Default: false) If false, will use m_pcap_read_full_scan_delay_ms
bool m_pcap_read_once
Default: false.
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1,...
const std::string & getPCAPOutputFile() const
void setCalibration(const mrpt::obs::VelodyneCalibration &calib)
void insert(const KEY &k, const VALUE &v)
Insert a new pair KEY<->VALUE in the bi-map.
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Windows and Linux.
double m_pcap_repeat_delay
Default: 0 (in seconds)
This class allows loading and storing values and vectors of different types from a configuration text...
void setPCAPOutputFile(const std::string &out_pcap_file)
Enables dumping to a PCAP file in parallel to returning regular MRPT objects.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
std::string m_pcap_output_file
Default: "" (do not dump to an offline file)
void * m_pcap_out
opaque ptr: "pcap_t*"
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
bool getPCAPInputFileReadOnce() const
double m_pcap_read_full_scan_delay_ms
(Default:100 ms) delay after each full scan read from a PCAP log
double getPosPacketsMinPeriod() const
void * m_pcap
opaque ptr: "pcap_t*"
double m_pos_packets_min_period
Default: 0.5 seconds.
double m_pos_packets_timing_timeout
Default: 30 seconds.
unsigned int m_pcap_read_count
number of pkts read from the file so far (for debugging)
std::string m_pcap_input_file
Default: "" (do not operate from an offline file)
A generic interface for a wide-variety of sensors designed to be used in the application RawLogGrabbe...
double getPosPacketsTimingTimeout() const
std::string m_device_ip
Default: "" (no IP-based filtering)
Payload of one POSITION packet.
static void fill(bimap< enum_t, std::string > &m_map)
void setDeviceIP(const std::string &ip)
UDP packets from other IPs will be ignored.
model_t m_model
Default: "VLP16".
model_t getModelName() const
mrpt::poses::CPose3D m_sensorPose
void setPosPacketsMinPeriod(double period_seconds)
Set the minimum period between the generation of mrpt::obs::CObservationGPS observations from Velodyn...
const mrpt::obs::VelodyneCalibration & getCalibration() const
void setPCAPInputFileReadOnce(bool read_once)
mrpt::obs::CObservationVelodyneScanPtr m_rx_scan
In progress RX scan.
int platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
Only specializations of this class are defined for each enum type of interest.
Page generated by Doxygen 1.8.16 for MRPT 1.4.0 SVN: at Mon Oct 14 23:11:08 UTC 2019 | | |