#include <MapModel.h>

Public Member Functions | |
| DistanceMap (ros::NodeHandle *nh) | |
| virtual double | getFloorHeight (const tf::Transform &pose) const |
| virtual bool | isOccupied (octomap::OcTreeNode *node) const |
| virtual | ~DistanceMap () |
Public Member Functions inherited from humanoid_localization::MapModel | |
| void | getHeightlist (double x, double y, double totalHeight, std::vector< double > &heights) |
| boost::shared_ptr< octomap::OcTree > | getMap () const |
| virtual void | initGlobal (Particles &particles, double z, double roll, double pitch, const Vector6d &initNoise, UniformGeneratorT &rngUniform, NormalGeneratorT &rngNormal) |
| virtual bool | isOccupied (const octomap::point3d &position) const |
| MapModel (ros::NodeHandle *nh) | |
| virtual void | verifyPoses (Particles &particles) |
| virtual | ~MapModel () |
Additional Inherited Members | |
Protected Attributes inherited from humanoid_localization::MapModel | |
| boost::shared_ptr< octomap::OcTree > | m_map |
| double | m_motionMeanZ |
| double | m_motionObstacleDist |
| double | m_motionRangePitch |
| double | m_motionRangeRoll |
| double | m_motionRangeZ |
Definition at line 86 of file MapModel.h.
| humanoid_localization::DistanceMap::DistanceMap | ( | ros::NodeHandle * | nh | ) |
Definition at line 207 of file MapModel.cpp.
|
virtual |
Definition at line 236 of file MapModel.cpp.
|
virtual |
Implements humanoid_localization::MapModel.
Definition at line 247 of file MapModel.cpp.
|
virtual |
Implements humanoid_localization::MapModel.
Definition at line 240 of file MapModel.cpp.