Classes | |
class | AdaptiveOctTree |
Implements an OctTree with adaptive leaf splitting as a post process step. More... | |
class | Cell |
Base class for a rectangular 3D cell. More... | |
class | CellVector |
A spatial index represented as a grid map. More... | |
class | DepthCamera |
class | LazyGrid |
A spatial index represented as a grid map. More... | |
class | NDTCell |
implements a normal distibution cell More... | |
class | NDTHistogram |
class | NDTMap |
Implements an NDT based spatial index. More... | |
class | NDTMapHMT |
Implements an NDT based spatial index on top of an hybrid metric topological grid. More... | |
class | NDTOccupancyMap |
Implements an NDT based spatial index. More... | |
class | OctTree |
An Oct Tree data structure for storing 3D points. More... | |
class | SpatialIndex |
Base class for all spatial indexing structures. More... | |
Functions | |
bool | fromMessage (LazyGrid *&idx, NDTMap *&map, ndt_map::NDTMapMsg msg, std::string &frame_name) |
from message to NDTMap object | |
template<typename PointT > | |
double | geomDist (PointT p1, PointT p2) |
bool | toMessage (NDTMap *map, ndt_map::NDTMapMsg &msg, std::string frame_name) |
Message building fucntion. | |
bool | toOccupancyGrid (NDTMap *ndt_map, nav_msgs::OccupancyGrid &occ_grid, double resolution, std::string frame_id) |
builds ocuupancy grid message | |
template<typename PointT > | |
pcl::PointCloud< PointT > | transformPointCloud (Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &Tr, const pcl::PointCloud< PointT > &pc) |
template<typename PointT > | |
void | transformPointCloudInPlace (Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &Tr, pcl::PointCloud< PointT > &pc) |
This is an extension of NDTMap, which allows the update of occupancy on a cell level as well.
bool lslgeneric::fromMessage | ( | LazyGrid *& | idx, |
NDTMap *& | map, | ||
ndt_map::NDTMapMsg | msg, | ||
std::string & | frame_name | ||
) |
from message to NDTMap object
Converts ndt map message into a NDTMap object
[in,out] | idx | Pointer to lazy grid of the new NDTMap |
[out] | map | Pointer to NDTMap object |
[in] | msg | message to be converted |
[out] | frame_name | name of the coordination frame of the map |
Definition at line 73 of file ndt_conversions.h.
double lslgeneric::geomDist | ( | PointT | p1, |
PointT | p2 | ||
) |
Definition at line 33 of file pointcloud_utils.hpp.
bool lslgeneric::toMessage | ( | NDTMap * | map, |
ndt_map::NDTMapMsg & | msg, | ||
std::string | frame_name | ||
) |
Message building fucntion.
Converts an object of type NDTMap into NDTMapMsg message. Message contain all the data strored in the object.
[in] | map | Pointer to NDTMap object. |
[out] | msg | formated message |
[in] | frame_name | name of the coordination frame for the transformed map |
Definition at line 26 of file ndt_conversions.h.
bool lslgeneric::toOccupancyGrid | ( | NDTMap * | ndt_map, |
nav_msgs::OccupancyGrid & | occ_grid, | ||
double | resolution, | ||
std::string | frame_id | ||
) |
builds ocuupancy grid message
Builds 2D occupancy grid map based on 2D NDTMap
[in] | ndt_map | 2D ndt map to conversion |
[out] | occ_grid | 2D cost map |
[in] | resolution | desired resolution of occupancy map |
[in] | name | of cooridnation frame for the map (same as the NDT map has) |
Definition at line 107 of file ndt_conversions.h.
pcl::PointCloud< PointT > lslgeneric::transformPointCloud | ( | Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > & | Tr, |
const pcl::PointCloud< PointT > & | pc | ||
) |
Definition at line 5 of file pointcloud_utils.hpp.
void lslgeneric::transformPointCloudInPlace | ( | Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > & | Tr, |
pcl::PointCloud< PointT > & | pc | ||
) |
Definition at line 22 of file pointcloud_utils.hpp.