octomap::OctomapServer Class Reference

#include <OctomapServer.h>

List of all members.

Public Member Functions

virtual void insertCloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud)
bool loadInitialMap (const std::string &filename)
 OctomapServer ()
bool serviceCallback (octomap_ros::GetOctomap::Request &req, octomap_ros::GetOctomap::Response &res)
virtual ~OctomapServer ()

Protected Member Functions

void connectCallback (const ros::SingleSubscriberPublisher &pub)
std_msgs::ColorRGBA heightMapColor (double h) const
void publishCollisionObject (const ros::Time &rostime=ros::Time::now())
void publishMap (const ros::Time &rostime=ros::Time::now())
void publishMarkers (const ros::Time &rostime=ros::Time::now())
void publishPointCloud (const ros::Time &rostime=ros::Time::now())

Protected Attributes

ros::Publisher m_binaryMapPub
ros::Publisher m_collisionObjectPub
std_msgs::ColorRGBA m_color
double m_colorFactor
std::string m_frameId
ros::Publisher m_markerPub
double m_maxRange
ros::NodeHandle m_nh
OcTreeROS m_octoMap
ros::Publisher m_pointCloudPub
message_filters::Subscriber
< sensor_msgs::PointCloud2 > * 
m_pointCloudSub
ros::ServiceServer m_service
tf::TransformListener m_tfListener
tf::MessageFilter
< sensor_msgs::PointCloud2 > * 
m_tfPointCloudSub
bool m_useHeightMap
double m_visMaxZ
double m_visMinZ

Detailed Description

Definition at line 57 of file OctomapServer.h.


Constructor & Destructor Documentation

octomap::OctomapServer::OctomapServer (  ) 

Definition at line 42 of file OctomapServer.cpp.

octomap::OctomapServer::~OctomapServer (  )  [virtual]

Definition at line 107 of file OctomapServer.cpp.


Member Function Documentation

void octomap::OctomapServer::connectCallback ( const ros::SingleSubscriberPublisher &  pub  )  [protected]

Definition at line 169 of file OctomapServer.cpp.

std_msgs::ColorRGBA octomap::OctomapServer::heightMapColor ( double  h  )  const [protected]

Definition at line 327 of file OctomapServer.cpp.

void octomap::OctomapServer::insertCloudCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud  )  [virtual]

Definition at line 131 of file OctomapServer.cpp.

bool octomap::OctomapServer::loadInitialMap ( const std::string &  filename  ) 

Definition at line 113 of file OctomapServer.cpp.

void octomap::OctomapServer::publishCollisionObject ( const ros::Time &  rostime = ros::Time::now()  )  [protected]

Definition at line 179 of file OctomapServer.cpp.

void octomap::OctomapServer::publishMap ( const ros::Time &  rostime = ros::Time::now()  )  [protected]

Definition at line 316 of file OctomapServer.cpp.

void octomap::OctomapServer::publishMarkers ( const ros::Time &  rostime = ros::Time::now()  )  [protected]

Definition at line 217 of file OctomapServer.cpp.

void octomap::OctomapServer::publishPointCloud ( const ros::Time &  rostime = ros::Time::now()  )  [protected]

Definition at line 283 of file OctomapServer.cpp.

bool octomap::OctomapServer::serviceCallback ( octomap_ros::GetOctomap::Request &  req,
octomap_ros::GetOctomap::Response &  res 
)

Definition at line 305 of file OctomapServer.cpp.


Member Data Documentation

ros::Publisher octomap::OctomapServer::m_binaryMapPub [protected]

Definition at line 75 of file OctomapServer.h.

Definition at line 75 of file OctomapServer.h.

std_msgs::ColorRGBA octomap::OctomapServer::m_color [protected]

Definition at line 85 of file OctomapServer.h.

Definition at line 86 of file OctomapServer.h.

std::string octomap::OctomapServer::m_frameId [protected]

Definition at line 83 of file OctomapServer.h.

ros::Publisher octomap::OctomapServer::m_markerPub [protected]

Definition at line 75 of file OctomapServer.h.

Definition at line 82 of file OctomapServer.h.

ros::NodeHandle octomap::OctomapServer::m_nh [protected]

Definition at line 74 of file OctomapServer.h.

OcTreeROS octomap::OctomapServer::m_octoMap [protected]

Definition at line 81 of file OctomapServer.h.

ros::Publisher octomap::OctomapServer::m_pointCloudPub [protected]

Definition at line 75 of file OctomapServer.h.

message_filters::Subscriber<sensor_msgs::PointCloud2>* octomap::OctomapServer::m_pointCloudSub [protected]

Definition at line 76 of file OctomapServer.h.

ros::ServiceServer octomap::OctomapServer::m_service [protected]

Definition at line 78 of file OctomapServer.h.

tf::TransformListener octomap::OctomapServer::m_tfListener [protected]

Definition at line 79 of file OctomapServer.h.

tf::MessageFilter<sensor_msgs::PointCloud2>* octomap::OctomapServer::m_tfPointCloudSub [protected]

Definition at line 77 of file OctomapServer.h.

Definition at line 84 of file OctomapServer.h.

Definition at line 88 of file OctomapServer.h.

Definition at line 87 of file OctomapServer.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Defines


octomap_server
Author(s): Armin Hornung
autogenerated on Fri Jan 11 09:32:37 2013