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

#include <map2d_plugin.h>

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

List of all members.

Public Member Functions

 CMap2DPlugin (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 ~CMap2DPlugin ()
 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...
bool m_latchedTopics
std::string m_map2DFrameId
 Used frame id (input data will be transformed to it)
ros::Publisher m_map2DPublisher
 Collision object publisher.
std::string m_map2DPublisherName
 Collision object publisher name.
double m_minSizeX
 Map limits.
double m_minSizeY
std::string m_ocFrameId
 Crawled octomap frame id.
Eigen::Matrix3f m_ocToMap2DRot
 Transformation from octomap to the collision object frame id - rotation.
Eigen::Vector3f m_ocToMap2DTrans
 Transformation from octomap to the collision object frame id - translation.
octomap::OcTreeKey m_paddedMinKey
 Padded key minimum.
bool m_publishMap2D
 Is publishing enabled?
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Definition at line 40 of file map2d_plugin.h.


Constructor & Destructor Documentation

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

Constructor.

Definition at line 34 of file map2d_plugin.cpp.

Destructor.

Definition at line 48 of file map2d_plugin.cpp.


Member Function Documentation

void srs_env_model::CMap2DPlugin::enable ( bool  enabled) [inline]

Enable or disable publishing.

Definition at line 50 of file map2d_plugin.h.

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

Handle free node (does nothing here)

Free node handler

Definition at line 243 of file map2d_plugin.cpp.

void srs_env_model::CMap2DPlugin::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 216 of file map2d_plugin.cpp.

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

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 61 of file map2d_plugin.cpp.

void srs_env_model::CMap2DPlugin::newMapDataCB ( SMapWithParameters par) [protected, virtual]

Set used octomap frame id and timestamp.

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

Definition at line 82 of file map2d_plugin.cpp.

void srs_env_model::CMap2DPlugin::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 270 of file map2d_plugin.cpp.

void srs_env_model::CMap2DPlugin::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 74 of file map2d_plugin.cpp.

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 54 of file map2d_plugin.cpp.


Member Data Documentation

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

Definition at line 113 of file map2d_plugin.h.

Definition at line 91 of file map2d_plugin.h.

Used frame id (input data will be transformed to it)

Definition at line 94 of file map2d_plugin.h.

Collision object publisher.

Definition at line 85 of file map2d_plugin.h.

Collision object publisher name.

Definition at line 82 of file map2d_plugin.h.

Map limits.

Definition at line 109 of file map2d_plugin.h.

Definition at line 110 of file map2d_plugin.h.

Crawled octomap frame id.

Definition at line 97 of file map2d_plugin.h.

Eigen::Matrix3f srs_env_model::CMap2DPlugin::m_ocToMap2DRot [protected]

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

Definition at line 100 of file map2d_plugin.h.

Eigen::Vector3f srs_env_model::CMap2DPlugin::m_ocToMap2DTrans [protected]

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

Definition at line 103 of file map2d_plugin.h.

octomap::OcTreeKey srs_env_model::CMap2DPlugin::m_paddedMinKey [protected]

Padded key minimum.

Definition at line 106 of file map2d_plugin.h.

Is publishing enabled?

Definition at line 79 of file map2d_plugin.h.

Transform listener.

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