Functions
icp_2d Namespace Reference

Functions

double alignICP (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform, size_t max_iterations=10, double min_delta_rmsd=0.000001)
 Perform Iterative Closest Point (ICP) algorithm to align two point clouds in a two dimensional plane. More...
 
bool alignPCA (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform)
 Perform PCA algorithm to align two point clouds in a two dimensional plane. More...
 
bool alignSVD (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target, geometry_msgs::Transform &transform)
 Perform SVD optimization to align two point clouds in a two dimensional plane. More...
 
bool computeCorrespondences (const std::vector< geometry_msgs::Point > &source, const std::vector< geometry_msgs::Point > &target, std::vector< geometry_msgs::Point > &correspondences)
 
geometry_msgs::Point getCentroid (const std::vector< geometry_msgs::Point > points)
 Get the centroid of a set of points. More...
 
double getRMSD (const std::vector< geometry_msgs::Point > source, const std::vector< geometry_msgs::Point > target)
 
double thetaFromQuaternion (const geometry_msgs::Quaternion &q)
 Get the 2d rotation from a quaternion. More...
 
std::vector< geometry_msgs::Pointtransform (const std::vector< geometry_msgs::Point > &points, double x, double y, double theta)
 Transform a vector of points in 2d. More...
 

Function Documentation

double icp_2d::alignICP ( const std::vector< geometry_msgs::Point source,
const std::vector< geometry_msgs::Point target,
geometry_msgs::Transform &  transform,
size_t  max_iterations = 10,
double  min_delta_rmsd = 0.000001 
)

Perform Iterative Closest Point (ICP) algorithm to align two point clouds in a two dimensional plane.

Parameters
sourceThe cloud to be aligned with target.
targetThe cloud to be aligned to.
transformThe transformation to align source with target.
Returns
Fitness score, negative if error.

Definition at line 289 of file icp_2d.cpp.

bool icp_2d::alignPCA ( const std::vector< geometry_msgs::Point source,
const std::vector< geometry_msgs::Point target,
geometry_msgs::Transform &  transform 
)

Perform PCA algorithm to align two point clouds in a two dimensional plane.

Parameters
sourceThe cloud to be aligned with target.
targetThe cloud to be aligned to.
transformThe transformation to align source with target.
Returns
True if successful, false otherwise.

Definition at line 119 of file icp_2d.cpp.

bool icp_2d::alignSVD ( const std::vector< geometry_msgs::Point source,
const std::vector< geometry_msgs::Point target,
geometry_msgs::Transform &  transform 
)

Perform SVD optimization to align two point clouds in a two dimensional plane.

Parameters
sourceThe cloud to be aligned with target.
targetThe cloud to be aligned to.
transformThe transformation to align source with target.
Returns
True if successful, false otherwise.

Definition at line 197 of file icp_2d.cpp.

bool icp_2d::computeCorrespondences ( const std::vector< geometry_msgs::Point > &  source,
const std::vector< geometry_msgs::Point > &  target,
std::vector< geometry_msgs::Point > &  correspondences 
)

Definition at line 82 of file icp_2d.cpp.

geometry_msgs::Point icp_2d::getCentroid ( const std::vector< geometry_msgs::Point points)

Get the centroid of a set of points.

Parameters
pointsThe points to find centroid of.

Definition at line 66 of file icp_2d.cpp.

double icp_2d::getRMSD ( const std::vector< geometry_msgs::Point source,
const std::vector< geometry_msgs::Point target 
)

Definition at line 262 of file icp_2d.cpp.

double icp_2d::thetaFromQuaternion ( const geometry_msgs::Quaternion &  q)

Get the 2d rotation from a quaternion.

Parameters
qThe quaternion to convert.
Returns
The orientation in 2d.

Note: will throw if q.x or q.y is not equal to zero

Definition at line 28 of file icp_2d.cpp.

std::vector< geometry_msgs::Point > icp_2d::transform ( const std::vector< geometry_msgs::Point > &  points,
double  x,
double  y,
double  theta 
)

Transform a vector of points in 2d.

Parameters
pointsThe points to transform.
xThe x offset to transform, in the current frame of points.
yThe y offset to transform, in the current frame of points.
thetaThe rotation, in the current frame of points.
Returns
The transformed points.

Definition at line 41 of file icp_2d.cpp.



caster_app
Author(s): Ye Tian
autogenerated on Wed Dec 18 2019 03:34:44