#include <OctomapInterface.h>
Public Member Functions | |
void | addKeyFrame (KeyFrame::Ptr k) |
void | deletePoint (MapPoint::Ptr p) |
OctoMapInterface (ros::NodeHandle &nh) | |
void | updatePoint (MapPoint::Ptr p) |
void | updatePoints (std::set< MapPoint::Ptr > &p) |
virtual | ~OctoMapInterface () |
Protected Member Functions | |
void | publishPointUpdateFromQueue () |
Private Attributes | |
unsigned int | kfseq_ |
std::set< MapPoint::Ptr > | localUpdateQueue_ |
ros::NodeHandle & | nh_ |
unsigned int | pointseq_ |
ros::Publisher | pub_points_ |
ros::Publisher | pub_scan_ |
Definition at line 14 of file OctomapInterface.h.
Definition at line 14 of file OctomapInterface.cc.
OctoMapInterface::~OctoMapInterface | ( | ) | [virtual] |
Definition at line 23 of file OctomapInterface.cc.
void OctoMapInterface::addKeyFrame | ( | KeyFrame::Ptr | k | ) |
Definition at line 28 of file OctomapInterface.cc.
void OctoMapInterface::deletePoint | ( | MapPoint::Ptr | p | ) |
Definition at line 121 of file OctomapInterface.cc.
void OctoMapInterface::publishPointUpdateFromQueue | ( | ) | [protected] |
Definition at line 94 of file OctomapInterface.cc.
void OctoMapInterface::updatePoint | ( | MapPoint::Ptr | p | ) |
Definition at line 79 of file OctomapInterface.cc.
void OctoMapInterface::updatePoints | ( | std::set< MapPoint::Ptr > & | p | ) |
Definition at line 86 of file OctomapInterface.cc.
unsigned int OctoMapInterface::kfseq_ [private] |
Definition at line 23 of file OctomapInterface.h.
Definition at line 21 of file OctomapInterface.h.
ros::NodeHandle& OctoMapInterface::nh_ [private] |
Definition at line 17 of file OctomapInterface.h.
unsigned int OctoMapInterface::pointseq_ [private] |
Definition at line 24 of file OctomapInterface.h.
ros::Publisher OctoMapInterface::pub_points_ [private] |
Definition at line 19 of file OctomapInterface.h.
ros::Publisher OctoMapInterface::pub_scan_ [private] |
Definition at line 18 of file OctomapInterface.h.