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

#include <but_server.h>

List of all members.

Public Types

typedef pcl::PointCloud
< pcl::PointXYZ > 
tPCLPointCloud
 Type of the used pointcloud.

Public Member Functions

 CButServer (const std::string &filename="")
 Constructor - load file.
void pause (bool bPause)
 Pause-resume server.
void reset ()
 Reset server and all plugins.
virtual ~CButServer ()
 Destructor.

Protected Types

typedef std::vector
< CServerPluginBase * > 
tVecPlugins
 All plugins vector type.

Protected Member Functions

void onOcMapDataChanged (tButServerOcMapConstPtr mapdata, const ros::Time &stamp)
 On octomap data changed.
bool onPause (ButServerPause::Request &request, ButServerPause::Response &response)
 On pause service call.
bool onReset (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 On reset service call.
bool onUseInputColor (srs_env_model::UseInputColor::Request &req, srs_env_model::UseInputColor::Response &res)
 Use/do not use color service callback.
void publishAll (const ros::Time &rostime)
 Publish all.
void publishPlugins (const ros::Time &rostime)
 Publish all.

Protected Attributes

bool m_bIsPaused
 Is server running now.
bool m_bUseOldIMP
 Use old interactive server plugin? TODO: Remov this when new is will be finished.
int m_frameCounter
 Current frame counter.
bool m_latchedTopics
ros::NodeHandle m_nh
 Node handle.
int m_numPCFramesProcessed
 Every N-th frame should be processed when including point-cloud.
boost::shared_ptr< CCMapPluginm_plugCMap
 Collision map.
boost::shared_ptr
< CCollisionObjectPlugin
m_plugCollisionObject
 Collision object plugin.
boost::shared_ptr
< CCompressedPointCloudPlugin
m_plugCompressedPointCloud
 Compressed pointcloud plugin.
boost::shared_ptr< CExamplePluginm_plugExample
 Create example plugin.
boost::shared_ptr
< CExampleCrawlerPlugin
m_plugExampleCrawler
 Create crawler plugin holder.
boost::shared_ptr
< CIMarkersPlugin
m_plugIMarkers
 Interactive markers server plugin.
boost::shared_ptr
< CPointCloudPlugin
m_plugInputPointCloud
 Incoming depth points cloud.
tVecPlugins m_plugins
 All plugins.
boost::shared_ptr
< CCollisionGridPlugin
m_plugMap2D
 2D map plugin
boost::shared_ptr
< CMarkerArrayPlugin
m_plugMarkerArray
 Marker array publisher plugin.
boost::shared_ptr< CObjTreePluginm_plugObjTree
 ObjTree plugin.
boost::shared_ptr
< CPointCloudPlugin
m_plugOcMapPointCloud
 Output depth points cloud - whole octomap.
boost::shared_ptr< COctoMapPluginm_plugOctoMap
 Octo map plugin.
boost::shared_ptr
< COldIMarkersPlugin
m_plugOldIMarkers
 Old interactive markers plugin.
boost::shared_ptr
< CPointCloudPlugin
m_plugVisiblePointCloud
 Visible points point cloud.
ros::ServiceServer m_servicePause
 Pause service.
ros::ServiceServer m_serviceReset
 Reset service.
ros::ServiceServer m_serviceUseInputColor
 Use input color service.

Detailed Description

BUT dynamic scene server class.

Definition at line 96 of file but_server.h.


Member Typedef Documentation

Type of the used pointcloud.

Definition at line 100 of file but_server.h.

All plugins vector type.

Definition at line 173 of file but_server.h.


Constructor & Destructor Documentation

srs_env_model::CButServer::CButServer ( const std::string &  filename = "")

Constructor - load file.

Swap function template.

octomap_server: A Tool to serve 3D OctoMaps in ROS (binary and as visualization) (inspired by the ROS map_saver)

Author:
A. Hornung, University of Freiburg, Copyright (C) 2010-2011.
See also:
http://octomap.sourceforge.net/ License: BSD Copyright (c) 2010-2011, A. Hornung, University of Freiburg All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. * Neither the name of the University of Freiburg nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. Constructor

Definition at line 65 of file but_server.cpp.

Destructor.

Destructor

Definition at line 159 of file but_server.cpp.


Member Function Documentation

void srs_env_model::CButServer::onOcMapDataChanged ( tButServerOcMapConstPtr  mapdata,
const ros::Time stamp 
) [inline, protected]

On octomap data changed.

Definition at line 120 of file but_server.h.

bool srs_env_model::CButServer::onPause ( ButServerPause::Request &  request,
ButServerPause::Response &  response 
) [protected]

On pause service call.

On pause service call

Definition at line 220 of file but_server.cpp.

bool srs_env_model::CButServer::onReset ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [inline, protected]

On reset service call.

Definition at line 126 of file but_server.h.

bool srs_env_model::CButServer::onUseInputColor ( srs_env_model::UseInputColor::Request &  req,
srs_env_model::UseInputColor::Response &  res 
) [protected]

Use/do not use color service callback.

Use/do not use color service callback

Definition at line 276 of file but_server.cpp.

Pause-resume server.

Pause-resume server

Definition at line 237 of file but_server.cpp.

void srs_env_model::CButServer::publishAll ( const ros::Time rostime) [protected]

Publish all.

Publish all data

Definition at line 171 of file but_server.cpp.

void srs_env_model::CButServer::publishPlugins ( const ros::Time rostime) [protected]

Publish all.

Publish data

Definition at line 266 of file but_server.cpp.

Reset server and all plugins.

Definition at line 206 of file but_server.cpp.


Member Data Documentation

Is server running now.

Definition at line 144 of file but_server.h.

Use old interactive server plugin? TODO: Remov this when new is will be finished.

Definition at line 217 of file but_server.h.

Current frame counter.

Definition at line 155 of file but_server.h.

Definition at line 149 of file but_server.h.

Node handle.

Definition at line 147 of file but_server.h.

Every N-th frame should be processed when including point-cloud.

Definition at line 152 of file but_server.h.

boost::shared_ptr< CCMapPlugin > srs_env_model::CButServer::m_plugCMap [protected]

Collision map.

Definition at line 183 of file but_server.h.

Collision object plugin.

Definition at line 196 of file but_server.h.

Compressed pointcloud plugin.

Definition at line 214 of file but_server.h.

boost::shared_ptr< CExamplePlugin > srs_env_model::CButServer::m_plugExample [protected]

Create example plugin.

Definition at line 221 of file but_server.h.

Create crawler plugin holder.

Definition at line 224 of file but_server.h.

Interactive markers server plugin.

Definition at line 202 of file but_server.h.

Incoming depth points cloud.

Definition at line 186 of file but_server.h.

All plugins.

Definition at line 176 of file but_server.h.

2D map plugin

Definition at line 199 of file but_server.h.

Marker array publisher plugin.

Definition at line 205 of file but_server.h.

boost::shared_ptr< CObjTreePlugin > srs_env_model::CButServer::m_plugObjTree [protected]

ObjTree plugin.

Definition at line 208 of file but_server.h.

Output depth points cloud - whole octomap.

Definition at line 186 of file but_server.h.

boost::shared_ptr< COctoMapPlugin > srs_env_model::CButServer::m_plugOctoMap [protected]

Octo map plugin.

Definition at line 193 of file but_server.h.

Old interactive markers plugin.

Definition at line 211 of file but_server.h.

Visible points point cloud.

Definition at line 190 of file but_server.h.

Pause service.

Definition at line 164 of file but_server.h.

Reset service.

Definition at line 161 of file but_server.h.

Use input color service.

Definition at line 167 of file but_server.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