22 #ifdef MRPT_OS_WINDOWS 23 #define _WINSOCK_DEPRECATED_NO_WARNINGS 24 #if defined(_WIN32_WINNT) && (_WIN32_WINNT < 0x600) 26 #define _WIN32_WINNT 0x600 // Minimum: Windows Vista (required to pollfd) 30 typedef int socklen_t;
32 #if defined(__BORLANDC__) || defined(_MSC_VER) 33 #pragma comment(lib, "WS2_32.LIB") 37 #define INVALID_SOCKET (-1) 39 #include <sys/socket.h> 43 #include <sys/types.h> 44 #include <sys/ioctl.h> 46 #include <arpa/inet.h> 47 #include <netinet/in.h> 48 #include <netinet/tcp.h> 54 #if !defined(PCAP_NETMASK_UNKNOWN) // for older pcap versions 55 #define PCAP_NETMASK_UNKNOWN 0xffffffff 73 static bool init =
false;
81 return modelProperties;
90 it != lst.end(); ++it)
101 m_pos_packets_min_period(0.5),
102 m_pos_packets_timing_timeout(30.0),
104 m_pcap_verbose(true),
108 m_pcap_dumper(nullptr),
109 m_pcap_bpf_program(nullptr),
110 m_pcap_file_empty(true),
111 m_pcap_read_once(false),
112 m_pcap_read_fast(false),
113 m_pcap_read_full_scan_delay_ms(100),
114 m_pcap_repeat_delay(0.0),
119 m_lidar_return(UNCHANGED)
127 #ifdef MRPT_OS_WINDOWS 129 WORD wVersionRequested = MAKEWORD(2, 0);
131 if (WSAStartup(wVersionRequested, &wsaData))
139 #ifdef MRPT_OS_WINDOWS 194 if (lstModels.find(
m_model) == lstModels.end())
198 "Unrecognized `model` parameter: `%u` . Known values are: %s",
199 static_cast<unsigned int>(
m_model),
228 data_pkt_timestamp, rx_pkt, pos_pkt_timestamp, rx_pos_pkt);
239 mrpt::make_aligned_shared<mrpt::obs::CObservationGPS>();
243 gps_obs->originalReceivedTimestamp = pos_pkt_timestamp;
251 gps_obs->has_satellite_timestamp =
false;
252 gps_obs->timestamp = pos_pkt_timestamp;
277 if (rx_pkt_start_angle <
278 m_rx_scan->scan_packets.rbegin()->blocks[0].rotation)
287 std::this_thread::sleep_for(
288 std::chrono::duration<double, std::milli>(
310 if (it != lstModels.end())
312 m_rx_scan->maxRange = it->second.maxRange;
324 m_rx_scan->originalReceivedTimestamp = data_pkt_timestamp;
353 m_rx_scan->has_satellite_timestamp =
true;
357 m_rx_scan->has_satellite_timestamp =
false;
358 m_rx_scan->timestamp = data_pkt_timestamp;
363 m_rx_scan->scan_packets.push_back(rx_pkt);
370 cerr <<
"[CVelodyneScanner::getObservation] Returning false due to " 373 cerr << e.what() << endl;
392 cerr <<
"ERROR receiving data from Velodyne devic!" << endl;
415 "Could not find default calibration data for the given LIDAR " 416 "`model` name. Please, specify a valid `model` or load a valid " 417 "XML configuration file first.");
441 "Error creating UDP socket:\n%s",
444 struct sockaddr_in bindAddr;
445 memset(&bindAddr, 0,
sizeof(bindAddr));
446 bindAddr.sin_family = AF_INET;
448 bindAddr.sin_addr.s_addr = INADDR_ANY;
452 m_hDataSock, (
struct sockaddr*)(&bindAddr),
sizeof(sockaddr)))
455 #ifdef MRPT_OS_WINDOWS 456 unsigned long non_block_mode = 1;
457 if (ioctlsocket(
m_hDataSock, FIONBIO, &non_block_mode))
459 "Error entering non-blocking mode with ioctlsocket().");
464 oldflags |= O_NONBLOCK | FASYNC;
475 "Error creating UDP socket:\n%s",
482 (
struct sockaddr*)(&bindAddr),
486 #ifdef MRPT_OS_WINDOWS 489 "Error entering non-blocking mode with ioctlsocket().");
494 oldflags |= O_NONBLOCK | FASYNC;
502 char errbuf[PCAP_ERRBUF_SIZE];
506 "\n[CVelodyneScanner] Opening PCAP file \"%s\"\n",
517 "(udp dst port %d || udp dst port %d)",
524 "[CVelodyneScanner] Error calling pcap_compile: ";
538 reinterpret_cast<pcap_t*>(
m_pcap),
540 filter_str.c_str(), 1, PCAP_NETMASK_UNKNOWN) < 0)
541 pcap_perror(reinterpret_cast<pcap_t*>(
m_pcap), &sMsgError[0]);
549 "Velodyne: Reading from PCAP requires building MRPT with libpcap " 566 #ifdef MRPT_OS_WINDOWS 577 #ifdef MRPT_OS_WINDOWS 587 pcap_close(reinterpret_cast<pcap_t*>(
m_pcap));
592 pcap_dump_close(reinterpret_cast<pcap_dumper_t*>(
m_pcap_dumper));
597 pcap_close(reinterpret_cast<pcap_t*>(
m_pcap_out));
606 const uint16_t LidarPacketHeader[21] = {0xffff, 0xffff, 0xffff, 0x7660, 0x0088,
607 0x0000, 0x0008, 0x0045, 0xd204, 0x0000,
608 0x0040, 0x11ff, 0xaab4, 0xa8c0, 0xc801,
612 0xffff, 0x4009, 0x4009, 0xbe04, 0x0000};
613 const uint16_t PositionPacketHeader[21] = {
614 0xffff, 0xffff, 0xffff, 0x7660, 0x0088, 0x0000, 0x0008, 0x0045, 0xd204,
615 0x0000, 0x0040, 0x11ff, 0xaab4, 0xa8c0, 0xc801, 0xffff,
619 0xffff, 0x7420, 0x7420, 0x0802, 0x0000};
622 #if defined(MRPT_OS_WINDOWS) && MRPT_HAS_LIBPCAP 623 int gettimeofday(
struct timeval* tp,
void*)
626 ::GetSystemTimeAsFileTime(&ft);
628 (
static_cast<long long>(ft.dwHighDateTime) << 32) | ft.dwLowDateTime;
629 t -= 116444736000000000LL;
631 tp->tv_sec =
static_cast<long>(
t / 1000000UL);
632 tp->tv_usec =
static_cast<long>(
t % 1000000UL);
645 CObservationVelodyneScan::POS_PACKET_SIZE);
648 CObservationVelodyneScan::PACKET_SIZE);
654 data_pkt_timestamp, (
uint8_t*)&out_data_pkt, pos_pkt_timestamp,
661 CObservationVelodyneScan::PACKET_SIZE,
m_device_ip);
664 CObservationVelodyneScan::POS_PACKET_SIZE,
m_device_ip);
674 char errbuf[PCAP_ERRBUF_SIZE];
678 string sFilePostfix =
"_";
680 "%04u-%02u-%02u_%02uh%02um%02us", (
unsigned int)parts.
year,
681 (
unsigned int)parts.
month, (
unsigned int)parts.
day,
682 (
unsigned int)parts.
hour, (
unsigned int)parts.
minute,
683 (
unsigned int)parts.
second);
684 const string sFileName =
689 m_pcap_out = pcap_open_dead(DLT_EN10MB, 65535);
691 m_pcap_out !=
nullptr,
"Error creating PCAP live capture handle");
694 "\n[CVelodyneScanner] Writing to PCAP file \"%s\"\n",
697 reinterpret_cast<pcap_t*>(
m_pcap_out), sFileName.c_str())) ==
701 "Error creating PCAP live dumper: '%s'", errbuf);
705 "Velodyne: Writing PCAP files requires building MRPT with libpcap " 714 struct pcap_pkthdr
header;
715 struct timeval currentTime;
716 gettimeofday(¤tTime,
nullptr);
717 std::vector<unsigned char> packetBuffer;
723 CObservationVelodyneScan::PACKET_SIZE + 42;
724 packetBuffer.resize(
header.caplen);
727 memcpy(&(packetBuffer[0]), LidarPacketHeader, 42);
729 &(packetBuffer[0]) + 42, (
uint8_t*)&out_data_pkt,
730 CObservationVelodyneScan::PACKET_SIZE);
738 CObservationVelodyneScan::POS_PACKET_SIZE + 42;
739 packetBuffer.resize(
header.caplen);
742 memcpy(&(packetBuffer[0]), PositionPacketHeader, 42);
744 &(packetBuffer[0]) + 42, (
uint8_t*)&out_pos_pkt,
745 CObservationVelodyneScan::POS_PACKET_SIZE);
755 #if MRPT_IS_BIG_ENDIAN 759 for (
int i = 0; i < CObservationVelodyneScan::BLOCKS_PER_PACKET; i++)
763 for (
int k = 0; k < CObservationVelodyneScan::SCANS_PER_BLOCK; k++)
801 const size_t expected_packet_size,
const std::string& filter_only_from_IP)
805 "Error: UDP socket is not open yet! Have you called initialize() " 808 unsigned long devip_addr = 0;
809 if (!filter_only_from_IP.empty())
810 devip_addr = inet_addr(filter_only_from_IP.c_str());
814 struct pollfd fds[1];
816 fds[0].events = POLLIN;
817 static const int POLL_TIMEOUT = 1;
819 sockaddr_in sender_address;
820 socklen_t sender_address_len =
sizeof(sender_address);
846 #if !defined(MRPT_OS_WINDOWS) 851 (fds, 1, POLL_TIMEOUT);
857 "Error in UDP poll():\n%s",
864 if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) ||
865 (fds[0].revents & POLLNVAL))
868 "Error in UDP poll() (seems Velodyne device error?)");
870 }
while ((fds[0].revents & POLLIN) == 0);
874 int nbytes = recvfrom(
875 hSocket, (
char*)&out_buffer[0], expected_packet_size, 0,
876 (sockaddr*)&sender_address, &sender_address_len);
882 else if ((
size_t)nbytes == expected_packet_size)
887 if (!filter_only_from_IP.empty() &&
888 sender_address.sin_addr.s_addr != devip_addr)
895 <<
"[CVelodyneScanner] Warning: incomplete Velodyne packet read: " 896 << nbytes <<
" bytes\n";
916 char errbuf[PCAP_ERRBUF_SIZE];
917 struct pcap_pkthdr*
header;
918 const u_char* pkt_data;
923 if ((
res = pcap_next_ex(
924 reinterpret_cast<pcap_t*>(
m_pcap), &
header, &pkt_data)) >= 0)
930 if (pcap_offline_filter(
936 <<
"[CVelodyneScanner] DEBUG: Filtering out packet #" 945 ntohs(*reinterpret_cast<const uint16_t*>(pkt_data + 0x24));
950 std::cout <<
"[CVelodyneScanner] DEBUG: Packet #" 952 <<
" in PCAP file is POSITION pkt.\n";
954 out_pos_buffer, pkt_data + 42,
955 CObservationVelodyneScan::POS_PACKET_SIZE);
962 std::cout <<
"[CVelodyneScanner] DEBUG: Packet #" 964 <<
" in PCAP file is DATA pkt.\n";
966 out_data_buffer, pkt_data + 42,
967 CObservationVelodyneScan::PACKET_SIZE);
973 std::cerr <<
"[CVelodyneScanner] ERROR: Packet " 975 <<
" in PCAP file passed the filter but does not " 976 "match expected UDP port numbers! Skipping it.\n";
984 "[CVelodyneScanner] Maybe the PCAP file is empty? Error %d " 985 "reading Velodyne packet: `%s`\n",
986 res, pcap_geterr(reinterpret_cast<pcap_t*>(
m_pcap)));
994 "[CVelodyneScanner] INFO: end of file reached -- done " 996 std::this_thread::sleep_for(250ms);
1004 "[CVelodyneScanner] INFO: end of file reached -- delaying " 1007 std::this_thread::sleep_for(
1008 std::chrono::duration<double, std::milli>(
1013 printf(
"[CVelodyneScanner] INFO: replaying Velodyne dump file.\n");
1016 pcap_close(reinterpret_cast<pcap_t*>(
m_pcap));
1026 "MRPT needs to be built against libpcap to enable this functionality")
1047 strRet =
"Strongest";
1100 !
m_device_ip.empty(),
"A device IP address must be specified first!");
1105 string post_err_str;
1112 extra_headers[
"Upgrade-Insecure-Requests"] =
"1";
1113 extra_headers[
"Content-Type"] =
"application/x-www-form-urlencoded";
1118 post_err_str, 80 ,
string(),
string(),
1119 &http_rep_code, &extra_headers, &out_headers);
1122 (http_rep_code == 200 || http_rep_code == 204);
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
void timestampToParts(TTimeStamp t, TTimeParts &p, bool localTime=false)
Gets the individual parts of a date/time (days, hours, minutes, seconds) - UTC time or local time...
content_t fields
Message content, accesible by individual fields.
std::map< model_t, TModelProperties > model_properties_list_t
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
unsigned __int16 uint16_t
#define MRPT_LOAD_HERE_CONFIG_VAR( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
For usage when passing a dynamic number of (numeric) arguments to a function, by name.
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows...
mrpt::system::TTimeStamp getAsTimestamp(const mrpt::system::TTimeStamp &date) const
Build an MRPT timestamp with the hour/minute/sec of this structure and the date from the given timest...
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
std::vector< uint8_t > vector_byte
raw_block_t blocks[BLOCKS_PER_PACKET]
double DEG2RAD(const double x)
Degrees to radians.
int platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
platform_socket_t m_hPositionSock
uint32_t gps_timestamp
us from top of hour
std::string m_sensorLabel
See CGenericSensor.
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
#define THROW_EXCEPTION(msg)
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
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::system::TTimeStamp buildTimestampFromParts(const mrpt::system::TTimeParts &p)
Builds a timestamp from the parts (Parts are in UTC)
static std::string getListKnownModels()
Return human-readable string: "`VLP16`,`XXX`,...".
std::string getLastSocketErrorStr()
Returns a description of the last Sockets error.
void close()
Close the UDP sockets set-up in initialize().
bool m_pcap_read_once
Default: false.
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Contains classes for various device interfaces.
void * m_pcap_bpf_program
opaque ptr: bpf_program*
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores ('_') or any other user-given char. ...
const Scalar * const_iterator
model_t
LIDAR model types.
int8_t validity_char
This will be: 'A'=OK or 'V'=void.
bool m_pcap_read_fast
(Default: false) If false, will use m_pcap_read_full_scan_delay_ms
void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string §ion)
See the class documentation at the top for expected parameters.
UTC_time UTCTime
The GPS sensor measured timestamp (in UTC time)
mrpt::system::TTimeStamp m_last_pos_packet_timestamp
char NMEA_GPRMC[72+234]
the full $GPRMC message, as received by Velodyne, terminated with "\r\n\0"
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)
ERRORCODE_HTTP
Possible returns from a HTTP request.
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig...
double m_pos_packets_min_period
Default: 0.5 seconds.
std::shared_ptr< CObservationVelodyneScan > Ptr
return_type_t m_lidar_return
bool setLidarOnOff(bool on)
Switches the LASER on/off (saves energy when not measuring) (via HTTP post interface).
A helper class that can convert an enum value into its textual representation, and viceversa...
nv_oem6_header_t header
Novatel frame: NV_OEM6_BESTPOS.
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.
The parts of a date/time (it's like the standard 'tm' but with fractions of seconds).
virtual ~CVelodyneScanner()
unsigned int m_pcap_read_count
number of pkts read from the file so far (for debugging)
std::string m_pcap_output_file
Default: "" (do not dump to an offline file)
static const model_properties_list_t & get()
Singleton access.
This namespace contains representation of robot actions and observations.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
bool m_pcap_verbose
Default: true Output PCAP Info msgs.
ERRORCODE_HTTP http_request(const string &http_method, const string &http_send_content, const string &url, vector_byte &out_content, string &out_errormsg, int port=80, const string &auth_user=string(), const string &auth_pass=string(), int *out_http_responsecode=nullptr, mrpt::utils::TParameters< string > *extra_headers=nullptr, mrpt::utils::TParameters< string > *out_headers=nullptr, int timeout_ms=1000)
Generic function for HTTP GET & POST methods.
platform_socket_t m_hDataSock
bool setLidarReturnType(return_type_t ret_type)
Changes among STRONGEST, LAST, DUAL return types (via HTTP post interface).
GLsizei const GLchar ** string
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
std::string m_pcap_input_file
Default: "" (do not operate from an offline file)
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
static bool parse_NMEA(const std::string &cmd_line, mrpt::obs::CObservationGPS &out_obs, const bool verbose=false)
Parses one line of NMEA data from a GPS receiver, and writes the recognized fields (if any) into an o...
ENUMTYPE read_enum(const std::string §ion, const std::string &name, const ENUMTYPE &defaultValue, bool failIfNotFound=false) const
Reads an "enum" value, where the value in the config file can be either a numerical value or the symb...
void appendObservation(const mrpt::utils::CSerializable::Ptr &obj)
Like appendObservations() but for just one observation.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Payload of one POSITION packet.
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
double second
Minute (0-59)
#define MRPT_COMPILE_TIME_ASSERT(f)
void * m_pcap_out
opaque ptr: "pcap_t*"
bool internal_send_http_post(const std::string &post_data)
mrpt::system::TTimeStamp getDateAsTimestamp() const
Build an MRPT timestamp with the year/month/day of this observation.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double m_pos_packets_timing_timeout
Default: 30 seconds.
laser_return_t laser_returns[SCANS_PER_BLOCK]
uint8_t minute
Hour (0-23)
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
One unit of data from the scanner (the payload of one UDP DATA packet)
bool empty() const
Returns true if no calibration has been loaded yet.
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
void * m_pcap
opaque ptr: "pcap_t*"
std::shared_ptr< CObservationGPS > Ptr
void doProcess()
This method will be invoked at a minimum rate of "process_rate" (Hz)
A set of useful routines for networking.
std::shared_ptr< T > make_aligned_shared(Args &&... args)
Creates a shared_ptr with 16-byte aligned memory.
uint16_t rotation
0-35999, divide by 100 to get degrees
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
void reverseBytesInPlace(bool &v_in_out)
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) ...
std::string m_device_ip
Default: "" (no IP-based filtering)
bool loadCalibrationFile(const std::string &velodyne_xml_calib_file_path)
Returns false on error.
#define ASSERTMSG_(f, __ERROR_MSG)
return_type_t
LIDAR return type.
mrpt::poses::CPose3D m_sensorPose
mrpt::system::TTimeStamp m_last_gps_rmc_age
mrpt::obs::CObservationVelodyneScan::Ptr m_rx_scan
In progress RX scan.
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 m_model
Default: "VLP16".
mrpt::obs::gnss::Message_NMEA_RMC m_last_gps_rmc
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
bool setLidarRPM(int rpm)
Changes Lidar RPM (valid range: 300-600) (via HTTP post interface).