Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
srs_env_model::COctoMapPlugin Class Reference

#include <octomap_plugin.h>

Inheritance diagram for srs_env_model::COctoMapPlugin:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::signal< void(SMapWithParameters &) > tSigOnNewData
 On new octomap data signal.

Public Member Functions

 COctoMapPlugin (const std::string &name)
 Constructor.
 COctoMapPlugin (const std::string &name, const std::string &filename)
 Constructor - load data from the file.
void crawl (const ros::Time &currentTime)
 Crawl octomap.
double getResolution ()
 Get octomap resolution.
tSigOnNewDatagetSigOnNewData ()
unsigned getSize ()
 Get current octomap size.
unsigned getTreeDepth ()
 Get current tree depth.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
void insertCloud (tPointCloud::ConstPtr cloud)
 Insert pointcloud.
virtual void pause (bool bPause, ros::NodeHandle &node_handle)
 Pause/resume plugin. All publishers and subscribers are disconnected on pause.
void reset (bool clearLoaded=true)
 Reset octomap.
virtual ~COctoMapPlugin ()
 Destructor.

Protected Member Functions

bool addCubeCB (srs_env_model::AddCube::Request &req, srs_env_model::AddCube::Response &res)
 Remove cube as a service - callback.
void addCubeGizmo (const geometry_msgs::Pose &pose, const geometry_msgs::Point &size)
 For debugging purpouses - add cubical interactive marker to the scene.
long int doObjectTesting (CTestingObjectBase *object)
 Do octomap testing by object.
void fillMapParameters (const ros::Time &time)
 Fill map parameters.
void filterCloud (tPointCloudConstPtr &cloud)
 Use pointcloud to raycast filter map.
bool getTreeDepthCB (srs_env_model::GetTreeDepth::Request &req, srs_env_model::GetTreeDepth::Response &res)
 Get octomap tree depth - service callback.
void insertScan (const tf::Point &sensorOriginTf, const tPointCloud &ground, const tPointCloud &nonground)
 Insert scan to the octomap.
bool loadFullOctreeCB (srs_env_model::LoadSaveRequest &req, srs_env_model::LoadSaveResponse &res)
 Load map service callback - full octree.
bool loadOctreeCB (srs_env_model::LoadSaveRequest &req, srs_env_model::LoadSaveResponse &res)
 Load map service callback.
virtual void publishInternal (const ros::Time &timestamp)
 Publishing callback.
bool removeCubeCB (srs_env_model::RemoveCube::Request &req, srs_env_model::RemoveCube::Response &res)
 Remove cube as a service - callback.
