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
Showing
with 83 additions and 436 deletions
......@@ -5,11 +5,12 @@
#include <vtkDoubleArray.h>
#include <vtkPointData.h>
#include <vtkPolyData.h>
#include <vtkCustomTransformInterpolator.h>
#include <Eigen/Geometry>
#include "LidarCoreModule.h"
#include "vtkCustomTransformInterpolator.h"
#include "lvCommonCoreModule.h"
/**
* @brief The vtkTemporalTransforms class store some vtkTransform associated with time
......@@ -24,7 +25,7 @@
* It can be used to pass an vtkTransformInterpolator between 2 filter: a filter inherit from
* vtkAlgorithm, and it can only take a vtkDataObject as input/output.
*/
class LIDARCORE_EXPORT vtkTemporalTransforms : public vtkPolyData
class LVCOMMONCORE_EXPORT vtkTemporalTransforms : public vtkPolyData
{
public:
static vtkTemporalTransforms *New();
......
......@@ -15,9 +15,9 @@
#include <Eigen/Eigenvalues>
#include "vtkConversions.h"
#include "Common/vtkCustomTransformInterpolator.h"
#include "vtkCustomTransformInterpolator.h"
#include "vtkTimeCalibration.h"
#include "Common/statistics.h"
#include "statistics.h"
#include "eigenFFTCorrelation.h"
#include "interpolator1D.h"
......
......@@ -28,7 +28,7 @@
#include <Eigen/Dense>
#include <Eigen/Geometry>
#include "LidarCoreModule.h"
#include "lvCommonCoreModule.h"
#include "vtkTemporalTransforms.h"
enum class CorrelationStrategy
......@@ -59,7 +59,7 @@ std::string ToString(CorrelationStrategy strategy);
* 2) resample them
* 3) FFT then iFFT
**/
double LIDARCORE_EXPORT ComputeTimeShift(vtkSmartPointer<vtkTemporalTransforms> reference,
double LVCOMMONCORE_EXPORT ComputeTimeShift(vtkSmartPointer<vtkTemporalTransforms> reference,
vtkSmartPointer<vtkTemporalTransforms> aligned,
CorrelationStrategy correlationStrategy,
double time_window_width,
......@@ -76,7 +76,7 @@ void DemoAllTimesyncMethods(vtkSmartPointer<vtkTemporalTransforms> reference,
* If you rescale the "aligned" pose trajectory by the inverse of the scale
* returned, both pose trajectories will be on scale.
**/
double LIDARCORE_EXPORT ComputeScale(vtkSmartPointer<vtkTemporalTransforms> reference,
double LVCOMMONCORE_EXPORT ComputeScale(vtkSmartPointer<vtkTemporalTransforms> reference,
vtkSmartPointer<vtkTemporalTransforms> aligned,
CorrelationStrategy correlationStrategy,
double time_window_width);
......
//=========================================================================
//
// Copyright 2019 Kitware, Inc.
// Author: Guilbert Pierre (spguilbert@gmail.com)
// Data: 04-19-2018
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//=========================================================================
#ifndef KDTREE_PCL_ADAPTOR_H
#define KDTREE_PCL_ADAPTOR_H
// PCL
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
// BOOST
#include <boost/shared_ptr.hpp>
// NANOFLANN
#include <nanoflann.hpp>
#include <LidarPoint.h>
class KDTreePCLAdaptor
{
using Point = PointXYZTIId;
typedef typename nanoflann::metric_L2::template traits<double, KDTreePCLAdaptor>::distance_t metric_t;
typedef nanoflann::KDTreeSingleIndexAdaptor<metric_t, KDTreePCLAdaptor, 3, int> index_t;
public:
KDTreePCLAdaptor(pcl::PointCloud<Point>::Ptr cloud)
{
// copy the input cloud
this->Cloud = cloud;
// depth of the kdtree
int leaf_max_size = 25;
Index = new index_t(3, *this, nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size));
Index->buildIndex();
}
~KDTreePCLAdaptor()
{
delete Index;
}
/** Query for the \a num_closest closest points to a given point (entered as query_point[0:dim-1]).
* Note that this is a short-cut method for index->findNeighbors().
* The user can also call index->... methods as desired.
* \note nChecks_IGNORED is ignored but kept for compatibility with the original FLANN interface.
*/
inline void query(const Point& query_point, int knearest, int* out_indices, double* out_distances_sq/*, const int nChecks_IGNORED = 10*/) const
{
double pt[3] = {query_point.x, query_point.y, query_point.z};
nanoflann::KNNResultSet<double, int> resultSet(knearest);
resultSet.init(out_indices, out_distances_sq);
this->Index->findNeighbors(resultSet, pt, nanoflann::SearchParams());
}
const KDTreePCLAdaptor & derived() const
{
return *this;
}
KDTreePCLAdaptor& derived()
{
return *this;
}
// Must return the number of data points
inline int kdtree_get_point_count() const
{
return this->Cloud->size();
}
// Returns the dim'th component of the idx'th point in the class:
inline double kdtree_get_pt(const int idx, const int dim) const
{
if (dim == 0)
return this->Cloud->points[idx].x;
else if (dim == 1)
return this->Cloud->points[idx].y;
else
{
return this->Cloud->points[idx].z;
}
}
pcl::PointCloud<Point>::Ptr getInputCloud()
{
return this->Cloud;
}
// Optional bounding-box computation: return false to default to a standard bbox computation loop.
// Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again.
// Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds)
template <class BBOX>
bool kdtree_get_bbox(BBOX & /*bb*/) const
{
return false;
}
//! The kd-tree index for the user to call its methods as usual with any other FLANN index.
index_t* Index;
//! the inputed data
pcl::PointCloud<Point>::Ptr Cloud;
protected:
};
# endif // KDTREE_PCL_ADAPTOR_H
set(classes
vtkOpenCVConversions)
vtk_module_add_module(LidarView::CommonOpenCV
FORCE_STATIC
CLASSES ${classes})
NAME
LidarView::CommonOpenCV
LIBRARY_NAME
lvCommonOpenCV
CONDITION
LIDARVIEW_USE_OPENCV
DEPENDS
VTK::CommonCore
VTK::CommonDataModel
......@@ -18,7 +18,9 @@
//=========================================================================
// LOCAL
#include "Common/vtkOpenCVConversions.h"
#include "vtkOpenCVConversions.h"
// OPENCV
#include <opencv2/imgproc.hpp>
// VTK
......
......@@ -27,7 +27,7 @@
// OPENCV
#include <opencv2/core.hpp>
#include "LidarCoreModule.h"
#include "lvCommonOpenCVModule.h"
/**
* @brief CvImageToVtkImage converts a OpenCV BGR CV_8UC3 image to a vtkImageData
......@@ -42,7 +42,7 @@
* correct dimensions
* @return true iff the conversion succeeds
*/
bool LIDARCORE_EXPORT CvImageToVtkImage(const cv::Mat& inImg, vtkSmartPointer<vtkImageData> outImg);
bool LVCOMMONOPENCV_EXPORT CvImageToVtkImage(const cv::Mat& inImg, vtkSmartPointer<vtkImageData> outImg);
/**
* @brief CvImageToVtkImage converts a OpenCV BGR CV_8UC3 image to a vtkImageData
......@@ -52,7 +52,7 @@ bool LIDARCORE_EXPORT CvImageToVtkImage(const cv::Mat& inImg, vtkSmartPointer<vt
* for error on the colorspace). This is the type of cv::Mat you get when
* reading a JPEG/PNG image with colors.
*/
vtkSmartPointer<vtkImageData> LIDARCORE_EXPORT CvImageToVtkImage(const cv::Mat& inImg);
vtkSmartPointer<vtkImageData> LVCOMMONOPENCV_EXPORT CvImageToVtkImage(const cv::Mat& inImg);
/**
* @brief VtkImageToCVImage converts a 2D vtkImageData (depth == 1) with only
......@@ -64,7 +64,7 @@ vtkSmartPointer<vtkImageData> LIDARCORE_EXPORT CvImageToVtkImage(const cv::Mat&
* This is needed because vtkImages have their origin in the bottom left corner
* of the image, where as cv::Mat have their origin in the top left corner of the image.
*/
cv::Mat LIDARCORE_EXPORT VtkImageToCvImage(vtkSmartPointer<vtkImageData> inImg,
cv::Mat LVCOMMONOPENCV_EXPORT VtkImageToCvImage(vtkSmartPointer<vtkImageData> inImg,
bool flipHorizontally = true);
#endif // VTK_OPENCV_CONVERSIONS_H
set(classes
vtkPCLConversions)
vtk_module_add_module(LidarView::CommonPCL
FORCE_STATIC
CLASSES ${classes})
NAME
LidarView::CommonPCL
LIBRARY_NAME
lvCommonPCL
CONDITION
LIDARVIEW_USE_PCL
DEPENDS
pcl_common
VTK::CommonCore
PRIVATE_DEPENDS
pcl_io
VTK::CommonDataModel
VTK::CommonSystem
......@@ -32,13 +32,13 @@
#include <pcl/PointIndices.h>
#include <pcl/ModelCoefficients.h>
#include "LidarCoreModule.h"
#include "lvCommonPCLModule.h"
class vtkPolyData;
class vtkCellArray;
class vtkIntArray;
class LIDARCORE_EXPORT vtkPCLConversions : public vtkObject
class LVCOMMONPCL_EXPORT vtkPCLConversions : public vtkObject
{
public:
......
//=========================================================================
//
// Copyright 2019 Kitware, Inc.
// Author: Guilbert Pierre (spguilbert@gmail.com)
// Date: 05-29-2019
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//=========================================================================
// LOCAL
#include "RegistrationTools.h"
#include "vtkEigenTools.h"
#include "CeresCostFunctions.h"
// STD
#include <iostream>
// PCL
#include <pcl/kdtree/kdtree_flann.h>
// CERES
#include <ceres/ceres.h>
//-----------------------------------------------------------------------------
Eigen::Matrix4d ICPPointToPlaneRegistration(pcl::PointCloud<pcl::PointXYZ>::Ptr reference,
pcl::PointCloud<pcl::PointXYZ>::Ptr toAligned,
const Eigen::Matrix4d& H,
std::vector<bool>& pointUsed,
unsigned int maxICPIteration,
unsigned int maxLMIteration)
{
int requiredNearest = 9;
pointUsed = std::vector<bool>(toAligned->size(), false);
// Build kdtree to perform fast knearest neighbor
pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr kdtreeReference(new pcl::KdTreeFLANN<pcl::PointXYZ>());
pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr kdtreeToAligned(new pcl::KdTreeFLANN<pcl::PointXYZ>());
kdtreeReference->setInputCloud(reference);
kdtreeToAligned->setInputCloud(toAligned);
// Current pose estimation
Eigen::Matrix<double, 6, 1> DoF6Params;
DoF6Params.block(0, 0, 3, 1) = MatrixToRollPitchYaw(H.block(0, 0, 3, 3));
DoF6Params.block(3, 0, 3, 1) = H.block(0, 3, 3, 1);
std::vector<double> maxDist;
maxDist.push_back(5);
maxDist.push_back(4.5);
maxDist.push_back(4);
maxDist.push_back(3.5);
maxDist.push_back(3);
maxDist.push_back(2.5);
maxDist.push_back(2);
maxDist.push_back(1.5);
maxDist.push_back(1);
// loop over ICP iteration
for (unsigned int icpIteration = 0; icpIteration < maxICPIteration; ++icpIteration)
{
// Current estimated isometry
Eigen::Matrix3d R = RollPitchYawToMatrix(DoF6Params.block(0, 0, 3, 1));
Eigen::Vector3d T = DoF6Params.block(3, 0, 3, 1);
// Matches parameters
std::vector<Eigen::Matrix3d> SemiDist;
std::vector<Eigen::Vector3d> PointOnPlane, Points;
std::vector<double> scores;
// loop to create ICP matches
for (unsigned int pointIndex = 0; pointIndex < toAligned->size(); ++pointIndex)
{
// Get point and transform it
pcl::PointXYZ rawPclPoint = toAligned->points[pointIndex];
Eigen::Vector3d rawX(rawPclPoint.x, rawPclPoint.y, rawPclPoint.z);
Eigen::Vector3d X = R * rawX + T;
pcl::PointXYZ pclPoint(X(0), X(1), X(2));
Eigen::Matrix3d A;
Eigen::Vector3d P;
double planarity;
unsigned int maxIndex = std::min((unsigned int)(maxDist.size() - 1), icpIteration);
// Check that the current point is
// belonging itself on a plane
bool isOk = FindBestPlaneParameters(rawPclPoint, requiredNearest, maxDist[maxIndex], 0.35, kdtreeToAligned, A, P, planarity);
// Get matches params
isOk = isOk & FindBestPlaneParameters(pclPoint, requiredNearest, maxDist[maxIndex], 0.35, kdtreeReference, A, P, planarity);
if (!isOk)
{
pointUsed[pointIndex] = false;
continue;
}
PointOnPlane.push_back(P);
Points.push_back(rawX);
scores.push_back(planarity);
SemiDist.push_back(A);
pointUsed[pointIndex] = true;
}
//std::cout << "# Match: " << SemiDist.size() << " on " << toAligned->size() << std::endl;
//std::cout << "# rejection: " << (toAligned->size() - SemiDist.size()) << std::endl;
// We want to estimate our 6-DOF parameters using a non
// linear least square minimization. The non linear part
// comes from the Euler Angle parametrization of the rotation
// endomorphism SO(3). To minimize it we use CERES to perform
// the Levenberg-Marquardt algorithm.
ceres::Problem problem;
for (unsigned int k = 0; k < Points.size(); ++k)
{
ceres::CostFunction* cost_function = new ceres::AutoDiffCostFunction<CostFunctions::MahalanobisDistanceAffineIsometryResidual, 1, 6>(
new CostFunctions::MahalanobisDistanceAffineIsometryResidual(SemiDist[k], PointOnPlane[k],
Points[k], scores[k]));
problem.AddResidualBlock(cost_function, nullptr, DoF6Params.data());
}
ceres::Solver::Options options;
options.max_num_iterations = maxLMIteration;
options.linear_solver_type = ceres::DENSE_QR;
options.minimizer_progress_to_stdout = false;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);
}
Eigen::Matrix4d Href;
Href.block(0, 0, 3, 3) = RollPitchYawToMatrix(DoF6Params.block(0, 0, 3, 1));
Href.block(0, 3, 3, 1) = DoF6Params.block(3, 0, 3, 1);
return Href;
}
//-----------------------------------------------------------------------------
bool FindBestPlaneParameters(pcl::PointXYZ query, unsigned int knearest, double maxDist,
double minPlanarity, pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr kdtree,
Eigen::Matrix3d& SemiDist, Eigen::Vector3d& P, double& planarity)
{
// Get nearest neighbor of the current point transformed
// using the current isometry estimation within the reference
// pointcloud
std::vector<float> neighSquaredDist;
std::vector<int> neighIndex;
kdtree->nearestKSearch(query, knearest, neighIndex, neighSquaredDist);
// Invalid the query if the neighbor is too far
if (std::sqrt(neighSquaredDist[neighSquaredDist.size() - 1]) > maxDist)
{
return false;
}
// Compute best plane that approximate the neighborhood
Eigen::MatrixXd data(knearest, 3);
for (unsigned int k = 0; k < knearest; k++)
{
pcl::PointXYZ pt = kdtree->getInputCloud()->points[neighIndex[k]];
data.row(k) << pt.x, pt.y, pt.z;
}
P = data.colwise().mean();
Eigen::MatrixXd centered = data.rowwise() - P.transpose();
Eigen::Matrix3d Sigma = centered.transpose() * centered;
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> eig(Sigma);
// Eigenvalues
Eigen::VectorXd D = eig.eigenvalues();
Eigen::Vector3d n = eig.eigenvectors().col(0);
SemiDist = n * n.transpose();
planarity = (D(1) - D(0)) / D(2);
if (planarity < minPlanarity)
{
return false;
}
return true;
}
//-----------------------------------------------------------------------------
void ComputeSimilitude(const std::vector<Eigen::Vector3d>& X,
const std::vector<Eigen::Vector3d>& Y,
Eigen::Matrix<double, 9, 1>& W)
{
ceres::Problem problem;
for (unsigned int k = 0; k < X.size(); ++k)
{
ceres::CostFunction* cost_function = new ceres::AutoDiffCostFunction<CostFunctions::SimilitudeResidual, 1, 9>(
new CostFunctions::SimilitudeResidual(X[k], Y[k]));
problem.AddResidualBlock(cost_function, nullptr, W.data());
}
ceres::Solver::Options options;
options.max_num_iterations = 250;
options.linear_solver_type = ceres::DENSE_QR;
options.minimizer_progress_to_stdout = false;
ceres::Solver::Summary summary;
ceres::Solve(options, &problem, &summary);
}
//=========================================================================
//
// Copyright 2019 Kitware, Inc.
// Author: Guilbert Pierre (spguilbert@gmail.com)
// Date: 05-29-2019
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//=========================================================================
// PCL
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/kdtree/kdtree_flann.h>
// EIGEN
#include <Eigen/Dense>
/**
* @brief ICPPointToPlaneRegistration From a given source pointcloud and a first estimation
* pose of this pointcloud; refine the pose estimation by registering the
* source point cloud on the reference pointcloud
*
* The registration will be performed using an ICP algorithm with a
* point to surface distance
*
* @param reference reference point cloud
* @param toAligned point cloud we want to align on the reference
* @param H initial guess of the pose of toAligned point cloud
* @param maxICPIteration maximum number of ICP iteration
* @param maxLMIteration maximum number of Levenberg-Marquardt iteration
* per ICP iteration
*/
Eigen::Matrix4d ICPPointToPlaneRegistration(pcl::PointCloud<pcl::PointXYZ>::Ptr reference,
pcl::PointCloud<pcl::PointXYZ>::Ptr toAligned,
const Eigen::Matrix4d& H,
std::vector<bool>& pointUsed,
unsigned int maxICPIteration = 4,
unsigned int maxLMIteration = 15);
/**
* @brief FindBestPlaneParameters Compute parameters of the plane that best
* approximate the neighborhood of a point according to the squared
* euclidean distance.
*
* The parameters are provided as a symmetric matrix and a point belonging
* to the plane so that:
* d(X, Plane) = (X - P).t * SemiDist * (X - P)
*
* @param query point whose neighborhood must be approximated
* @param knearest number of point selected in query neighborhood
* @param maxDist maximum distance allowed for a point to be consider in the neighborhood
* @param minPlanarity minimum planarity score to consider the neighborhood as a plane
* @param kdtree kdtree used to extract knearest points
* @param SemiDist symmetric matrix encoding the point-to-plane distance
* @param P point belonging to the plane
* @param planarity of the neighborhood
*/
bool FindBestPlaneParameters(pcl::PointXYZ query, unsigned int knearest, double maxDist,
double minPlanarity, pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr kdtree,
Eigen::Matrix3d& SemiDist, Eigen::Vector3d& P, double& planarity);
/**
* @brief ComputeSimilitude Compute the similitude that matches Xi to Yi
*
* @param X set of input points
* @param Y set of output points
* @param W parameters of the similitude [a0, a1, a2, t0, t1, t2, s0, s1, s2]
* with ai being euler-angle SO(3) manifold parametrization. We chose the
* following Euler-Angle mapping between R^3 and SO(3)
* R(rx, ry, rz) = Rz(rz) * Ry(ry) * Rx(rx)
* ti being the translation and si the scale factors
*/
void ComputeSimilitude(const std::vector<Eigen::Vector3d>& X,
const std::vector<Eigen::Vector3d>& Y,
Eigen::Matrix<double, 9, 1>& W);
set(sources
CameraCalibration.cxx)
set(headers
CameraCalibration.h)
set(classes
vtkCalibrationFromPoses
vtkCarGeometricCalibration
vtkTemporalTransformsRemapper)
vtk_module_add_module(LidarView::FiltersCalibration
FORCE_STATIC
SOURCES ${sources}
CLASSES ${classes}
HEADERS ${headers})
paraview_add_server_manager_xmls(
XMLS
Resources/CalibrationFromPoses.xml
Resources/TemporalTransformsRemapper.xml)
......@@ -27,7 +27,7 @@
// EIGEN
#include <Eigen/Dense>
#include "LidarCoreModule.h"
#include "lvFiltersCalibrationModule.h"
/**
* @brief LoadMatchesFromCSV Load 2D - 3D matches from a .csv file. These matches are
......@@ -39,7 +39,7 @@
* @param X 3D keypoints associated to the 2D keypoints
* @param x 2D keypoints associated to the 3D keypoints
*/
LIDARCORE_EXPORT void LoadMatchesFromCSV(std::string filename, std::vector<Eigen::Vector3d>& X, std::vector<Eigen::Vector2d>& x);
LVFILTERSCALIBRATION_EXPORT void LoadMatchesFromCSV(std::string filename, std::vector<Eigen::Vector3d>& X, std::vector<Eigen::Vector2d>& x);
/**
* @brief LinearPinholeCalibration Compute the pinhole camera model parameters
......@@ -57,7 +57,7 @@ LIDARCORE_EXPORT void LoadMatchesFromCSV(std::string filename, std::vector<Eigen
* @param x 2D keypoints associated to the 3D keypoints
* @param P camera projection matrix estimated
*/
LIDARCORE_EXPORT double LinearPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x, Eigen::Matrix<double, 3, 4>& P);
LVFILTERSCALIBRATION_EXPORT double LinearPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x, Eigen::Matrix<double, 3, 4>& P);
/**
* @brief NonLinearPinholeCalibration Compute the pinhole camera model parameters
......@@ -74,7 +74,7 @@ LIDARCORE_EXPORT double LinearPinholeCalibration(const std::vector<Eigen::Vector
* @param x 2D keypoints associated to the 3D keypoints
* @param P W pinhole camera model parameters estimated
*/
LIDARCORE_EXPORT double NonLinearPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x, Eigen::Matrix<double, 11, 1>& W);
LVFILTERSCALIBRATION_EXPORT double NonLinearPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x, Eigen::Matrix<double, 11, 1>& W);
/**
* @brief NonLinearFisheyeCalibration Compute the fisheye camera model parameters
......@@ -91,7 +91,7 @@ LIDARCORE_EXPORT double NonLinearPinholeCalibration(const std::vector<Eigen::Vec
* @param x 2D keypoints associated to the 3D keypoints
* @param P W fisheye camera model parameters estimated
*/
LIDARCORE_EXPORT double NonLinearFisheyeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x,
LVFILTERSCALIBRATION_EXPORT double NonLinearFisheyeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x,
Eigen::Matrix<double, 15, 1>& W, unsigned int it = 1000);
/**
......@@ -117,7 +117,7 @@ LIDARCORE_EXPORT double NonLinearFisheyeCalibration(const std::vector<Eigen::Vec
* reprojection error
* @param shouldOptimizeParam Indicates which parameters should be optimized
*/
LIDARCORE_EXPORT double BrownConradyPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x,
LVFILTERSCALIBRATION_EXPORT double BrownConradyPinholeCalibration(const std::vector<Eigen::Vector3d>& X, const std::vector<Eigen::Vector2d>& x,
Eigen::Matrix<double, 17, 1>& W, unsigned int it = 1000,
double initLossScale = 5.0, double finalLossScale = 0.60,
const std::vector<bool>& shouldOptimizeParam = (std::vector<bool>(0)));
......@@ -131,7 +131,7 @@ LIDARCORE_EXPORT double BrownConradyPinholeCalibration(const std::vector<Eigen::
* @param R orientation of the camera (extrinsic parameters)
* @param T position of the camera (extrinsic parameters)
*/
LIDARCORE_EXPORT void CalibrationMatrixDecomposition(const Eigen::Matrix<double, 3, 4>& P, Eigen::Matrix3d& K, Eigen::Matrix3d& R, Eigen::Vector3d& T);
LVFILTERSCALIBRATION_EXPORT void CalibrationMatrixDecomposition(const Eigen::Matrix<double, 3, 4>& P, Eigen::Matrix3d& K, Eigen::Matrix3d& R, Eigen::Vector3d& T);
/**
* @brief CalibrationMatrixDecomposition Decompose the pinhole camera model
......@@ -142,7 +142,7 @@ LIDARCORE_EXPORT void CalibrationMatrixDecomposition(const Eigen::Matrix<double,
* @param T position of the camera (extrinsic parameters)
* @param W pinhole model parameters
*/
LIDARCORE_EXPORT void GetParametersFromMatrix(const Eigen::Matrix3d& K, const Eigen::Matrix3d& R, const Eigen::Vector3d& T, Eigen::Matrix<double, 11, 1>& W);
LVFILTERSCALIBRATION_EXPORT void GetParametersFromMatrix(const Eigen::Matrix3d& K, const Eigen::Matrix3d& R, const Eigen::Vector3d& T, Eigen::Matrix<double, 11, 1>& W);
/**
* @brief GetMatrixFromParameters Compose the pinhole camera model
......@@ -151,7 +151,7 @@ LIDARCORE_EXPORT void GetParametersFromMatrix(const Eigen::Matrix3d& K, const Ei
* @param W pinhole model parameters
* @param P camera projection matrix
*/
LIDARCORE_EXPORT void GetMatrixFromParameters(const Eigen::Matrix<double, 11, 1>& W, Eigen::Matrix<double, 3, 4>& P);
LVFILTERSCALIBRATION_EXPORT void GetMatrixFromParameters(const Eigen::Matrix<double, 11, 1>& W, Eigen::Matrix<double, 3, 4>& P);
Eigen::Matrix<double, 3, 4> GetMatrixFromParameters(const Eigen::Matrix<double, 11, 1>& W);
/**
......@@ -163,7 +163,7 @@ Eigen::Matrix<double, 3, 4> GetMatrixFromParameters(const Eigen::Matrix<double,
* @param filename file containing the matches
* @param activatedParams Indicates which params should be optimized
*/
LIDARCORE_EXPORT Eigen::VectorXd FullCalibrationPipelineFromMatches(std::string filename,
LVFILTERSCALIBRATION_EXPORT Eigen::VectorXd FullCalibrationPipelineFromMatches(std::string filename,
const std::vector<bool>& activatedParams = (std::vector<bool>(0)));
#endif // CAMERA_CALIBRATION_H