Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • LidarView/lidarview-core
  • nick.laurenson/lidarview-core
  • aerezarang/lidarview-core
3 results
Show changes
Commits on Source (13)
Showing
with 1012 additions and 9 deletions
......@@ -19,8 +19,6 @@ variables:
# This will enable to run the pipeline with the updated module
TRIGGER_MODULE_PATH: '' # path of the module that trigger the pipeline relative to LidarView
TRIGGER_MODULE_SHA: '' # commit sha of the module that trigger the pipeline
TRIGGER_MODULE_REPOSITORY_PATH: '' # path of the remote of the module that trigger the pipeline
TRIGGER_MODULE_REMOTE_NAME: '' # name given to the remote of the module that trigger the pipeline
SB_BUILD_PREFIX: '' # use a unique value to have a custom SB dir for some branches and not rely on the generic one
# this may be usefull, when you make changes to the superbuild, and want to check
# that this change pass the CI pipeline, but in the mean time you don't want to
......@@ -40,8 +38,7 @@ default:
# so the next fetching and checkout will basically do nothing.
# "$git checkout " is a glorified no-op (no operation), see https://git-scm.com/docs/git-checkout#Documentation/git-checkout.txt-emgitcheckoutemltbranchgt
- cd $CI_PROJECT_DIR/$TRIGGER_MODULE_PATH
- git remote add $TRIGGER_MODULE_REMOTE_NAME $TRIGGER_MODULE_REPOSITORY_PATH
- git fetch $TRIGGER_MODULE_REMOTE_NAME
- git fetch
- git checkout $TRIGGER_MODULE_SHA
retry:
max: 2
......
add_subdirectory("ApplicationComponents/")
add_subdirectory("DatasetIOPlugin/")
add_subdirectory("LidarPlugin/")
add_subdirectory("LidarSlamPlugin/")
add_subdirectory("Python")
......
set(server_manager_xml
Kitti/data/LidarKITTIDataSetReader.xml
Kitti/data/LidarKITTIDataSetWriter.xml
Kitti/labels/KITTIObjectLabelsReader.xml
)
set(server_manager_sources
${CMAKE_CURRENT_SOURCE_DIR}/Kitti/data/vtkLidarKITTIDataSetReader.cxx
${CMAKE_CURRENT_SOURCE_DIR}/Kitti/data/vtkLidarKITTIDataSetWriter.cxx
${CMAKE_CURRENT_SOURCE_DIR}/Kitti/labels/vtkKITTIObjectLabelsReader.cxx
)
set(server_sources
)
ADD_PARAVIEW_PLUGIN(DatasetIOPlugin "1.0"
SERVER_MANAGER_XML ${server_manager_xml}
SERVER_MANAGER_SOURCES ${server_manager_sources}
SERVER_SOURCES ${server_sources})
target_link_libraries(DatasetIOPlugin PUBLIC LidarPlugin)
target_include_directories(DatasetIOPlugin
PUBLIC
Kitti/
Kitti/data
Kitti/labels
)
# install libraries
if (APPLE)
install(TARGETS DatasetIOPlugin
RUNTIME DESTINATION ${VV_INSTALL_RUNTIME_DIR}/${SOFTWARE_NAME}.app/Contents/MacOS/plugins
LIBRARY DESTINATION ${VV_INSTALL_RUNTIME_DIR}/${SOFTWARE_NAME}.app/Contents/MacOS/plugins
COMPONENT Runtime)
else()
install(TARGETS DatasetIOPlugin
RUNTIME DESTINATION ${VV_INSTALL_LIBRARY_DIR}/plugins
LIBRARY DESTINATION ${VV_INSTALL_LIBRARY_DIR}/plugins
COMPONENT Runtime)
endif()
......@@ -13,11 +13,26 @@
command="SetFileName"
number_of_elements="1">
<FileListDomain name="files"/>
<Hints>
<UseDirectoryName/>
</Hints>
<Documentation>
This property specifies the file name for the reader.
</Documentation>
</StringVectorProperty>
<IntVectorProperty
name="NumberOfFileNameDigits"
animateable="0"
command="SetNumberOfFileNameDigits"
number_of_elements="1"
default_values="10"
panel_visibility="advanced">
<Documentation>
Number of digits expected in the filenames
</Documentation>
</IntVectorProperty>
<DoubleVectorProperty
name="TimestepValues"
information_only="1" >
......
<ServerManagerConfiguration>
<ProxyGroup name="filters">
<!-- <WriterProxy -->
<SourceProxy
class="vtkLidarKITTIDataSetWriter"
name="LidarKITTIDataSetWriter">
<Documentation>
vtkLidarKITTIDataSetWriter generates binary files in the same format as
the Kitti dataset, containing the data of the input vtkPolyData.
</Documentation>
<InputProperty command="SetInputConnection"
name="PointCloud"
port_index="0">
<DataTypeDomain composite_data_supported="0"
name="input_type">
<DataType value="vtkPolyData" />
</DataTypeDomain>
</InputProperty>
<StringVectorProperty
command="SetFolderName"
name="FolderName"
number_of_elements="1">
<FileListDomain name="files"/>
<Hints>
<UseDirectoryName/>
</Hints>
<Documentation>
The name of the folder to write to.
</Documentation>
</StringVectorProperty>
<IntVectorProperty
name="NumberOfFileNameDigits"
animateable="0"
command="SetNumberOfFileNameDigits"
number_of_elements="1"
default_values="10"
panel_visibility="advanced">
<Documentation>
Number of digits expected in the filenames.
</Documentation>
</IntVectorProperty>
<StringVectorProperty name="SelectIntensityArray"
label="Intensity Array"
command="SetInputArrayToProcess"
number_of_elements="5"
element_types="0 0 0 0 2"
default_values_delimiter=";"
default_values="0;0;0;0;intensity"
animateable="0"
panel_visibility="advanced">
<ArrayListDomain name="array_list"
attribute_type="Scalars">
<RequiredProperties>
<Property name="PointCloud"
function="Input" />
</RequiredProperties>
</ArrayListDomain>
<!-- In versions of ParaView greater than 5.6, the FieldDataDomain element is not needed. -->
<FieldDataDomain name="field_list">
<RequiredProperties>
<Property name="PointCloud"
function="Input" />
</RequiredProperties>
</FieldDataDomain>
</StringVectorProperty>
<IntVectorProperty name="NormalizeIntensity"
command="SetNormalizeIntensity"
number_of_elements="1"
default_values="1"
panel_visibility="advanced">
<BooleanDomain name="bool"/>
<Documentation>
Enable Intensity normalization. If activated, the intensity in the output
files is rescaled from 0-InputIntensityMaxValue to 0-1 (in order to match
the value range from the Kitti dataset)
</Documentation>
</IntVectorProperty>
<DoubleVectorProperty name="InputIntensityMaxValue"
command="SetInputIntensityMaxValue"
number_of_elements="1"
default_values="255."
panel_visibility="advanced">
<Documentation>
Maximum value for the intensity value range. If NormalizeIntensity is activated,
the intensity in the output files is rescaled from 0-InputIntensityMaxValue to 0-1
(in order to match the value range from the Kitti dataset)
</Documentation>
<Hints>
<PropertyWidgetDecorator type="GenericDecorator"
mode="visibility"
property="NormalizeIntensity"
value="1" />
</Hints>
</DoubleVectorProperty>
<PropertyGroup label="File Parameters">
<Property name="FolderName" />
<Property name="NumberOfFileNameDigits" />
</PropertyGroup>
<PropertyGroup label="Intensity field Parameters">
<Property name="SelectIntensityArray" />
<Property name="NormalizeIntensity" />
<Property name="InputIntensityMaxValue" />
</PropertyGroup>
<!--
<Hints>
<Property name="Input"
show="0" />
<Property name="FolderName"
show="0" />
<WriterFactory extensions="bin"
file_description="KITTI binary point cloud file" />
</Hints>
</WriterProxy>
-->
</SourceProxy>
</ProxyGroup>
</ServerManagerConfiguration>
......@@ -115,7 +115,7 @@ vtkSmartPointer<vtkPolyData> vtkLidarKITTIDataSetReader::GetFrame(int frameNumbe
{
// produce path to the required .bin file
std::stringstream ss;
ss << std::setw(10) << std::setfill('0') << i;
ss << std::setw(this->NumberOfFileNameDigits) << std::setfill('0') << i;
std::string filename = this->GetFileName() + ss.str() + ".bin";
ifstream is;
......
......@@ -31,6 +31,8 @@ public:
vtkGetMacro(NumberOfFrames, int)
vtkSetMacro(NumberOfFileNameDigits, int)
//! Not implemented
void SetCalibrationFileName(const std::string& vtkNotUsed(filename)) override {notImpementedBody}
......@@ -71,6 +73,9 @@ private:
int NbrLaser = 64;
//! Number of digits expected in the filenames to read
int NumberOfFileNameDigits = 10;
vtkLidarKITTIDataSetReader(const vtkLidarKITTIDataSetReader&) = delete;
void operator=(const vtkLidarKITTIDataSetReader&) = delete;
};
......
#include "vtkLidarKITTIDataSetWriter.h"
#include <vtkInformationVector.h>
#include <vtkInformation.h>
#include <vtkPointData.h>
#include <vtkPolyData.h>
#include <vtkStreamingDemandDrivenPipeline.h>
#include <vector>
#include <fstream>
#include <sstream>
#include <boost/filesystem.hpp>
namespace
{
/*
* @brief WriteToBinaryFile writes the information to export in a binary file
* */
void WriteToBinaryFile(std::vector<float> &inData, const std::string &filename)
{
std::ofstream fout(filename, std::ios::out | std::ios::binary);
if (!fout.is_open())
{
std::cout << "Error: could not open file " << filename << " for writing." << std::endl;
}
else
{
fout.write(reinterpret_cast<char*>(&inData[0]), inData.size() * sizeof(float));
fout.close();
}
}
}
//-----------------------------------------------------------------------------
vtkStandardNewMacro(vtkLidarKITTIDataSetWriter)
//-----------------------------------------------------------------------------
vtkLidarKITTIDataSetWriter::vtkLidarKITTIDataSetWriter()
{
// TODO: set it as a writer
// this->SetNumberOfOutputPorts(0);
}
void vtkLidarKITTIDataSetWriter::UpdatePipelineIndex(vtkInformation * inInfo)
{
// Save current pipeline time step
this->PipelineTime = inInfo->Get(vtkStreamingDemandDrivenPipeline::UPDATE_TIME_STEP());
// TODO check best way to get the pipeline index
double *time_steps = inInfo->Get(vtkStreamingDemandDrivenPipeline::TIME_STEPS());
int nb_time_steps = inInfo->Length(vtkStreamingDemandDrivenPipeline::TIME_STEPS());
std::vector<double> TimeSteps(time_steps, time_steps + nb_time_steps);
// get the index corresponding to the requested pipeline time
// find the index of the first time step that is not less than pipeline time
this->PipelineIndex = std::distance(TimeSteps.begin(),
std::lower_bound(TimeSteps.begin(),
TimeSteps.end(),
this->PipelineTime));
// check if the previous index is closer
if (this->PipelineIndex > 0)
{
if (TimeSteps[this->PipelineIndex] - this->PipelineTime > this->PipelineTime - TimeSteps[this->PipelineIndex - 1])
{
this->PipelineIndex -= 1;
}
}
}
//-----------------------------------------------------------------------------
int vtkLidarKITTIDataSetWriter::RequestUpdateExtent(vtkInformation* vtkNotUsed(request),
vtkInformationVector** inputVector,
vtkInformationVector* vtkNotUsed(outputVector))
{
vtkInformation *inInfo = inputVector[0]->GetInformationObject(0);
this->UpdatePipelineIndex(inInfo);
return 1;
}
//-----------------------------------------------------------------------------
void vtkLidarKITTIDataSetWriter::SetFolderName(const std::string &foldername)
{
if (foldername.empty())
{
this->FolderName = "";
return;
}
if (!boost::filesystem::is_directory(foldername))
{
boost::filesystem::create_directory(foldername);
}
this->FolderName = foldername;
return;
}
std::vector<float> vtkLidarKITTIDataSetWriter::ParseCloudData(vtkSmartPointer<vtkPolyData> cloud, vtkDataArray* intensity)
{
std::vector<float> dataToWrite(4 * cloud->GetNumberOfPoints());
for (int pointIndex = 0; pointIndex < cloud->GetNumberOfPoints(); ++pointIndex)
{
double* pos = cloud->GetPoint(pointIndex);
float ptIntensity = static_cast<float>(intensity->GetTuple1(pointIndex));
if (this->NormalizeIntensity)
{
ptIntensity /= this->InputIntensityMaxValue;
}
dataToWrite[4 * pointIndex] = static_cast<float>(pos[0]);
dataToWrite[4 * pointIndex + 1] = static_cast<float>(pos[1]);
dataToWrite[4 * pointIndex + 2] = static_cast<float>(pos[2]);
dataToWrite[4 * pointIndex + 3] = ptIntensity;
}
return dataToWrite;
}
//-----------------------------------------------------------------------------
int vtkLidarKITTIDataSetWriter::RequestData(vtkInformation *, vtkInformationVector **inputVector, vtkInformationVector *outputVector)
{
if (this->FolderName.empty())
{
vtkErrorMacro("FolderName is empty. Please provide a folder name to write to.");
}
// Get IO
vtkPolyData* inCloud = vtkPolyData::GetData(inputVector[0], 0);
vtkPolyData* outCloud = vtkPolyData::GetData(outputVector, 0);
// Copy input over (TODO: remove this part when using as a writer)
outCloud->ShallowCopy(inCloud);
std::stringstream ss;
ss << std::setw(this->NumberOfFileNameDigits) << std::setfill('0') << this->PipelineIndex;
std::string frameFileName((boost::filesystem::path(this->FolderName) / (ss.str() + ".bin")).string());
// Get intensity array
vtkDataArray* intensity = this->GetInputArrayToProcess(0, inputVector);
if (!intensity)
{
vtkErrorMacro(<<"No Intensity array selected.")
return 1;
}
// Data for the .bin file are stored in a std::vector to make it easier to use
std::vector<float> dataToWrite = this->ParseCloudData(inCloud, intensity);
WriteToBinaryFile(dataToWrite, frameFileName);
return VTK_OK;
}
#ifndef VTKLIDARKITTIDATASETWRITER_H
#define VTKLIDARKITTIDATASETWRITER_H
#include <vtkPolyDataAlgorithm.h>
#include <vtkInformation.h>
#include <vtkInformationVector.h>
#include <vtkNew.h>
#include <string>
/*
* @brief vtkLidarKITTIDataSetWriter writes point clouds in KITTI Format
* The kitti format is:
* a binary file for each frame, containing a Nx4 float matrix (with N the number of points)
* the data is stored row-aligned (the first 4 values correspond to the first point)
* each point is represented by: x, y, z, reflectance
*
* The array to use as reflectance can be set in the "advanced" properties
* or by using "SetInputArrayToProcess"
*
* @warning In the kitti setup, x is pointing forward, and z upwards, make sure
* your data is oriented the same way before using this writer
**/
class VTK_EXPORT vtkLidarKITTIDataSetWriter : public vtkPolyDataAlgorithm
{
public:
static vtkLidarKITTIDataSetWriter* New();
vtkTypeMacro(vtkLidarKITTIDataSetWriter, vtkPolyDataAlgorithm);
// void PrintSelf(ostream& os, vtkIndent indent);
vtkGetMacro(FolderName, const std::string&)
void SetFolderName(const std::string&);
vtkGetMacro(NumberOfFileNameDigits, unsigned int)
vtkSetMacro(NumberOfFileNameDigits, unsigned int)
vtkGetMacro(NormalizeIntensity, bool)
vtkSetMacro(NormalizeIntensity, bool)
vtkGetMacro(InputIntensityMaxValue, float)
vtkSetMacro(InputIntensityMaxValue, float)
protected:
vtkLidarKITTIDataSetWriter();
~vtkLidarKITTIDataSetWriter() = default;
/*
* @brief UpdatePipelineIndex updates tHe pipeline index when requesting a new frame
* (used in RequestUpdateExtent)
**/
void UpdatePipelineIndex(vtkInformation *);
/*
* @brief ParseCloudData parses a point cloud vtkPolyData to retrieve information
* to export as a vector of floats containing (x, y, z, intensity) for each
* point.
* */
std::vector<float> ParseCloudData(vtkSmartPointer<vtkPolyData> cloud, vtkDataArray* intensity);
int RequestUpdateExtent(vtkInformation *, vtkInformationVector **, vtkInformationVector*);
int RequestData(vtkInformation *, vtkInformationVector **, vtkInformationVector *);
// Name of the folder to write the frames to
std::string FolderName;
// Internal variables for pipeline time and index (used to create a filename for each frame)
double PipelineTime;
unsigned int PipelineIndex;
// Desired number of digits in the output file names
unsigned int NumberOfFileNameDigits = 6;
// Do normalize intensity to 0-1. By default, data is normalized from 0-255 to 0-1
bool NormalizeIntensity = 1;
float InputIntensityMaxValue = 255.;
private:
vtkLidarKITTIDataSetWriter(const vtkLidarKITTIDataSetWriter&) = delete;
void operator=(const vtkLidarKITTIDataSetWriter&) = delete;
};
#endif // VTKLIDARKITTIDATASETWRITER_H
<ServerManagerConfiguration>
<ProxyGroup name="sources">
<SourceProxy name="KITTILabel" class="vtkKITTIObjectLabelsReader" label="KITTIObjectLabelsReader">
<Documentation
short_help="Parse KITTI 3D object detection labels"
long_help="Parse KITTI 3D object detection labels">
Parse KITTI 3D object detection labels
</Documentation>
<StringVectorProperty
name="FolderName"
animateable="0"
command="SetFolderName"
number_of_elements="1">
<FileListDomain name="files"/>
<Hints>
<UseDirectoryName/>
</Hints>
<Documentation>
This property specifies the labels folder for the reader.
</Documentation>
</StringVectorProperty>
<IntVectorProperty
name="NumberOfFileNameDigits"
animateable="0"
command="SetNumberOfFileNameDigits"
number_of_elements="1"
default_values="10"
panel_visibility="advanced">
<Documentation>
Number of digits expected in the filenames.
</Documentation>
</IntVectorProperty>
<IntVectorProperty
name="UseCalibration"
animateable="0"
command="SetUseCalibration"
number_of_elements="1"
default_values="0">
<BooleanDomain name="UseCalibration"/>
<Documentation>
Use calibration file to project boxes to the lidar coordinate system.
</Documentation>
</IntVectorProperty>
<StringVectorProperty
name="CalibFolderName"
animateable="0"
command="SetCalibFolderName"
number_of_elements="1">
<FileListDomain name="files"/>
<Hints>
<UseDirectoryName/>
<PropertyWidgetDecorator type="GenericDecorator"
mode="visibility"
property="UseCalibration"
value="1" />
</Hints>
<Documentation>
This property specifies the calibration files folder for the reader.
</Documentation>
</StringVectorProperty>
<DoubleVectorProperty
name="TimestepValues"
information_only="1" >
<TimeStepsInformationHelper/>
</DoubleVectorProperty>
<Hints>
<ReaderFactory extensions="txt"
file_description="Labels File"/>
</Hints>
</SourceProxy>
</ProxyGroup>
</ServerManagerConfiguration>
#include "vtkKITTIObjectLabelsReader.h"
#include <vtkMultiBlockDataSet.h>
#include <vtkObjectFactory.h>
#include <vtkInformationVector.h>
#include <vtkStreamingDemandDrivenPipeline.h>
#include <vtkInformation.h>
#include <vtkPolyData.h>
#include <vtkFieldData.h>
#include <vtkCubeSource.h>
#include <vtkStringArray.h>
#include <vtkIntArray.h>
#include <vtkFloatArray.h>
#include <vtkNew.h>
#include <vtkTransform.h>
#include <vtkTransformPolyDataFilter.h>
#include <Eigen/Geometry>
#include <sstream>
#include <fstream>
#include <string>
#include <vector>
#include <numeric>
# include <boost/filesystem.hpp>
#include "vtkHelper.h"
namespace {
typedef struct object {
std::string type;
float truncation;
int occlusion;
float alpha; // rad
std::vector<float> bbox2d; // xmin, ymin, xmax, ymax
float height;
float width;
float length;
std::vector<float> position; // x, y, z
float rotY; // rad
float score = 1;
} object_t;
/**
* @brief ParseObject parses a label line to create an `object` instance
*/
object_t ParseObject(const std::string &line){
std::stringstream ss(line);
object_t object;
std::string tmp_str;
std::getline(ss, object.type, ' ');
std::getline(ss, tmp_str, ' ');
object.truncation = std::stof(tmp_str);
std::getline(ss, tmp_str, ' ');
object.occlusion = std::stoi(tmp_str);
std::getline(ss, tmp_str, ' ');
object.alpha = std::stof(tmp_str);
for (unsigned int ii=0; ii<4; ii++)
{
std::getline(ss, tmp_str, ' ');
object.bbox2d.push_back(std::stof(tmp_str));
}
std::getline(ss, tmp_str, ' ');
object.height = std::stof(tmp_str);
std::getline(ss, tmp_str, ' ');
object.width = std::stof(tmp_str);
std::getline(ss, tmp_str, ' ');
object.length = std::stof(tmp_str);
for (unsigned int ii=0; ii<3; ii++)
{
std::getline(ss, tmp_str, ' ');
object.position.push_back(std::stof(tmp_str));
}
std::getline(ss, tmp_str, ' ');
object.rotY = std::stof(tmp_str);
if (std::getline(ss, tmp_str, ' '))
{
object.score = std::stof(tmp_str);
}
return object;
}
vtkSmartPointer<vtkPolyData> ApplyEigenIsometryToPolyData(const Eigen::Isometry3d &p, vtkSmartPointer<vtkPolyData> pd)
{
vtkNew<vtkMatrix4x4> m;
for (int i = 0; i < 4; ++i)
for (int j = 0; j < 4; ++j)
{
m->SetElement(i, j, p(i, j));
}
vtkNew<vtkTransform> tm;
tm->SetMatrix(m);
// transform the bounding box
vtkNew<vtkTransformPolyDataFilter> transformFilter;
transformFilter->SetInputData(0, pd);
transformFilter->SetTransform(tm);
transformFilter->Update();
return transformFilter->GetOutput();
}
/*
* @brief ConvertLabelToPolyData converts a object_t label (for example parsed
* with ParseObject) to a PolyData (a 3D box with field data containins its
* attributes)
**/
vtkSmartPointer<vtkPolyData> ConvertLabelToPolyData(const object_t object)
{
auto cubeSource = vtkSmartPointer<vtkCubeSource>::New();
// Generate 3d bbox centered on zero with the correct dimensions in order to
// be able to rotate the box around its center
cubeSource->SetCenter(0, 0, 0);
cubeSource->SetXLength(object.length);
cubeSource->SetYLength(object.height);
cubeSource->SetZLength(object.width);
cubeSource->Update();
vtkSmartPointer<vtkPolyData> bb = cubeSource->GetOutput();
// Construct the transform from object_t to move the bbox to its correct
// position and orientation
// In the ground truth, it looks like the vertical position is the one of the bottom of the object,
// differently from the other dimensions
Eigen::Translation3d ts(object.position[0], object.position[1] - object.height / 2, object.position[2]);
Eigen::AngleAxisd r(object.rotY, Eigen::Vector3d::UnitY()); // in rad
Eigen::Isometry3d p(ts * r);
bb = ApplyEigenIsometryToPolyData(p, bb);
// Add additionnal info as field data
auto typeData = createArray<vtkStringArray>("type", 1, 1);
typeData->SetValue(0, object.type);
bb->GetFieldData()->AddArray(typeData);
auto truncData = createArray<vtkFloatArray>("truncation", 1, 1);
truncData->SetValue(0, object.truncation);
bb->GetFieldData()->AddArray(truncData);
auto occlData = createArray<vtkIntArray>("occlusion", 1, 1);
occlData->SetValue(0, object.occlusion);
bb->GetFieldData()->AddArray(occlData);
auto scoreData = createArray<vtkFloatArray>("score", 1, 1);
scoreData->SetValue(0, object.score);
bb->GetFieldData()->AddArray(scoreData);
return bb;
}
/*
* @brief ParseCalibFile parses a calibration file and returns the corresponding lidar to camera transformation
* as an Eigen isometry
**/
Eigen::Isometry3d ParseCalibFile(const std::string &filename)
{
std::fstream f;
f.open(filename, std::ios::in);
// In order to project the detections from the rectified camera coordinate system to the lidar coordinate system, only R0_rect and Tr_velo_to_cam are required
// need to be extracted
std::vector<double> P2, R0_rect, Tr_velo_to_cam;
if (f.is_open()){
std::string line;
while(std::getline(f, line)){
std::stringstream ss(line);
std::string key;
std::getline(ss, key, ' ');
if (key == "R0_rect:")
{
while (std::getline(ss, key, ' '))
{
R0_rect.push_back(std::stod(key));
}
}
else if (key == "Tr_velo_to_cam:")
{
while (std::getline(ss, key, ' '))
{
Tr_velo_to_cam.push_back(std::stod(key));
}
}
}
}
else
{
std::cerr << "Could not open calibration file." << std::endl;
return Eigen::Isometry3d::Identity();
}
f.close();
// Transform Tr_velo_to_cam into a 4x4 matrix using by adding a 1 as the bottom-right
// element and 0's elsewhere.
assert(R0_rect.size == 9 && "R0_rect has an incorrect size, it should contain 3x3 elements");
std::vector<double>::iterator it = R0_rect.begin();
R0_rect.insert(it+3, 0);
it = R0_rect.begin();
R0_rect.insert(it+7, 0);
it = R0_rect.begin();
R0_rect.insert(it+11, 0);
R0_rect.insert(R0_rect.end(), { 0, 0, 0, 1});
Eigen::Matrix<double, 4, 4, Eigen::RowMajor> rotation(R0_rect.data());
// Transform Tr_velo_to_cam into a 4x4 matrix using by adding a 1 as the bottom-right
// element and 0's elsewhere.
assert(Tr_velo_to_cam.size == 12 && "Tr_velo_to_cam has an incorrect size, it should contain 3x4 elements");
Tr_velo_to_cam.insert(Tr_velo_to_cam.end(), { 0, 0, 0, 1});
Eigen::Matrix<double, 4, 4, Eigen::RowMajor> lidar2cam(Tr_velo_to_cam.data());
return Eigen::Isometry3d(rotation * lidar2cam);
}
}
//-----------------------------------------------------------------------------
vtkStandardNewMacro(vtkKITTIObjectLabelsReader)
//-----------------------------------------------------------------------------
vtkKITTIObjectLabelsReader::vtkKITTIObjectLabelsReader()
{
this->SetNumberOfInputPorts(0);
}
//----------------------------------------------------------------------------
void vtkKITTIObjectLabelsReader::SetFolderName(const std::string &path)
{
if (path == this->FolderName)
{
return;
}
if (!boost::filesystem::exists(path))
{
vtkErrorMacro("Folder not be found! Contrary to what the name of this function implies,"
" the input must be the folder containing all \".txt\" label files for a given sequence/dataset");
return;
}
// count number of frames inside the folder
this->NumberOfFrames = 0;
boost::filesystem::path folder(path);
boost::filesystem::directory_iterator it(folder);
while (it != boost::filesystem::directory_iterator())
{
this->NumberOfFrames++;
*it++;
}
this->FolderName = path + "/";
this->Modified();
}
//-----------------------------------------------------------------------------
void vtkKITTIObjectLabelsReader::SetCalibFolderName(const std::string &path)
{
if (path == this->CalibFolderName)
{
return;
}
if (!boost::filesystem::exists(path))
{
vtkErrorMacro("Folder not be found! Please provide a valid folder path to the calibration files for each frame");
return;
}
this->CalibFolderName = path + "/";
this->Modified();
}
//-----------------------------------------------------------------------------
void vtkKITTIObjectLabelsReader::GetLabelData(int frameIndex, vtkMultiBlockDataSet* output)
{
// produce path to the required .txt file
std::stringstream ss;
ss << std::setw(this->NumberOfFileNameDigits) << std::setfill('0') << frameIndex;
std::string filename = this->GetFolderName() + ss.str() + ".txt";
std::vector<object_t> objects;
// parse label file (1 line per object)
std::fstream f;
f.open(filename, std::ios::in);
if (f.is_open()){
std::string line;
while(std::getline(f, line)){
auto object = ParseObject(line);
if (object.type != "DontCare")
{
objects.push_back(object);
}
}
f.close();
}
Eigen::Isometry3d Lidar2Camera = Eigen::Isometry3d::Identity();
if (this->UseCalibration)
{
// produce path to the calibration .txt file
std::stringstream ss;
ss << std::setw(this->NumberOfFileNameDigits) << std::setfill('0') << frameIndex;
std::string calibFilename = this->GetCalibFolderName() + ss.str() + ".txt";
Lidar2Camera = ParseCalibFile(calibFilename);
}
// create a polydata for each object with a 3d bounding box and field values
unsigned int nbObjects = objects.size();
output->SetNumberOfBlocks(nbObjects);
for (unsigned int i=0; i < nbObjects; i++)
{
auto bb = ConvertLabelToPolyData(objects[i]);
if (this->UseCalibration)
{
Eigen::Isometry3d inv = Lidar2Camera.inverse();
bb = ApplyEigenIsometryToPolyData(inv, bb);
}
output->SetBlock(i, bb);
}
}
//-----------------------------------------------------------------------------
int vtkKITTIObjectLabelsReader::RequestData(vtkInformation *, vtkInformationVector **, vtkInformationVector *outputVector)
{
if (this->FolderName.empty())
{
vtkErrorMacro("Please specify a folder name")
return VTK_ERROR;
}
if (this->UseCalibration && this->CalibFolderName.empty())
{
vtkErrorMacro("Please specify a calibration folder path or untick 'Use Calibration'")
return VTK_ERROR;
}
auto *output = vtkMultiBlockDataSet::GetData(outputVector->GetInformationObject(0));
auto *info = outputVector->GetInformationObject(0);
int timestep = 0;
if (info->Has(vtkStreamingDemandDrivenPipeline::UPDATE_TIME_STEP()))
{
timestep = info->Get(vtkStreamingDemandDrivenPipeline::UPDATE_TIME_STEP());
}
// Because no timestep are present in the .bin file we consider that timestep = frame number.
if (timestep < 0 || timestep >= this->GetNumberOfFrames())
{
vtkErrorMacro("Cannot fulfill timestep request: " << timestep << ". There are only "
<< this->GetNumberOfFrames() << " datasets.");
return 0;
}
this->GetLabelData(timestep, output);
return 1;
}
//----------------------------------------------------------------------------
int vtkKITTIObjectLabelsReader::RequestInformation(vtkInformation* vtkNotUsed(request),
vtkInformationVector** vtkNotUsed(inputVector),
vtkInformationVector* outputVector)
{
vtkInformation* info = outputVector->GetInformationObject(0);
int numberOfTimesteps = this->NumberOfFrames;
std::vector<double> timesteps(numberOfTimesteps);
std::iota(timesteps.begin(), timesteps.end(), 0.);
if (numberOfTimesteps)
{
double timeRange[2] = { timesteps.front(), timesteps.back() };
info->Set(vtkStreamingDemandDrivenPipeline::TIME_STEPS(), &timesteps.front(), timesteps.size());
info->Set(vtkStreamingDemandDrivenPipeline::TIME_RANGE(), timeRange, 2);
}
else
{
info->Remove(vtkStreamingDemandDrivenPipeline::TIME_STEPS());
info->Remove(vtkStreamingDemandDrivenPipeline::TIME_RANGE());
}
return 1;
}
#ifndef VTKKITTIOBJECTLABELSREADER_H
#define VTKKITTIOBJECTLABELSREADER_H
#include <string>
#include <vtkMultiBlockDataSetAlgorithm.h>
/**
* @brief vtkKITTIObjectLabelsReader reads labels in the format adopted in
* KITTI 3D objects detection benchmark
* (cf. http://www.cvlibs.net/datasets/kitti/eval_object.php?obj_benchmark=3d)
*
* By default, the output boxes are in the camera coordinate system.
* If a calibration file is provided, the output boxes will be in the lidar coordinate system
*
* Implementation details:
* ----------------------
*
* Labels for each frame are stored in a text file "{frame_index}.txt"
* With 1 line per object.
*
* The fields for each objects are:
* [0] type ('Car', 'Pedestrian', ...)
* [1] truncation (truncated pixel ratio [0..1])
* [2] occlusion (0=visible, 1=partly occluded, 2=fully occluded, 3=unknown)
* [3] alpha (object observation angle [-pi..pi])
* [4..7] 2d bounding box in 0 based coordinated (left, top, right, bottom)
* [8] 3d bbox height
* [9] 3d bbox width
* [10] 3d bbox length (in meters)
* [11..13] 3d location (x, y, z) in camera coordinates
* [14] rotY rotation angle around Y axis in camera coordinates [-pi..pi]
* [15] score (only for results)
*
* (Source: https://github.com/kuixu/kitti_object_vis/blob/master/kitti_util.py)
*
* Calibration:
*
* The transformation from lidar coordinates to camera coodinates is:
* x = P2 * R0_rect * Tr_velo_to_cam * y
* "
* The Px matrices project a point in the rectified referenced camera coordinate to the camera_x image.
* camera_0 is the reference camera coordinate. R0_rect is the rectifying rotation for reference coordinate
* ( rectification makes images of multiple cameras lie on the same plan). Tr_velo_to_cam maps a point in
* point cloud coordinate to reference co-ordinate.
* "
* (source: https://medium.com/test-ttile/kitti-3d-object-detection-dataset-d78a762b5a4)
*
* TODO Calibration between camera and lidar from calibration file
*/
class VTK_EXPORT vtkKITTIObjectLabelsReader : public vtkMultiBlockDataSetAlgorithm
{
public:
static vtkKITTIObjectLabelsReader* New();
vtkTypeMacro(vtkKITTIObjectLabelsReader, vtkMultiBlockDataSetAlgorithm)
void GetLabelData(int frameIndex, vtkMultiBlockDataSet* output);
vtkGetMacro(FolderName, std::string)
void SetFolderName(const std::string& path);
vtkSetMacro(UseCalibration, bool)
vtkGetMacro(UseCalibration, bool)
vtkGetMacro(CalibFolderName, std::string)
void SetCalibFolderName(const std::string& path);
vtkGetMacro(NumberOfFrames, int)
vtkSetMacro(NumberOfFileNameDigits, int)
private:
vtkKITTIObjectLabelsReader();
int RequestData(vtkInformation* request,
vtkInformationVector** inputVector,
vtkInformationVector* outputVector) override;
int RequestInformation(vtkInformation*, vtkInformationVector**, vtkInformationVector*) override;
//! folder containing all the .bin files for a sequence
std::string FolderName = "";
//! Number of frame in this sequence
int NumberOfFrames = 0;
//! Number of digits expected in the filenames to read
int NumberOfFileNameDigits = 10;
//! Use calibration files to project the bboxes to the lidar coordinate system?
bool UseCalibration = false;
//! folder containing all the calibration files for a sequence
//! If not provided, the boxes are in the camera coordinate system
std::string CalibFolderName = "";
vtkKITTIObjectLabelsReader(const vtkKITTIObjectLabelsReader&) = delete;
void operator=(const vtkKITTIObjectLabelsReader&) = delete;
};
#endif // VTKKITTIOBJECTLABELSREADER_H
pv_plugin(DatasetIOPlugin
DESCRIPTION "Plugin to read/write standard point cloud datasets files"
)
......@@ -155,7 +155,6 @@ list(APPEND servermanager_sources
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/Common/vtkLidarReader.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/Common/vtkLidarStream.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/Common/vtkLidarPacketInterpreter.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/KITTIDataSet/vtkLidarKITTIDataSetReader.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/GPS-IMU/Applanix/vtkApplanixPositionReader.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/GPS-IMU/ArduPilotDataFlashLogReader/vtkArduPilotDataFlashLogReader.cxx
${CMAKE_CURRENT_SOURCE_DIR}/IO/GPS-IMU/Common/vtkPositionOrientationPacketInterpreter.cxx
......@@ -232,7 +231,6 @@ list(APPEND servermanager_xml
xml/Reader.xml
xml/Stream.xml
xml/Interpreter.xml
xml/LidarKITTIDataSetReader.xml
xml/ApplanixPositionReader.xml
xml/ArduPilotDataFlashLogReader.xml
xml/BoundingBoxReader.xml
......@@ -380,7 +378,6 @@ set(plugin_include_dirs
${CMAKE_CURRENT_SOURCE_DIR}/Common/NanoflannAdaptor
${CMAKE_CURRENT_SOURCE_DIR}/IO/Camera
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/Common
${CMAKE_CURRENT_SOURCE_DIR}/IO/Lidar/KITTIDataSet
${CMAKE_CURRENT_SOURCE_DIR}/IO/Camera
${CMAKE_CURRENT_SOURCE_DIR}/IO/GPS-IMU/Applanix
${CMAKE_CURRENT_SOURCE_DIR}/IO/GPS-IMU/ArduPilotDataFlashLogReader/
......
......@@ -162,7 +162,7 @@ int vtkBoundingBoxReader::RequestData(vtkInformation *, vtkInformationVector **,
vtkErrorMacro("In yaml file, no 'objects' key at level 0!")
output->SetNumberOfBlocks(objects.size());
for (int i = 0; i < objects.size(); ++i)
for (unsigned int i = 0; i < objects.size(); ++i)
{
try {
std::string type = objects[i]["selector"]["type"].as<std::string>();
......