diff --git a/LidarCore/IO/Lidar/vtkLidarReader.cxx b/LidarCore/IO/Lidar/vtkLidarReader.cxx index 7c4f6c952e49ab43236f0a6ef75c391723c1803f..b4ed2002a8fe1873d7c0d47fa2c75acc6f77662b 100644 --- a/LidarCore/IO/Lidar/vtkLidarReader.cxx +++ b/LidarCore/IO/Lidar/vtkLidarReader.cxx @@ -31,8 +31,8 @@ #include "vtkPacketFileReader.h" #include "vtkPacketFileWriter.h" -#include <sstream> #include <algorithm> +#include <sstream> namespace { @@ -207,7 +207,7 @@ bool vtkLidarReader::BuildFramesIndex() { return false; } - const unsigned char* data = 0; + const unsigned char* data = nullptr; unsigned int dataLength = 0; // reset the frame catalog to build a new one @@ -291,7 +291,7 @@ bool vtkLidarReader::ReadFrame(size_t index, vtkPolyData* output) return 0; } - const unsigned char* data = 0; + const unsigned char* data = nullptr; unsigned int dataLength = 0; double timeSinceStart = 0; @@ -356,7 +356,7 @@ bool vtkLidarReader::Open(std::vector<int> ports, bool reassemble) filterPCAP += " port " + portsString; } - if (!this->Internals->Reader.Open(this->FileName, filterPCAP.c_str(), reassemble)) + if (!this->Internals->Reader.Open(this->FileName, filterPCAP, reassemble)) { vtkErrorMacro(<< "Failed to open packet file: " << this->FileName << "!\n" << this->Internals->Reader.GetLastError()); @@ -414,8 +414,8 @@ void vtkLidarReader::SaveFrames(unsigned int startFrame, return; } - pcap_pkthdr* header = 0; - const unsigned char* data = 0; + pcap_pkthdr* header = nullptr; + const unsigned char* data = nullptr; unsigned int dataLength = 0; unsigned int headerLength = 0; double networkTime = 0; @@ -453,7 +453,7 @@ int vtkLidarReader::RequestInformation(vtkInformation* vtkNotUsed(request), if (!this->LidarInterpreter->GetIsInitialized()) { this->LidarInterpreter->Initialize(); - this->Internals->NeedsReIndexing = true; + this->ResetFrameIndexes(); } if (this->Internals->NeedsReIndexing && !this->FileName.empty()) @@ -552,6 +552,12 @@ double vtkLidarReader::GetNetworkTimeToDataTime() return this->Internals->ComputeNetworkTimeToDataTime(); } +//----------------------------------------------------------------------------- +void vtkLidarReader::ResetFrameIndexes() +{ + this->Internals->NeedsReIndexing = true; +} + //----------------------------------------------------------------------------- void vtkLidarReader::SetFileName(const std::string& filename) { @@ -559,7 +565,7 @@ void vtkLidarReader::SetFileName(const std::string& filename) { this->FileName = filename; this->Modified(); - this->Internals->NeedsReIndexing = true; + this->ResetFrameIndexes(); } } @@ -570,7 +576,7 @@ void vtkLidarReader::SetLidarPort(int port) { this->LidarPort = port; this->Modified(); - this->Internals->NeedsReIndexing = true; + this->ResetFrameIndexes(); } } @@ -581,7 +587,7 @@ void vtkLidarReader::SetShowPartialFrames(bool show) { this->ShowPartialFrames = show; this->Modified(); - this->Internals->NeedsReIndexing = true; + this->ResetFrameIndexes(); } } diff --git a/LidarCore/IO/Lidar/vtkLidarReader.h b/LidarCore/IO/Lidar/vtkLidarReader.h index a797dc7d263a33b28a785ddb4cc7a1693b1d636b..4922d66caa8079f1b5b1d9541bc649f4e17c5506 100644 --- a/LidarCore/IO/Lidar/vtkLidarReader.h +++ b/LidarCore/IO/Lidar/vtkLidarReader.h @@ -151,6 +151,12 @@ protected: void Close(); ///@} + /** + * Reset the indexing of pcap frames on the next request information. + * (May add significant time overhead depending of pcap size) + */ + void ResetFrameIndexes(); + private: vtkLidarReader(const vtkLidarReader&) = delete; void operator=(const vtkLidarReader&) = delete;