Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::OctomapServerContact Class Reference

#include <octomap_server_contact.h>

Inheritance diagram for jsk_pcl_ros::OctomapServerContact:
Inheritance graph
[legend]

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)
 

Protected Attributes

ros::ServiceServer m_clearBBXService
 
std_msgs::ColorRGBA m_colorFrontier
 
std_msgs::ColorRGBA m_colorUnknown
 
message_filters::Subscriber< jsk_recognition_msgs::ContactSensorArray > m_contactSensorSub
 
ros::Publisher m_fromarkerPub
 
ros::Publisher m_frontierPointCloudPub
 
double m_maxRangeProximity
 
double m_occupancyMaxX
 
double m_occupancyMaxY
 
double m_occupancyMinX
 
double m_occupancyMinY
 
ros::ServiceServer m_octomapBinaryService
 
ros::ServiceServer m_octomapFullService
 
octomap::OcTreeContactm_octreeContact
 
double m_offsetVisualizeUnknown
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointProximitySub
 
bool m_publishFrontierSpace
 
bool m_publishUnknownSpace
 
ros::ServiceServer m_resetService
 
boost::shared_ptr< robot_self_filter::SelfMaskNamedLinkm_selfMask
 
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::ContactSensorArray > > m_tfContactSensorSub
 
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointProximitySub
 
ros::Publisher m_umarkerPub
 
ros::Publisher m_unknownPointCloudPub
 
bool m_useContactSurface
 
- Protected Attributes inherited from octomap_server::OctomapServer
std::string m_baseFrameId
 
ros::Publisher m_binaryMapPub
 
ros::ServiceServer m_clearBBXService
 
ros::Publisher m_cmapPub
 
ros::Publisher m_collisionObjectPub
 
std_msgs::ColorRGBA m_color
 
double m_colorFactor
 
std_msgs::ColorRGBA m_colorFree
 
bool m_compressMap
 
boost::recursive_mutex m_config_mutex
 
bool m_filterGroundPlane
 
bool m_filterSpeckles
 
ros::Publisher m_fmapPub
 
ros::Publisher m_fmarkerPub
 
ros::Publisher m_fullMapPub
 
nav_msgs::OccupancyGrid m_gridmap
 
double m_groundFilterAngle
 
double m_groundFilterDistance
 
double m_groundFilterPlaneDistance
 
bool m_incrementalUpdate
 
bool m_initConfig
 
octomap::KeyRay m_keyRay
 
bool m_latchedTopics
 
bool m_mapOriginChanged
 
ros::Publisher m_mapPub
 
ros::Publisher m_markerPub
 
double m_maxRange
 
unsigned m_maxTreeDepth
 
double m_minRange
 
double m_minSizeX
 
double m_minSizeY
 
unsigned m_multires2DScale
 
ros::NodeHandle m_nh
 
ros::NodeHandle m_nh_private
 
double m_occupancyMaxZ
 
double m_occupancyMinZ
 
ros::ServiceServer m_octomapBinaryService
 
ros::ServiceServer m_octomapFullService
 
OcTreeTm_octree
 
octomap::OcTreeKey m_paddedMinKey
 
double m_pointcloudMaxX
 
double m_pointcloudMaxY
 
double m_pointcloudMaxZ
 
double m_pointcloudMinX
 
double m_pointcloudMinY
 
double m_pointcloudMinZ
 
ros::Publisher m_pointCloudPub
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointCloudSub
 
bool m_projectCompleteMap
 
bool m_publish2DMap
 
bool m_publishFreeSpace
 
dynamic_reconfigure::Server< OctomapServerConfig > m_reconfigureServer
 
double m_res
 
ros::ServiceServer m_resetService
 
tf::TransformListener m_tfListener
 
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointCloudSub
 
unsigned m_treeDepth
 
octomap::OcTreeKey m_updateBBXMax
 
octomap::OcTreeKey m_updateBBXMin
 
bool m_useColoredMap
 
bool m_useHeightMap
 
std::string m_worldFrameId
 

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)
 

Detailed Description

Definition at line 52 of file octomap_server_contact.h.

Constructor & Destructor Documentation

◆ OctomapServerContact()

jsk_pcl_ros::OctomapServerContact::OctomapServerContact ( const ros::NodeHandle privateNh = ros::NodeHandle("~"))

Definition at line 45 of file octomap_server_contact_nodelet.cpp.

◆ ~OctomapServerContact()

jsk_pcl_ros::OctomapServerContact::~OctomapServerContact ( )
virtual

Definition at line 118 of file octomap_server_contact_nodelet.cpp.

Member Function Documentation

◆ initContactSensor()

void jsk_pcl_ros::OctomapServerContact::initContactSensor ( const ros::NodeHandle privateNh)
virtual

Definition at line 121 of file octomap_server_contact_nodelet.cpp.

◆ insertContactSensor()

void jsk_pcl_ros::OctomapServerContact::insertContactSensor ( const jsk_recognition_msgs::ContactSensorArray::ConstPtr &  msg)
virtual

Definition at line 315 of file octomap_server_contact_nodelet.cpp.

◆ insertContactSensorCallback()

void jsk_pcl_ros::OctomapServerContact::insertContactSensorCallback ( const jsk_recognition_msgs::ContactSensorArray::ConstPtr &  msg)
virtual

Definition at line 459 of file octomap_server_contact_nodelet.cpp.

◆ insertProximityCallback()

void jsk_pcl_ros::OctomapServerContact::insertProximityCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud)
virtual

Definition at line 174 of file octomap_server_contact_nodelet.cpp.

