#include <octomap_server_contact.h>
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.
jsk_pcl_ros::OctomapServerContact::~OctomapServerContact | ( | ) | [virtual] |
Definition at line 118 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::initContactSensor | ( | const ros::NodeHandle & | privateNh | ) | [virtual] |
Definition at line 121 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::insertContactSensor | ( | const jsk_recognition_msgs::ContactSensorArray::ConstPtr & | msg | ) | [virtual] |
Definition at line 307 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::insertContactSensorCallback | ( | const jsk_recognition_msgs::ContactSensorArray::ConstPtr & | msg | ) | [virtual] |
Definition at line 451 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::insertProximityCallback | ( | const sensor_msgs::PointCloud2::ConstPtr & | cloud | ) | [virtual] |
Definition at line 174 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::insertScanProximity | ( | const tf::Point & | sensorOriginTf, |
const PCLPointCloud & | pc | ||
) | [virtual] |
Definition at line 209 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::onInit | ( | void | ) | [protected, virtual] |
Definition at line 844 of file octomap_server_contact_nodelet.cpp.
void jsk_pcl_ros::OctomapServerContact::publishAll | ( | const ros::Time & | rostime | ) | [virtual] |
Reimplemented from octomap_server::OctomapServer.
Definition at line 458 of file octomap_server_contact_nodelet.cpp.
virtual void jsk_pcl_ros::OctomapServerContact::subscribe | ( | ) | [inline, virtual] |
Definition at line 66 of file octomap_server_contact.h.
virtual void jsk_pcl_ros::OctomapServerContact::unsubscribe | ( | ) | [inline, virtual] |
Definition at line 67 of file octomap_server_contact.h.
Reimplemented from octomap_server::OctomapServer.
Definition at line 77 of file octomap_server_contact.h.
std_msgs::ColorRGBA jsk_pcl_ros::OctomapServerContact::m_colorFrontier [protected] |
Definition at line 80 of file octomap_server_contact.h.
std_msgs::ColorRGBA jsk_pcl_ros::OctomapServerContact::m_colorUnknown [protected] |
Definition at line 79 of file octomap_server_contact.h.
message_filters::Subscriber<jsk_recognition_msgs::ContactSensorArray> jsk_pcl_ros::OctomapServerContact::m_contactSensorSub [protected] |
Definition at line 75 of file octomap_server_contact.h.
Definition at line 74 of file octomap_server_contact.h.
Definition at line 74 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_maxRangeProximity [protected] |
Definition at line 87 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_occupancyMaxX [protected] |
Definition at line 90 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_occupancyMaxY [protected] |
Definition at line 92 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_occupancyMinX [protected] |
Definition at line 89 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_occupancyMinY [protected] |
Definition at line 91 of file octomap_server_contact.h.
Reimplemented from octomap_server::OctomapServer.
Definition at line 77 of file octomap_server_contact.h.
Reimplemented from octomap_server::OctomapServer.
Definition at line 77 of file octomap_server_contact.h.
Definition at line 98 of file octomap_server_contact.h.
double jsk_pcl_ros::OctomapServerContact::m_offsetVisualizeUnknown [protected] |
Definition at line 83 of file octomap_server_contact.h.
message_filters::Subscriber<sensor_msgs::PointCloud2>* jsk_pcl_ros::OctomapServerContact::m_pointProximitySub [protected] |
Definition at line 72 of file octomap_server_contact.h.
bool jsk_pcl_ros::OctomapServerContact::m_publishFrontierSpace [protected] |
Definition at line 85 of file octomap_server_contact.h.
bool jsk_pcl_ros::OctomapServerContact::m_publishUnknownSpace [protected] |
Definition at line 82 of file octomap_server_contact.h.
Reimplemented from octomap_server::OctomapServer.
Definition at line 77 of file octomap_server_contact.h.
boost::shared_ptr<robot_self_filter::SelfMaskNamedLink> jsk_pcl_ros::OctomapServerContact::m_selfMask [protected] |
Definition at line 96 of file octomap_server_contact.h.
boost::shared_ptr<tf::MessageFilter<jsk_recognition_msgs::ContactSensorArray> > jsk_pcl_ros::OctomapServerContact::m_tfContactSensorSub [protected] |
Definition at line 76 of file octomap_server_contact.h.
tf::MessageFilter<sensor_msgs::PointCloud2>* jsk_pcl_ros::OctomapServerContact::m_tfPointProximitySub [protected] |
Definition at line 73 of file octomap_server_contact.h.
Definition at line 71 of file octomap_server_contact.h.
Definition at line 71 of file octomap_server_contact.h.
bool jsk_pcl_ros::OctomapServerContact::m_useContactSurface [protected] |
Definition at line 94 of file octomap_server_contact.h.