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