#include <octomap_server_contact.h>
Public Member Functions | |
virtual void | initContactSensor (const ros::NodeHandle &privateNh) |
virtual void | insertContactSensor (const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg) |
virtual void | insertContactSensorCallback (const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg) |
virtual void | insertProximityCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud) |
virtual void | insertScanProximity (const tf::Point &sensorOriginTf, const PCLPointCloud &pc) |
OctomapServerContact (const ros::NodeHandle &privateNh=ros::NodeHandle("~")) | |
virtual void | publishAll (const ros::Time &rostime) |
virtual void | subscribe () |
virtual void | unsubscribe () |
virtual | ~OctomapServerContact () |
Public Member Functions inherited from octomap_server::OctomapServer | |
bool | clearBBXSrv (BBXSrv::Request &req, BBXSrv::Response &resp) |
virtual void | insertCloudCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud) |
virtual bool | octomapBinarySrv (OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res) |
virtual bool | octomapFullSrv (OctomapSrv::Request &req, OctomapSrv::GetOctomap::Response &res) |
OctomapServer (const ros::NodeHandle private_nh_=ros::NodeHandle("~"), const ros::NodeHandle &nh_=ros::NodeHandle()) | |
virtual bool | openFile (const std::string &filename) |
bool | resetSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) |
virtual | ~OctomapServer () |
Protected Member Functions | |
virtual void | onInit () |
Protected Member Functions inherited from octomap_server::OctomapServer | |
void | adjustMapData (nav_msgs::OccupancyGrid &map, const nav_msgs::MapMetaData &oldMapInfo) const |
void | filterGroundPlane (const PCLPointCloud &pc, PCLPointCloud &ground, PCLPointCloud &nonground) const |
virtual void | handleFreeNode (const OcTreeT::iterator &it) |
virtual void | handleFreeNodeInBBX (const OcTreeT::iterator &it) |
virtual void | handleNode (const OcTreeT::iterator &it) |
virtual void | handleNodeInBBX (const OcTreeT::iterator &it) |
virtual void | handleOccupiedNode (const OcTreeT::iterator &it) |
virtual void | handleOccupiedNodeInBBX (const OcTreeT::iterator &it) |
virtual void | handlePostNodeTraversal (const ros::Time &rostime) |
virtual void | handlePreNodeTraversal (const ros::Time &rostime) |
virtual void | insertScan (const tf::Point &sensorOrigin, const PCLPointCloud &ground, const PCLPointCloud &nonground) |
bool | isInUpdateBBX (const OcTreeT::iterator &it) const |
bool | isSpeckleNode (const octomap::OcTreeKey &key) const |
bool | mapChanged (const nav_msgs::MapMetaData &oldMapInfo, const nav_msgs::MapMetaData &newMapInfo) |
unsigned | mapIdx (const octomap::OcTreeKey &key) const |
unsigned | mapIdx (int i, int j) const |
void | publishBinaryOctoMap (const ros::Time &rostime=ros::Time::now()) const |
void | publishFullOctoMap (const ros::Time &rostime=ros::Time::now()) const |
void | publishProjected2DMap (const ros::Time &rostime=ros::Time::now()) |
void | reconfigureCallback (octomap_server::OctomapServerConfig &config, uint32_t level) |
virtual void | update2DMap (const OcTreeT::iterator &it, bool occupied) |
Additional Inherited Members | |
Public Types inherited from octomap_server::OctomapServer | |
typedef octomap_msgs::BoundingBoxQuery | BBXSrv |
typedef octomap_msgs::GetOctomap | OctomapSrv |
typedef octomap::OcTree | OcTreeT |
typedef pcl::PointXYZ | PCLPoint |
typedef pcl::PointCloud< pcl::PointXYZ > | PCLPointCloud |
Static Protected Member Functions inherited from octomap_server::OctomapServer | |
static std_msgs::ColorRGBA | heightMapColor (double h) |
static void | updateMaxKey (const octomap::OcTreeKey &in, octomap::OcTreeKey &max) |
static void | updateMinKey (const octomap::OcTreeKey &in, octomap::OcTreeKey &min) |
Definition at line 52 of file octomap_server_contact.h.
jsk_pcl_ros::OctomapServerContact::OctomapServerContact | ( | const ros::NodeHandle & | privateNh = ros::NodeHandle("~") | ) |
Definition at line 45 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 118 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 121 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 315 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 459 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 174 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Definition at line 209 of file octomap_server_contact_nodelet.cpp.
|
protectedvirtual |
Definition at line 852 of file octomap_server_contact_nodelet.cpp.
|
virtual |
Reimplemented from octomap_server::OctomapServer.
Definition at line 466 of file octomap_server_contact_nodelet.cpp.
|
inlinevirtual |
Definition at line 66 of file octomap_server_contact.h.
|
inlinevirtual |
Definition at line 67 of file octomap_server_contact.h.
|
protected |
Definition at line 77 of file octomap_server_contact.h.
|
protected |
Definition at line 80 of file octomap_server_contact.h.
|
protected |
Definition at line 79 of file octomap_server_contact.h.
|
protected |
Definition at line 75 of file octomap_server_contact.h.
|
protected |
Definition at line 74 of file octomap_server_contact.h.
|
protected |
Definition at line 74 of file octomap_server_contact.h.
|
protected |
Definition at line 87 of file octomap_server_contact.h.
|
protected |
Definition at line 90 of file octomap_server_contact.h.
|
protected |
Definition at line 92 of file octomap_server_contact.h.
|
protected |
Definition at line 89 of file octomap_server_contact.h.
|
protected |
Definition at line 91 of file octomap_server_contact.h.
|
protected |
Definition at line 77 of file octomap_server_contact.h.
|
protected |
Definition at line 77 of file octomap_server_contact.h.
|
protected |
Definition at line 98 of file octomap_server_contact.h.
|
protected |
Definition at line 83 of file octomap_server_contact.h.
|
protected |
Definition at line 72 of file octomap_server_contact.h.
|
protected |
Definition at line 85 of file octomap_server_contact.h.
|
protected |
Definition at line 82 of file octomap_server_contact.h.
|
protected |
Definition at line 77 of file octomap_server_contact.h.
|
protected |
Definition at line 96 of file octomap_server_contact.h.
|
protected |
Definition at line 76 of file octomap_server_contact.h.
|
protected |
Definition at line 73 of file octomap_server_contact.h.
|
protected |
Definition at line 71 of file octomap_server_contact.h.
|
protected |
Definition at line 71 of file octomap_server_contact.h.
|
protected |
Definition at line 94 of file octomap_server_contact.h.