Public Member Functions | List of all members
toposens_pointcloud::Mapping Class Reference

Library for mapping/converting pcl::PointXYZINormal and toposens_msgs::TsPoint messages. More...

#include <mapping.h>

Public Member Functions

pcl::PointXYZINormal convertToXYZINormal (toposens_msgs::TsPoint i)
 Converts a point from a TsPoint message to a standard PCL point (PointXYZINormal). More...
 
void doTransform (pcl::PointXYZINormal &pt, Vector3f translation, Vector4f quaternion)
 
 Mapping ()=default
 

Detailed Description

Library for mapping/converting pcl::PointXYZINormal and toposens_msgs::TsPoint messages.

Definition at line 32 of file mapping.h.

Constructor & Destructor Documentation

◆ Mapping()

toposens_pointcloud::Mapping::Mapping ( )
default

Member Function Documentation

◆ convertToXYZINormal()

pcl::PointXYZINormal toposens_pointcloud::Mapping::convertToXYZINormal ( toposens_msgs::TsPoint  i)

Converts a point from a TsPoint message to a standard PCL point (PointXYZINormal).

The normal is generated as a vector pointing from the detected point to the sensor origin with unit length.

Parameters
iTsPoint to convert.
Returns
PointXYZINormal created from the given input.

Definition at line 42 of file mapping.cpp.

◆ doTransform()

void toposens_pointcloud::Mapping::doTransform ( pcl::PointXYZINormal &  pt,
Vector3f  translation,
Vector4f  quaternion 
)

Performs a point translation and rotation to the target frame. The input point is updated after transformation

Parameters
ptInput point that is to be transformed.
translationtranslation vector.
quaternionquaternion vector.

Definition at line 5 of file mapping.cpp.


The documentation for this class was generated from the following files:


toposens_pointcloud
Author(s): Adi Singh, Sebastian Dengler, Christopher Lang, Inshal Uddin
autogenerated on Mon Feb 28 2022 23:57:49