Public Member Functions | Protected Member Functions | Protected Attributes
srs_env_model::CCollisionGridPlugin Class Reference

#include <collision_grid_plugin.h>

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

List of all members.

Public Member Functions

 CCollisionGridPlugin (const std::string &name)
 Constructor.
void enable (bool enabled)
 Enable or disable publishing.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
virtual void pause (bool bPause, ros::NodeHandle &node_handle)
 Pause/resume plugin. All publishers and subscribers are disconnected on pause.
virtual ~CCollisionGridPlugin ()
 Destructor.

Protected Member Functions

virtual void handleFreeNode (tButServerOcTree::iterator &it, const SMapWithParameters &mp)
 Handle free node (does nothing here)
virtual void handleOccupiedNode (tButServerOcTree::iterator &it, const SMapWithParameters &mp)
 hook that is called when traversing occupied nodes of the updated Octree (does nothing here)
virtual void newMapDataCB (SMapWithParameters &par)
 Set used octomap frame id and timestamp.
virtual void publishInternal (const ros::Time &timestamp)
 Called when new scan was inserted and now all can be published.
bool shouldPublish ()
 Should plugin publish data?

Protected Attributes

bool m_bConvert
 Conversion between frame id's must be done...
ros::Publisher m_gridPublisher
 Collision object publisher.
std::string m_gridPublisherName
 Collision object publisher name.
bool m_latchedTopics
double m_minSizeX
 Map limits.
double m_minSizeY
unsigned m_multires2DScale
 Grid scaling.
std::string m_ocFrameId
 Crawled octomap frame id.
Eigen::Matrix3f m_ocToGridRot
 Transformation from octomap to the collision object frame id - rotation.
Eigen::Vector3f m_ocToGridTrans
 Transformation from octomap to the collision object frame id - translation.
octomap::OcTreeKey m_paddedMinKey
 Padded key minimum.
bool m_publishGrid
 Is publishing enabled?
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Definition at line 40 of file collision_grid_plugin.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 34 of file collision_grid_plugin.cpp.

Destructor.

Definition at line 47 of file collision_grid_plugin.cpp.


Member Function Documentation

Enable or disable publishing.

Definition at line 50 of file collision_grid_plugin.h.

void srs_env_model::CCollisionGridPlugin::handleFreeNode ( tButServerOcTree::iterator &  it,
const SMapWithParameters mp 
) [protected, virtual]

Handle free node (does nothing here)

Free node handler

Definition at line 228 of file collision_grid_plugin.cpp.

void srs_env_model::CCollisionGridPlugin::handleOccupiedNode ( tButServerOcTree::iterator &  it,
const SMapWithParameters mp 
) [protected, virtual]

hook that is called when traversing occupied nodes of the updated Octree (does nothing here)

Occupied node handler

Definition at line 201 of file collision_grid_plugin.cpp.

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 60 of file collision_grid_plugin.cpp.

Set used octomap frame id and timestamp.

Implements srs_env_model::COctomapCrawlerBase< tButServerOcTree::NodeType >.

Definition at line 85 of file collision_grid_plugin.cpp.

void srs_env_model::CCollisionGridPlugin::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 255 of file collision_grid_plugin.cpp.

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

Called when new scan was inserted and now all can be published.

Implements srs_env_model::CServerPluginBase.

Definition at line 75 of file collision_grid_plugin.cpp.

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 53 of file collision_grid_plugin.cpp.


Member Data Documentation

Conversion between frame id's must be done...

Definition at line 110 of file collision_grid_plugin.h.

Collision object publisher.

Definition at line 85 of file collision_grid_plugin.h.

Collision object publisher name.

Definition at line 82 of file collision_grid_plugin.h.

Definition at line 91 of file collision_grid_plugin.h.

Map limits.

Definition at line 106 of file collision_grid_plugin.h.

Definition at line 107 of file collision_grid_plugin.h.

Grid scaling.

Definition at line 113 of file collision_grid_plugin.h.

Crawled octomap frame id.

Definition at line 94 of file collision_grid_plugin.h.

Transformation from octomap to the collision object frame id - rotation.

Definition at line 97 of file collision_grid_plugin.h.

Transformation from octomap to the collision object frame id - translation.

Definition at line 100 of file collision_grid_plugin.h.

Padded key minimum.

Definition at line 103 of file collision_grid_plugin.h.

Is publishing enabled?

Definition at line 79 of file collision_grid_plugin.h.

Transform listener.

Definition at line 88 of file collision_grid_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