Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
HectorMapTools::CoordinateTransformer< ConcreteScalar > Class Template Reference

#include <HectorMapTools.h>

Public Member Functions

 CoordinateTransformer ()
 
 CoordinateTransformer (const nav_msgs::OccupancyGridConstPtr map)
 
Eigen::Matrix< ConcreteScalar, 2, 1 > getC1Coords (const Eigen::Matrix< ConcreteScalar, 2, 1 > &mapCoords) const
 
ConcreteScalar getC1Scale (float c2_scale) const
 
Eigen::Matrix< ConcreteScalar, 2, 1 > getC2Coords (const Eigen::Matrix< ConcreteScalar, 2, 1 > &worldCoords) const
 
ConcreteScalar getC2Scale (float c1_scale) const
 
void setTransforms (const nav_msgs::OccupancyGrid &map)
 
void setTransforms (const nav_msgs::MapMetaData &meta)
 
void setTransformsBetweenCoordSystems (const Eigen::Matrix< ConcreteScalar, 2, 1 > &origoCS1, const Eigen::Matrix< ConcreteScalar, 2, 1 > &endCS1, const Eigen::Matrix< ConcreteScalar, 2, 1 > &origoCS2, const Eigen::Matrix< ConcreteScalar, 2, 1 > &endCS2)
 

Protected Member Functions

Eigen::Matrix< ConcreteScalar, 2, 1 > getLinearTransform (const Eigen::Matrix< ConcreteScalar, 2, 1 > &coordSystem1, const Eigen::Matrix< ConcreteScalar, 2, 1 > &coordSystem2)
 

Protected Attributes

ConcreteScalar inv_scale_
 
Eigen::Matrix< ConcreteScalar, 2, 1 > origo_
 
ConcreteScalar scale_
 

Detailed Description

template<typename ConcreteScalar>
class HectorMapTools::CoordinateTransformer< ConcreteScalar >

Definition at line 41 of file HectorMapTools.h.

Constructor & Destructor Documentation

template<typename ConcreteScalar>
HectorMapTools::CoordinateTransformer< ConcreteScalar >::CoordinateTransformer ( )
inline

Definition at line 44 of file HectorMapTools.h.

template<typename ConcreteScalar>
HectorMapTools::CoordinateTransformer< ConcreteScalar >::CoordinateTransformer ( const nav_msgs::OccupancyGridConstPtr  map)
inline

Definition at line 49 of file HectorMapTools.h.

Member Function Documentation

template<typename ConcreteScalar>
Eigen::Matrix<ConcreteScalar, 2, 1> HectorMapTools::CoordinateTransformer< ConcreteScalar >::getC1Coords ( const Eigen::Matrix< ConcreteScalar, 2, 1 > &  mapCoords) const
inline

Definition at line 84 of file HectorMapTools.h.

template<typename ConcreteScalar>
ConcreteScalar HectorMapTools::CoordinateTransformer< ConcreteScalar >::getC1Scale ( float  c2_scale) const
inline

Definition at line 94 of file HectorMapTools.h.

template<typename ConcreteScalar>
Eigen::Matrix<ConcreteScalar, 2, 1> HectorMapTools::CoordinateTransformer< ConcreteScalar >::getC2Coords ( const Eigen::Matrix< ConcreteScalar, 2, 1 > &  worldCoords) const
inline

Definition at line 89 of file HectorMapTools.h.

template<typename ConcreteScalar>
ConcreteScalar HectorMapTools::CoordinateTransformer< ConcreteScalar >::getC2Scale ( float  c1_scale) const
inline

Definition at line 99 of file HectorMapTools.h.

template<typename ConcreteScalar>
Eigen::Matrix<ConcreteScalar, 2, 1> HectorMapTools::CoordinateTransformer< ConcreteScalar >::getLinearTransform ( const Eigen::Matrix< ConcreteScalar, 2, 1 > &  coordSystem1,
const Eigen::Matrix< ConcreteScalar, 2, 1 > &  coordSystem2 
)
inlineprotected

Definition at line 106 of file HectorMapTools.h.

template<typename ConcreteScalar>
void HectorMapTools::CoordinateTransformer< ConcreteScalar >::setTransforms ( const nav_msgs::OccupancyGrid &  map)
inline

Definition at line 55 of file HectorMapTools.h.

template<typename ConcreteScalar>
void HectorMapTools::CoordinateTransformer< ConcreteScalar >::setTransforms ( const nav_msgs::MapMetaData &  meta)
inline

Definition at line 60 of file HectorMapTools.h.

template<typename ConcreteScalar>
void HectorMapTools::CoordinateTransformer< ConcreteScalar >::setTransformsBetweenCoordSystems ( const Eigen::Matrix< ConcreteScalar, 2, 1 > &  origoCS1,
const Eigen::Matrix< ConcreteScalar, 2, 1 > &  endCS1,
const Eigen::Matrix< ConcreteScalar, 2, 1 > &  origoCS2,
const Eigen::Matrix< ConcreteScalar, 2, 1 > &  endCS2 
)
inline

Definition at line 67 of file HectorMapTools.h.

Member Data Documentation

template<typename ConcreteScalar>
ConcreteScalar HectorMapTools::CoordinateTransformer< ConcreteScalar >::inv_scale_
protected

Definition at line 115 of file HectorMapTools.h.

template<typename ConcreteScalar>
Eigen::Matrix<ConcreteScalar, 2, 1> HectorMapTools::CoordinateTransformer< ConcreteScalar >::origo_
protected

Definition at line 113 of file HectorMapTools.h.

template<typename ConcreteScalar>
ConcreteScalar HectorMapTools::CoordinateTransformer< ConcreteScalar >::scale_
protected

Definition at line 114 of file HectorMapTools.h.


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


hector_map_tools
Author(s): Stefan Kohlbrecher
autogenerated on Sun Nov 3 2019 03:18:30