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

#include <collision_object_plugin.h>

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

List of all members.

Public Member Functions

 CCollisionObjectPlugin (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)
 Connect/disconnect plugin to/from all topics.
bool shouldPublish ()
 Should plugin publish data?
virtual ~CCollisionObjectPlugin ()
 Destructor.

Protected Member Functions

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.

Protected Attributes

bool m_bConvert
 Does point need to be converted from ocmap frame id to the collision objects frame id?
std::string m_coFrameId
 Used frame id (input data will be transformed to it)
ros::Publisher m_coPublisher
 Collision object publisher.
std::string m_coPublisherName
 Collision object publisher name.
bool m_latchedTopics
std::string m_ocFrameId
 Crawled octomap frame id.
Eigen::Matrix3f m_ocToCoRot
 Transformation from octomap to the collision object frame id - rotation.
Eigen::Vector3f m_ocToCoTrans
 Transformation from octomap to the collision object frame id - translation.
bool m_publishCollisionObject
 Is publishing enabled?
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Definition at line 40 of file collision_object_plugin.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 34 of file collision_object_plugin.cpp.

Destructor.

Definition at line 47 of file collision_object_plugin.cpp.


Member Function Documentation

Enable or disable publishing.

Definition at line 50 of file collision_object_plugin.h.

void srs_env_model::CCollisionObjectPlugin::handleOccupiedNode ( 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 141 of file collision_object_plugin.cpp.

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 60 of file collision_object_plugin.cpp.

Set used octomap frame id and timestamp.

We need no transformation - frames are the same...

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

Definition at line 79 of file collision_object_plugin.cpp.

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

Connect/disconnect plugin to/from all topics.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 168 of file collision_object_plugin.cpp.

void srs_env_model::CCollisionObjectPlugin::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 71 of file collision_object_plugin.cpp.

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 53 of file collision_object_plugin.cpp.


Member Data Documentation

Does point need to be converted from ocmap frame id to the collision objects frame id?

Definition at line 103 of file collision_object_plugin.h.

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

Definition at line 91 of file collision_object_plugin.h.

Collision object publisher.

Definition at line 82 of file collision_object_plugin.h.

Collision object publisher name.

Definition at line 79 of file collision_object_plugin.h.

Definition at line 88 of file collision_object_plugin.h.

Crawled octomap frame id.

Definition at line 94 of file collision_object_plugin.h.

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

Definition at line 97 of file collision_object_plugin.h.

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

Definition at line 100 of file collision_object_plugin.h.

Is publishing enabled?

Definition at line 76 of file collision_object_plugin.h.

Transform listener.

Definition at line 85 of file collision_object_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