#include <OctomapServerCombined.h>
Public Member Functions | |
void | insertCloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud) |
OctomapServerCombined (const std::string &filename="") | |
bool | serviceCallback (octomap_ros::GetOctomap::Request &req, octomap_ros::GetOctomap::Response &res) |
virtual | ~OctomapServerCombined () |
Private Member Functions | |
std_msgs::ColorRGBA | heightMapColor (double h) const |
void | publishAll (const ros::Time &rostime=ros::Time::now()) |
void | publishMap (const ros::Time &rostime=ros::Time::now()) |
Private Attributes | |
std::string | m_baseFrameId |
ros::Publisher | m_binaryMapPub |
ros::Publisher | m_collisionObjectPub |
std_msgs::ColorRGBA | m_color |
double | m_colorFactor |
bool | m_filterGroundPlane |
bool | m_filterSpeckles |
double | m_groundFilterAngle |
double | m_groundFilterDistance |
double | m_groundFilterPlaneDistance |
KeyRay | m_keyRay |
ros::Publisher | m_mapPub |
ros::Publisher | m_markerPub |
double | m_maxRange |
double | m_minSizeX |
double | m_minSizeY |
ros::NodeHandle | m_nh |
double | m_occupancyMaxZ |
double | m_occupancyMinZ |
OcTreeROS | m_octoMap |
double | m_pointcloudMaxZ |
double | m_pointcloudMinZ |
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 |
std::string | m_worldFrameId |
Definition at line 65 of file OctomapServerCombined.h.
octomap::OctomapServerCombined::OctomapServerCombined | ( | const std::string & | filename = "" |
) |
Definition at line 42 of file OctomapServerCombined.cpp.
octomap::OctomapServerCombined::~OctomapServerCombined | ( | ) | [virtual] |
Definition at line 144 of file OctomapServerCombined.cpp.
std_msgs::ColorRGBA octomap::OctomapServerCombined::heightMapColor | ( | double | h | ) | const [private] |
Definition at line 642 of file OctomapServerCombined.cpp.
void octomap::OctomapServerCombined::insertCloudCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud | ) |
Definition at line 152 of file OctomapServerCombined.cpp.
void octomap::OctomapServerCombined::publishAll | ( | const ros::Time & | rostime = ros::Time::now() |
) | [private] |
Definition at line 363 of file OctomapServerCombined.cpp.
void octomap::OctomapServerCombined::publishMap | ( | const ros::Time & | rostime = ros::Time::now() |
) | [private] |
Definition at line 631 of file OctomapServerCombined.cpp.
bool octomap::OctomapServerCombined::serviceCallback | ( | octomap_ros::GetOctomap::Request & | req, | |
octomap_ros::GetOctomap::Response & | res | |||
) |
Definition at line 620 of file OctomapServerCombined.cpp.
std::string octomap::OctomapServerCombined::m_baseFrameId [private] |
Definition at line 88 of file OctomapServerCombined.h.
ros::Publisher octomap::OctomapServerCombined::m_binaryMapPub [private] |
Definition at line 78 of file OctomapServerCombined.h.
ros::Publisher octomap::OctomapServerCombined::m_collisionObjectPub [private] |
Definition at line 78 of file OctomapServerCombined.h.
std_msgs::ColorRGBA octomap::OctomapServerCombined::m_color [private] |
Definition at line 90 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_colorFactor [private] |
Definition at line 91 of file OctomapServerCombined.h.
bool octomap::OctomapServerCombined::m_filterGroundPlane [private] |
Definition at line 101 of file OctomapServerCombined.h.
bool octomap::OctomapServerCombined::m_filterSpeckles [private] |
Definition at line 99 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_groundFilterAngle [private] |
Definition at line 103 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_groundFilterDistance [private] |
Definition at line 102 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_groundFilterPlaneDistance [private] |
Definition at line 104 of file OctomapServerCombined.h.
KeyRay octomap::OctomapServerCombined::m_keyRay [private] |
Definition at line 85 of file OctomapServerCombined.h.
ros::Publisher octomap::OctomapServerCombined::m_mapPub [private] |
Definition at line 78 of file OctomapServerCombined.h.
ros::Publisher octomap::OctomapServerCombined::m_markerPub [private] |
Definition at line 78 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_maxRange [private] |
Definition at line 86 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_minSizeX [private] |
Definition at line 97 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_minSizeY [private] |
Definition at line 98 of file OctomapServerCombined.h.
ros::NodeHandle octomap::OctomapServerCombined::m_nh [private] |
Definition at line 77 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_occupancyMaxZ [private] |
Definition at line 96 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_occupancyMinZ [private] |
Definition at line 95 of file OctomapServerCombined.h.
OcTreeROS octomap::OctomapServerCombined::m_octoMap [private] |
Definition at line 84 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_pointcloudMaxZ [private] |
Definition at line 94 of file OctomapServerCombined.h.
double octomap::OctomapServerCombined::m_pointcloudMinZ [private] |
Definition at line 93 of file OctomapServerCombined.h.
ros::Publisher octomap::OctomapServerCombined::m_pointCloudPub [private] |
Definition at line 78 of file OctomapServerCombined.h.
message_filters::Subscriber<sensor_msgs::PointCloud2>* octomap::OctomapServerCombined::m_pointCloudSub [private] |
Definition at line 79 of file OctomapServerCombined.h.
ros::ServiceServer octomap::OctomapServerCombined::m_service [private] |
Definition at line 81 of file OctomapServerCombined.h.
tf::TransformListener octomap::OctomapServerCombined::m_tfListener [private] |
Definition at line 82 of file OctomapServerCombined.h.
tf::MessageFilter<sensor_msgs::PointCloud2>* octomap::OctomapServerCombined::m_tfPointCloudSub [private] |
Definition at line 80 of file OctomapServerCombined.h.
bool octomap::OctomapServerCombined::m_useHeightMap [private] |
Definition at line 89 of file OctomapServerCombined.h.
std::string octomap::OctomapServerCombined::m_worldFrameId [private] |
Definition at line 87 of file OctomapServerCombined.h.