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

#include <marker_array_plugin.h>

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

List of all members.

Public Member Functions

 CMarkerArrayPlugin (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 ~CMarkerArrayPlugin ()
 Destructor.

Protected Member Functions

virtual void handleNode (const tButServerOcTree::iterator &it, const SMapWithParameters &mp)
 hook that is called when traversing occupied nodes of the updated Octree (does nothing here)
virtual void handlePostNodeTraversal (const SMapWithParameters &mp)
 Called when all nodes was visited.
std_msgs::ColorRGBA heightMapColor (double h) const
 Compute color from the height.
virtual void newMapDataCB (SMapWithParameters &par)
 Set used octo map frame id and time stamp.
virtual void publishInternal (const ros::Time &timestamp)
 Called when new scan was inserted and now all can be published.
virtual bool shouldPublish ()
 Should plugin publish data?

Protected Attributes

bool m_bHeightMap
 Create marker array as a height map.
bool m_bTransform
 Should input data be transformed? (are they in different frames?)
std_msgs::ColorRGBA m_color
 Markers color.
float m_colorFactor
 Coloring factor.
bool m_latchedTopics
std::string m_markerArrayFrameId
 Used frame id (input data will be transformed to it)
ros::Publisher m_markerArrayPublisher
 Collision object publisher.
std::string m_markerArrayPublisherName
 Collision object publisher name.
double m_maxX
double m_maxY
double m_maxZ
double m_minX
 Octomap metrics parameters.
double m_minY
double m_minZ
std::string m_ocFrameId
 Crawled octomap frame id.
Eigen::Matrix3f m_ocToMarkerArrayRot
 Transformation from octomap to the collision object frame id - rotation.
Eigen::Vector3f m_ocToMarkerArrayTrans
 Transformation from octomap to the collision object frame id - translation.
bool m_publishMarkerArray
 Is publishing enabled?
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Definition at line 40 of file marker_array_plugin.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 34 of file marker_array_plugin.cpp.

Destructor.

Definition at line 49 of file marker_array_plugin.cpp.


Member Function Documentation

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

Enable or disable publishing.

Definition at line 50 of file marker_array_plugin.h.

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

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

Definition at line 154 of file marker_array_plugin.cpp.

Called when all nodes was visited.

Definition at line 188 of file marker_array_plugin.cpp.

std_msgs::ColorRGBA srs_env_model::CMarkerArrayPlugin::heightMapColor ( double  h) const [protected]

Compute color from the height.

Definition at line 213 of file marker_array_plugin.cpp.

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

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 62 of file marker_array_plugin.cpp.

Set used octo map frame id and time stamp.

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

Definition at line 92 of file marker_array_plugin.cpp.

void srs_env_model::CMarkerArrayPlugin::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 265 of file marker_array_plugin.cpp.

void srs_env_model::CMarkerArrayPlugin::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 84 of file marker_array_plugin.cpp.

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 55 of file marker_array_plugin.cpp.


Member Data Documentation

Create marker array as a height map.

Definition at line 113 of file marker_array_plugin.h.

Should input data be transformed? (are they in different frames?)

Definition at line 116 of file marker_array_plugin.h.

std_msgs::ColorRGBA srs_env_model::CMarkerArrayPlugin::m_color [protected]

Markers color.

Definition at line 122 of file marker_array_plugin.h.

Coloring factor.

Definition at line 119 of file marker_array_plugin.h.

Definition at line 95 of file marker_array_plugin.h.

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

Definition at line 98 of file marker_array_plugin.h.

Collision object publisher.

Definition at line 89 of file marker_array_plugin.h.

Collision object publisher name.

Definition at line 86 of file marker_array_plugin.h.

Definition at line 110 of file marker_array_plugin.h.

Definition at line 110 of file marker_array_plugin.h.

Definition at line 110 of file marker_array_plugin.h.

Octomap metrics parameters.

Definition at line 110 of file marker_array_plugin.h.

Definition at line 110 of file marker_array_plugin.h.

Definition at line 110 of file marker_array_plugin.h.

Crawled octomap frame id.

Definition at line 101 of file marker_array_plugin.h.

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

Definition at line 104 of file marker_array_plugin.h.

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

Definition at line 107 of file marker_array_plugin.h.

Is publishing enabled?

Definition at line 83 of file marker_array_plugin.h.

Transform listener.

Definition at line 92 of file marker_array_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