bool resetOctomapCB (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 Reset octomap service callback.
bool saveFullOctreeCB (srs_env_model::LoadSaveRequest &req, srs_env_model::LoadSaveResponse &res)
 Save map service callback - full octree.
bool saveOctreeCB (srs_env_model::LoadSaveRequest &req, srs_env_model::LoadSaveResponse &res)
 Save map service callback.
bool setCrawlingDepthCB (srs_env_model::SetCrawlingDepth::Request &req, srs_env_model::SetCrawlingDepth::Response &res)
 Set crawling depth - service callback.
void setDefaults ()
 Set octomap default parameters.
virtual bool shouldPublish ()
 Should something be published?

Protected Attributes

int filecounter
uint8_t m_b
bool m_bFilterWithInput
 Use input cloud to raycast filter data?
bool m_bMapLoaded
 Was map loaded.
bool m_bNewDataToFilter
 New input data inserted, do raycast filtering.
bool m_bNotFirst
 First frame is already inserted.
bool m_bPublishOctomap
 Should octomap be published.
bool m_bRemoveOutdated
 Should be outdated nodes be removed?
unsigned char m_crawlDepth
 Maximal depth of tree used when crawling.
boost::shared_ptr
< CPointCloudPlugin
m_filterCloudPlugin
 Filter pointcloud plugin.
COcFilterGround m_filterGround
bool m_filterGroundPlane
 Should ground plane be filtered?
COcFilterRaycast m_filterRaycast
COcFilterSingleSpecles m_filterSingleSpecles
uint8_t m_g
octomap::KeyRay m_keyRay
 Temporary storage for ray casting.
bool m_latchedTopics
SMapWithParameters m_mapParameters
 Octomap parameters.
ros::Publisher m_ocPublisher
 Octomap publisher.
std::string m_ocPublisherName
 Octomap publisher name.
float m_probDeleted
 Deleted node probability.
uint8_t m_r
 Created geometry color.
CPcToOcRegistration m_registration
 Registration module.
bool m_removeSpecles
 Remove specle nodes now.
CTestingObjectBasem_removeTester
 Filtering object.
ros::ServiceServer m_serviceAddCube
 Add oriented box to the octomap service.
ros::ServiceServer m_serviceGetTreeDepth
 Get octtree depth service.
ros::ServiceServer m_serviceLoadFullMap
 Load full map service.
ros::ServiceServer m_serviceLoadMap
 Load map service.
ros::ServiceServer m_serviceRemoveCube
 Remove oriented box from octomap service.
ros::ServiceServer m_serviceResetOctomap
 Reset octomap service.
ros::ServiceServer m_serviceSaveFullMap
 Save full map service.
ros::ServiceServer m_serviceSaveMap
 Save map service.
ros::ServiceServer m_serviceSetCrawlDepth
 Set crawling depth.
tSigOnNewData m_sigOnNewData
 On traversal start.
unsigned int m_testerLife
 Tester life in scans count.
unsigned int m_testerLifeCounter
 Tester life counter.
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Octomap plugin

Definition at line 68 of file octomap_plugin.h.


Member Typedef Documentation

On new octomap data signal.

Definition at line 72 of file octomap_plugin.h.


Constructor & Destructor Documentation

srs_env_model::COctoMapPlugin::COctoMapPlugin ( const std::string &  name)

Constructor.

Definition at line 77 of file octomap_plugin.cpp.

srs_env_model::COctoMapPlugin::COctoMapPlugin ( const std::string &  name,
const std::string &  filename 
)

Constructor - load data from the file.

Definition at line 104 of file octomap_plugin.cpp.

Destructor.

Destructor

Definition at line 159 of file octomap_plugin.cpp.


Member Function Documentation

bool srs_env_model::COctoMapPlugin::addCubeCB ( srs_env_model::AddCube::Request &  req,
srs_env_model::AddCube::Response &  res 
) [protected]

Remove cube as a service - callback.

Definition at line 666 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::addCubeGizmo ( const geometry_msgs::Pose pose,
const geometry_msgs::Point size 
) [protected]

For debugging purpouses - add cubical interactive marker to the scene.

For debugging purpouses - add cubical interactive marker to the scene

Definition at line 762 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::crawl ( const ros::Time currentTime)

Crawl octomap.

Definition at line 504 of file octomap_plugin.cpp.

Do octomap testing by object.

Do octomap testing by object

Definition at line 578 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::fillMapParameters ( const ros::Time time) [protected]

Fill map parameters.

Definition at line 545 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::filterCloud ( tPointCloudConstPtr &  cloud) [protected]

Use pointcloud to raycast filter map.

Use pointcloud to raycast filter map

Definition at line 480 of file octomap_plugin.cpp.

Get octomap resolution.

Definition at line 100 of file octomap_plugin.h.

Definition at line 105 of file octomap_plugin.h.

Get current octomap size.

Definition at line 94 of file octomap_plugin.h.

Get current tree depth.

Definition at line 97 of file octomap_plugin.h.

bool srs_env_model::COctoMapPlugin::getTreeDepthCB ( srs_env_model::GetTreeDepth::Request &  req,
srs_env_model::GetTreeDepth::Response &  res 
) [protected]

Get octomap tree depth - service callback.

Get octomap tree depth - service callback

Definition at line 821 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::init ( ros::NodeHandle node_handle) [virtual]

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 167 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::insertCloud ( tPointCloud::ConstPtr  cloud)

Insert pointcloud.

Definition at line 286 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::insertScan ( const tf::Point sensorOriginTf,
const tPointCloud &  ground,
const tPointCloud &  nonground 
) [protected]

Insert scan to the octomap.

Insert pointcloud scan TODO: Modify to add ground

Definition at line 451 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::loadFullOctreeCB ( srs_env_model::LoadSaveRequest &  req,
srs_env_model::LoadSaveResponse &  res 
) [protected]

Load map service callback - full octree.

Load map service callback

Definition at line 918 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::loadOctreeCB ( srs_env_model::LoadSaveRequest &  req,
srs_env_model::LoadSaveResponse &  res 
) [protected]

Load map service callback.

Load map service callback

Definition at line 831 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::pause ( bool  bPause,
ros::NodeHandle node_handle 
) [virtual]

Pause/resume plugin. All publishers and subscribers are disconnected on pause.

Pause/resume plugin. All publishers and subscribers are disconnected on pause

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 778 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::publishInternal ( const ros::Time timestamp) [protected, virtual]

Publishing callback.

Publishing function

Implements srs_env_model::CServerPluginBase.

Definition at line 523 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::removeCubeCB ( srs_env_model::RemoveCube::Request &  req,
srs_env_model::RemoveCube::Response &  res 
) [protected]

Remove cube as a service - callback.

Definition at line 617 of file octomap_plugin.cpp.

void srs_env_model::COctoMapPlugin::reset ( bool  clearLoaded = true)

Reset octomap.

Definition at line 466 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::resetOctomapCB ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [protected]

Reset octomap service callback.

Reset octomap - service callback.

Definition at line 558 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::saveFullOctreeCB ( srs_env_model::LoadSaveRequest &  req,
srs_env_model::LoadSaveResponse &  res 
) [protected]

Save map service callback - full octree.

Load map service callback

Definition at line 1002 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::saveOctreeCB ( srs_env_model::LoadSaveRequest &  req,
srs_env_model::LoadSaveResponse &  res 
) [protected]

Save map service callback.

Load map service callback

Definition at line 893 of file octomap_plugin.cpp.

bool srs_env_model::COctoMapPlugin::setCrawlingDepthCB ( srs_env_model::SetCrawlingDepth::Request &  req,
srs_env_model::SetCrawlingDepth::Response &  res 
) [protected]

Set crawling depth - service callback.

Set crawling depth - service callback

Definition at line 803 of file octomap_plugin.cpp.

Set octomap default parameters.

Definition at line 45 of file octomap_plugin.cpp.

Should something be published?

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 515 of file octomap_plugin.cpp.


Member Data Documentation

Definition at line 227 of file octomap_plugin.h.

Definition at line 273 of file octomap_plugin.h.

Use input cloud to raycast filter data?

Definition at line 237 of file octomap_plugin.h.

Was map loaded.

Definition at line 267 of file octomap_plugin.h.

New input data inserted, do raycast filtering.

Definition at line 246 of file octomap_plugin.h.

First frame is already inserted.

Definition at line 264 of file octomap_plugin.h.

Should octomap be published.

Definition at line 214 of file octomap_plugin.h.

Should be outdated nodes be removed?

Definition at line 243 of file octomap_plugin.h.

Maximal depth of tree used when crawling.

Definition at line 258 of file octomap_plugin.h.

Filter pointcloud plugin.

Definition at line 240 of file octomap_plugin.h.

Definition at line 234 of file octomap_plugin.h.

Should ground plane be filtered?

Definition at line 172 of file octomap_plugin.h.

Definition at line 233 of file octomap_plugin.h.

Definition at line 232 of file octomap_plugin.h.

Definition at line 273 of file octomap_plugin.h.

octomap::KeyRay srs_env_model::COctoMapPlugin::m_keyRay [protected]

Temporary storage for ray casting.

Definition at line 175 of file octomap_plugin.h.

Definition at line 222 of file octomap_plugin.h.

Octomap parameters.

Definition at line 181 of file octomap_plugin.h.

Octomap publisher.

Definition at line 220 of file octomap_plugin.h.

Octomap publisher name.

Definition at line 217 of file octomap_plugin.h.

Deleted node probability.

Definition at line 270 of file octomap_plugin.h.

Created geometry color.

Definition at line 273 of file octomap_plugin.h.

Registration module.

Definition at line 261 of file octomap_plugin.h.

Remove specle nodes now.

Definition at line 225 of file octomap_plugin.h.

Filtering object.

Definition at line 249 of file octomap_plugin.h.

Add oriented box to the octomap service.

Definition at line 193 of file octomap_plugin.h.

Get octtree depth service.

Definition at line 199 of file octomap_plugin.h.

Load full map service.

Definition at line 208 of file octomap_plugin.h.

Load map service.

Definition at line 202 of file octomap_plugin.h.

Remove oriented box from octomap service.

Definition at line 190 of file octomap_plugin.h.

Reset octomap service.

Definition at line 187 of file octomap_plugin.h.

Save full map service.

Definition at line 211 of file octomap_plugin.h.

Save map service.

Definition at line 205 of file octomap_plugin.h.

Set crawling depth.

Definition at line 196 of file octomap_plugin.h.

On traversal start.

Definition at line 178 of file octomap_plugin.h.

Tester life in scans count.

Definition at line 252 of file octomap_plugin.h.

Tester life counter.

Definition at line 255 of file octomap_plugin.h.

Transform listener.

Definition at line 184 of file octomap_plugin.h.


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


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:50