Go to the documentation of this file.
10 #ifndef CVelodyneScanner_H
11 #define CVelodyneScanner_H
407 #if MRPT_WORD_SIZE == 64
421 const size_t expected_packet_size,
450 using namespace
mrpt::hwdrivers;
mrpt::obs::CObservationVelodyneScan::Ptr m_rx_scan
In progress RX scan.
Hard-wired properties of LIDARs depending on the model.
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
bool m_return_frames
Default: true Output whole frames and not data packets
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)
std::map< model_t, TModelProperties > model_properties_list_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
#define MRPT_ENUM_TYPE_END()
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
mrpt::system::TTimeStamp m_last_gps_rmc_age
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308.
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
const mrpt::obs::VelodyneCalibration & getCalibration() const
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)
Contains classes for various device interfaces.
platform_socket_t m_hPositionSock
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
void * m_pcap_bpf_program
opaque ptr: bpf_program*
const std::string & getDeviceIP() 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.
static std::string getListKnownModels()
Return human-readable string: "`VLP16`,`XXX`,...".
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.
#define MRPT_ENUM_TYPE_BEGIN(_ENUM_TYPE_WITH_NS)
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.
void close()
Close the UDP sockets set-up in initialize().
static const model_properties_list_t & get()
Singleton access.
platform_socket_t m_hDataSock
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)
bool internal_send_http_post(const std::string &post_data)
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig.
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows.
return_type_t m_lidar_return
std::shared_ptr< CObservationVelodyneScan > Ptr
This class allows loading and storing values and vectors of different types from a configuration text...
double m_pcap_repeat_delay
Default: 0 (in seconds)
mrpt::obs::VelodyneCalibration m_velodyne_calib
Device calibration file (supplied by vendor in an XML file)
void setFramePublishing(bool on)
Switches whole frame (points in a single revolution) on/off publication to data packet publication.
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)
MRPT_FILL_ENUM_MEMBER(CVelodyneScanner, VLP16)
void * m_pcap_out
opaque ptr: "pcap_t*"
Velodyne calibration data, for usage in mrpt::obs::CObservationVelodyneScan.
unsigned __int64 uint64_t
bool getPCAPInputFileReadOnce() const
static short int VELODYNE_DATA_UDP_PORT
Default: 2368.
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*"
std::shared_ptr< CObservationGPS > Ptr
double m_pos_packets_min_period
Default: 0.5 seconds.
double m_pos_packets_timing_timeout
Default: 30 seconds.
bool setLidarOnOff(bool on)
Switches the LASER on/off (saves energy when not measuring) (via HTTP post interface).
bool setLidarReturnType(return_type_t ret_type)
Changes among STRONGEST, LAST, DUAL return types (via HTTP post interface).
virtual ~CVelodyneScanner()
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.
void loadConfig_sensorSpecific(const mrpt::config::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
uint32_t platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
return_type_t
LIDAR return type.
void setDeviceIP(const std::string &ip)
UDP packets from other IPs will be ignored.
model_t m_model
Default: "VLP16".
model_t getModelName() const
bool loadCalibrationFile(const std::string &velodyne_xml_calib_file_path)
Returns false on error.
void doProcess()
This method will be invoked at a minimum rate of "process_rate" (Hz)
GLsizei const GLchar ** string
mrpt::poses::CPose3D m_sensorPose
void setPosPacketsMinPeriod(double period_seconds)
Set the minimum period between the generation of mrpt::obs::CObservationGPS observations from Velodyn...
bool setLidarRPM(int rpm)
Changes Lidar RPM (valid range: 300-600) (via HTTP post interface).
void setPCAPInputFileReadOnce(bool read_once)
unsigned __int32 uint32_t
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 | |