$search
#include <MapModel.h>
Public Member Functions | |
virtual double | getFloorHeight (const tf::Transform &pose) const =0 |
void | getHeightlist (double x, double y, double totalHeight, std::vector< double > &heights) |
boost::shared_ptr < octomap::OcTree > | getMap () const |
virtual void | initGlobal (Particles &particles, const Vector6d &initPose, const Vector6d &initNoise, UniformGeneratorT &rngUniform, NormalGeneratorT &rngNormal) |
virtual bool | isOccupied (octomap::OcTreeNode *node) const =0 |
virtual bool | isOccupied (const octomap::point3d &position) const |
MapModel (ros::NodeHandle *nh) | |
virtual void | verifyPoses (Particles &particles) |
virtual | ~MapModel () |
Protected Attributes | |
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 37 of file MapModel.h.
humanoid_localization::MapModel::MapModel | ( | ros::NodeHandle * | nh | ) |
Definition at line 27 of file MapModel.cpp.
humanoid_localization::MapModel::~MapModel | ( | ) | [virtual] |
Definition at line 43 of file MapModel.cpp.
virtual double humanoid_localization::MapModel::getFloorHeight | ( | const tf::Transform & | pose | ) | const [pure virtual] |
Implemented in humanoid_localization::DistanceMap, and humanoid_localization::OccupancyMap.
void humanoid_localization::MapModel::getHeightlist | ( | double | x, | |
double | y, | |||
double | totalHeight, | |||
std::vector< double > & | heights | |||
) |
Get a list of valid z values at a given xy-position
x | ||
y | ||
totalHeight | clearance of the robot required to be free | |
[out] | heights | list of valid heights, return by ref. |
Definition at line 173 of file MapModel.cpp.
boost::shared_ptr< octomap::OcTree > humanoid_localization::MapModel::getMap | ( | ) | const |
Definition at line 48 of file MapModel.cpp.
void humanoid_localization::MapModel::initGlobal | ( | Particles & | particles, | |
const Vector6d & | initPose, | |||
const Vector6d & | initNoise, | |||
UniformGeneratorT & | rngUniform, | |||
NormalGeneratorT & | rngNormal | |||
) | [virtual] |
Definition at line 133 of file MapModel.cpp.
virtual bool humanoid_localization::MapModel::isOccupied | ( | octomap::OcTreeNode * | node | ) | const [pure virtual] |
Implemented in humanoid_localization::DistanceMap, and humanoid_localization::OccupancyMap.
bool humanoid_localization::MapModel::isOccupied | ( | const octomap::point3d & | position | ) | const [virtual] |
Definition at line 194 of file MapModel.cpp.
void humanoid_localization::MapModel::verifyPoses | ( | Particles & | particles | ) | [virtual] |
Check if particles represent valid poses: Must be within map bounding box and not in an occupied area. Otherwise weight is minimized (=> die out at next resampling)
Definition at line 52 of file MapModel.cpp.
boost::shared_ptr<octomap::OcTree> humanoid_localization::MapModel::m_map [protected] |
Definition at line 74 of file MapModel.h.
double humanoid_localization::MapModel::m_motionMeanZ [protected] |
Definition at line 76 of file MapModel.h.
double humanoid_localization::MapModel::m_motionObstacleDist [protected] |
Definition at line 80 of file MapModel.h.
double humanoid_localization::MapModel::m_motionRangePitch [protected] |
Definition at line 79 of file MapModel.h.
double humanoid_localization::MapModel::m_motionRangeRoll [protected] |
Definition at line 78 of file MapModel.h.
double humanoid_localization::MapModel::m_motionRangeZ [protected] |
Definition at line 77 of file MapModel.h.