◆ insertScanProximity()

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.

◆ onInit()

void jsk_pcl_ros::OctomapServerContact::onInit ( )
protectedvirtual

Definition at line 852 of file octomap_server_contact_nodelet.cpp.

◆ publishAll()

void jsk_pcl_ros::OctomapServerContact::publishAll ( const ros::Time rostime)
virtual

Reimplemented from octomap_server::OctomapServer.

Definition at line 466 of file octomap_server_contact_nodelet.cpp.

◆ subscribe()

virtual void jsk_pcl_ros::OctomapServerContact::subscribe ( )
inlinevirtual

Definition at line 66 of file octomap_server_contact.h.

◆ unsubscribe()

virtual void jsk_pcl_ros::OctomapServerContact::unsubscribe ( )
inlinevirtual

Definition at line 67 of file octomap_server_contact.h.

Member Data Documentation

◆ m_clearBBXService

ros::ServiceServer jsk_pcl_ros::OctomapServerContact::m_clearBBXService
protected

Definition at line 77 of file octomap_server_contact.h.

◆ m_colorFrontier

std_msgs::ColorRGBA jsk_pcl_ros::OctomapServerContact::m_colorFrontier
protected

Definition at line 80 of file octomap_server_contact.h.

◆ m_colorUnknown

std_msgs::ColorRGBA jsk_pcl_ros::OctomapServerContact::m_colorUnknown
protected

Definition at line 79 of file octomap_server_contact.h.

◆ m_contactSensorSub

message_filters::Subscriber<jsk_recognition_msgs::ContactSensorArray> jsk_pcl_ros::OctomapServerContact::m_contactSensorSub
protected

Definition at line 75 of file octomap_server_contact.h.

◆ m_fromarkerPub

ros::Publisher jsk_pcl_ros::OctomapServerContact::m_fromarkerPub
protected

Definition at line 74 of file octomap_server_contact.h.

◆ m_frontierPointCloudPub

ros::Publisher jsk_pcl_ros::OctomapServerContact::m_frontierPointCloudPub
protected

Definition at line 74 of file octomap_server_contact.h.

◆ m_maxRangeProximity

double jsk_pcl_ros::OctomapServerContact::m_maxRangeProximity
protected

Definition at line 87 of file octomap_server_contact.h.

◆ m_occupancyMaxX

double jsk_pcl_ros::OctomapServerContact::m_occupancyMaxX
protected

Definition at line 90 of file octomap_server_contact.h.

◆ m_occupancyMaxY

double jsk_pcl_ros::OctomapServerContact::m_occupancyMaxY
protected

Definition at line 92 of file octomap_server_contact.h.

◆ m_occupancyMinX

double jsk_pcl_ros::OctomapServerContact::m_occupancyMinX
protected

Definition at line 89 of file octomap_server_contact.h.

◆ m_occupancyMinY

double jsk_pcl_ros::OctomapServerContact::m_occupancyMinY
protected

Definition at line 91 of file octomap_server_contact.h.

◆ m_octomapBinaryService

ros::ServiceServer jsk_pcl_ros::OctomapServerContact::m_octomapBinaryService
protected

Definition at line 77 of file octomap_server_contact.h.

◆ m_octomapFullService

ros::ServiceServer jsk_pcl_ros::OctomapServerContact::m_octomapFullService
protected

Definition at line 77 of file octomap_server_contact.h.

◆ m_octreeContact

octomap::OcTreeContact* jsk_pcl_ros::OctomapServerContact::m_octreeContact
protected

Definition at line 98 of file octomap_server_contact.h.

◆ m_offsetVisualizeUnknown

double jsk_pcl_ros::OctomapServerContact::m_offsetVisualizeUnknown
protected

Definition at line 83 of file octomap_server_contact.h.

◆ m_pointProximitySub

message_filters::Subscriber<sensor_msgs::PointCloud2>* jsk_pcl_ros::OctomapServerContact::m_pointProximitySub
protected

Definition at line 72 of file octomap_server_contact.h.

◆ m_publishFrontierSpace

bool jsk_pcl_ros::OctomapServerContact::m_publishFrontierSpace
protected

Definition at line 85 of file octomap_server_contact.h.

◆ m_publishUnknownSpace

bool jsk_pcl_ros::OctomapServerContact::m_publishUnknownSpace
protected

Definition at line 82 of file octomap_server_contact.h.

◆ m_resetService

ros::ServiceServer jsk_pcl_ros::OctomapServerContact::m_resetService
protected

Definition at line 77 of file octomap_server_contact.h.

◆ m_selfMask

boost::shared_ptr<robot_self_filter::SelfMaskNamedLink> jsk_pcl_ros::OctomapServerContact::m_selfMask
protected

Definition at line 96 of file octomap_server_contact.h.

◆ m_tfContactSensorSub

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.

◆ m_tfPointProximitySub

tf::MessageFilter<sensor_msgs::PointCloud2>* jsk_pcl_ros::OctomapServerContact::m_tfPointProximitySub
protected

Definition at line 73 of file octomap_server_contact.h.

◆ m_umarkerPub

ros::Publisher jsk_pcl_ros::OctomapServerContact::m_umarkerPub
protected

Definition at line 71 of file octomap_server_contact.h.

◆ m_unknownPointCloudPub

ros::Publisher jsk_pcl_ros::OctomapServerContact::m_unknownPointCloudPub
protected

Definition at line 71 of file octomap_server_contact.h.

◆ m_useContactSurface

bool jsk_pcl_ros::OctomapServerContact::m_useContactSurface
protected

Definition at line 94 of file octomap_server_contact.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46