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

#include <imarkers_plugin.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< interactive_markers::InteractiveMarkerServer
InteractiveMarkerServerPtr

Public Member Functions

 CIMarkersPlugin (const std::string &name)
 Constructor.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
virtual ~CIMarkersPlugin ()
 Destructor.

Protected Types

typedef std::pair< std::string,
srs_env_model_msgs::PlaneDesc
tNamedPlane
 Plane.
typedef std::map< int,
tNamedPlane
tPlanesMap

Protected Member Functions

void addPlaneSrvCall (const srs_env_model_msgs::PlaneDesc &plane, const std::string &name)
 Service helper - add plane.
std::string getUniqueName ()
 Get unique string (used as interactive marker name)
bool insertPlaneCallback (srs_env_model::AddPlanes::Request &req, srs_env_model::AddPlanes::Response &res)
 Insert or modify plane array.
void operatePlane (const srs_env_model_msgs::PlaneDesc &plane)
 Insert/modify/remove plane.
virtual void publishInternal (const ros::Time &timestamp)
 Publish data - virtual function.
void removePlaneSrvCall (const srs_env_model_msgs::PlaneDesc &plane, const std::string &name)
 Service helper - remove plane.
virtual bool shouldPublish ()
 Should plugin publish data?

Protected Attributes

ros::ServiceClient m_addInteractivePlaneService
 Add plane interactive marker service.
bool m_bUseExternalServer
 Use external server services?
tPlanesMap m_dataPlanes
std::string m_IMarkersFrameId
 Used frame id (input data will be transformed to it)
srs_interaction_primitives::InteractiveMarkerServerPtr m_imServer
 Interactive markers server pointer.
std::string m_planesFrameId
 Planes frame id.
ros::ServiceClient m_removeInteractiveMarkerService
 Remove object from the interactive markers server pointer.
std::string m_serverTopicName
 Server topic name.
ros::ServiceServer m_serviceInsertPlanes
 Insert some planes service.
long int m_uniqueNameCounter
 Unique name counter.

Detailed Description

Definition at line 46 of file imarkers_plugin.h.


Member Typedef Documentation

Definition at line 49 of file imarkers_plugin.h.

typedef std::pair< std::string, srs_env_model_msgs::PlaneDesc > srs_env_model::CIMarkersPlugin::tNamedPlane [protected]

Plane.

Definition at line 120 of file imarkers_plugin.h.

Definition at line 121 of file imarkers_plugin.h.


Constructor & Destructor Documentation

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

Constructor.

Definition at line 35 of file imarkers_plugin.cpp.

Destructor.

Definition at line 44 of file imarkers_plugin.cpp.


Member Function Documentation

void srs_env_model::CIMarkersPlugin::addPlaneSrvCall ( const srs_env_model_msgs::PlaneDesc plane,
const std::string &  name 
) [protected]

Service helper - add plane.

Parameters:
planeAdded plane

Definition at line 205 of file imarkers_plugin.cpp.

std::string srs_env_model::CIMarkersPlugin::getUniqueName ( ) [protected]

Get unique string (used as interactive marker name)

Definition at line 277 of file imarkers_plugin.cpp.

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

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Definition at line 53 of file imarkers_plugin.cpp.

bool srs_env_model::CIMarkersPlugin::insertPlaneCallback ( srs_env_model::AddPlanes::Request &  req,
srs_env_model::AddPlanes::Response &  res 
) [protected]

Insert or modify plane array.

Parameters:
paArray of planes

Definition at line 129 of file imarkers_plugin.cpp.

Insert/modify/remove plane.

Parameters:
planePlane

Definition at line 152 of file imarkers_plugin.cpp.

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

Publish data - virtual function.

Implements srs_env_model::CServerPluginBase.

Definition at line 100 of file imarkers_plugin.h.

void srs_env_model::CIMarkersPlugin::removePlaneSrvCall ( const srs_env_model_msgs::PlaneDesc plane,
const std::string &  name 
) [protected]

Service helper - remove plane.

Parameters:
planeAdded plane

Definition at line 253 of file imarkers_plugin.cpp.

virtual bool srs_env_model::CIMarkersPlugin::shouldPublish ( ) [inline, protected, virtual]

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Definition at line 97 of file imarkers_plugin.h.


Member Data Documentation

Add plane interactive marker service.

Definition at line 110 of file imarkers_plugin.h.

Use external server services?

Definition at line 134 of file imarkers_plugin.h.

Definition at line 122 of file imarkers_plugin.h.

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

Definition at line 113 of file imarkers_plugin.h.

Interactive markers server pointer.

Definition at line 116 of file imarkers_plugin.h.

Planes frame id.

Definition at line 125 of file imarkers_plugin.h.

Remove object from the interactive markers server pointer.

Definition at line 107 of file imarkers_plugin.h.

Server topic name.

Definition at line 128 of file imarkers_plugin.h.

Insert some planes service.

Definition at line 104 of file imarkers_plugin.h.

Unique name counter.

Definition at line 131 of file imarkers_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