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

#include <pointcloud_moveit_filter.h>

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

Public Member Functions

virtual ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape)
 
virtual void forgetShape (ShapeHandle handle)
 
virtual bool initialize ()
 
 PointCloudMoveitFilter ()
 
virtual bool setParams (XmlRpc::XmlRpcValue &params)
 
virtual void start ()
 
virtual void stop ()
 
virtual ~PointCloudMoveitFilter ()
 
- Public Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
const std::stringgetType () const
 
 OccupancyMapUpdater (const std::string &type)
 
void publishDebugInformation (bool flag)
 
void setMonitor (OccupancyMapMonitor *monitor)
 
void setTransformCacheCallback (const TransformCacheProvider &transform_callback)
 
virtual ~OccupancyMapUpdater ()
 

Protected Member Functions

template<typename PointT >
void cloudMsgCallback (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
 
virtual bool getShapeTransform (ShapeHandle h, Eigen::Affine3d &transform) const
 
virtual void stopHelper ()
 
- Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
bool updateTransformCache (const std::string &target_frame, const ros::Time &target_time)
 

Protected Attributes

ros::Publisher filtered_cloud_publisher_
 
std::string filtered_cloud_topic_
 
bool keep_organized_
 
std::vector< int > mask_
 
double max_range_
 
double padding_
 
tf::MessageFilter< sensor_msgs::PointCloud2 > * point_cloud_filter_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > * point_cloud_subscriber_
 
std::string point_cloud_topic_
 
unsigned int point_subsample_
 
ros::NodeHandle private_nh_
 
ros::NodeHandle root_nh_
 
double scale_
 
boost::scoped_ptr< point_containment_filter::ShapeMaskshape_mask_
 
boost::shared_ptr< tf::Transformertf_
 
bool use_color_
 
- Protected Attributes inherited from occupancy_map_monitor::OccupancyMapUpdater
bool debug_info_
 
OccupancyMapMonitormonitor_
 
ShapeTransformCache transform_cache_
 
TransformCacheProvider transform_provider_callback_
 
OccMapTreePtr tree_
 
std::string type_
 

Additional Inherited Members

- Static Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, double *value)
 
static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, unsigned int *value)
 

Detailed Description

Definition at line 64 of file pointcloud_moveit_filter.h.

Constructor & Destructor Documentation

jsk_pcl_ros::PointCloudMoveitFilter::PointCloudMoveitFilter ( )

Definition at line 40 of file pointcloud_moveit_filter.cpp.

jsk_pcl_ros::PointCloudMoveitFilter::~PointCloudMoveitFilter ( )
virtual

Definition at line 54 of file pointcloud_moveit_filter.cpp.

Member Function Documentation

template<typename PointT >
void jsk_pcl_ros::PointCloudMoveitFilter::cloudMsgCallback ( const sensor_msgs::PointCloud2::ConstPtr &  cloud_msg)
inlineprotected

Definition at line 87 of file pointcloud_moveit_filter.h.

ShapeHandle jsk_pcl_ros::PointCloudMoveitFilter::excludeShape ( const shapes::ShapeConstPtr shape)
virtual
void jsk_pcl_ros::PointCloudMoveitFilter::forgetShape ( ShapeHandle  handle)
virtual
bool jsk_pcl_ros::PointCloudMoveitFilter::getShapeTransform ( ShapeHandle  h,
Eigen::Affine3d &  transform 
) const
protectedvirtual

Definition at line 109 of file pointcloud_moveit_filter.cpp.

bool jsk_pcl_ros::PointCloudMoveitFilter::initialize ( )
virtual
bool jsk_pcl_ros::PointCloudMoveitFilter::setParams ( XmlRpc::XmlRpcValue params)
virtual
void jsk_pcl_ros::PointCloudMoveitFilter::start ( void  )
virtual
void jsk_pcl_ros::PointCloudMoveitFilter::stop ( void  )
virtual
void jsk_pcl_ros::PointCloudMoveitFilter::stopHelper ( )
protectedvirtual

Definition at line 191 of file pointcloud_moveit_filter.cpp.

Member Data Documentation

ros::Publisher jsk_pcl_ros::PointCloudMoveitFilter::filtered_cloud_publisher_
protected

Definition at line 190 of file pointcloud_moveit_filter.h.

std::string jsk_pcl_ros::PointCloudMoveitFilter::filtered_cloud_topic_
protected

Definition at line 189 of file pointcloud_moveit_filter.h.

bool jsk_pcl_ros::PointCloudMoveitFilter::keep_organized_
protected

Definition at line 203 of file pointcloud_moveit_filter.h.

std::vector<int> jsk_pcl_ros::PointCloudMoveitFilter::mask_
protected

Definition at line 200 of file pointcloud_moveit_filter.h.

double jsk_pcl_ros::PointCloudMoveitFilter::max_range_
protected

Definition at line 187 of file pointcloud_moveit_filter.h.

double jsk_pcl_ros::PointCloudMoveitFilter::padding_
protected

Definition at line 186 of file pointcloud_moveit_filter.h.

tf::MessageFilter<sensor_msgs::PointCloud2>* jsk_pcl_ros::PointCloudMoveitFilter::point_cloud_filter_
protected

Definition at line 196 of file pointcloud_moveit_filter.h.

message_filters::Subscriber<sensor_msgs::PointCloud2>* jsk_pcl_ros::PointCloudMoveitFilter::point_cloud_subscriber_
protected

Definition at line 192 of file pointcloud_moveit_filter.h.

std::string jsk_pcl_ros::PointCloudMoveitFilter::point_cloud_topic_
protected

Definition at line 184 of file pointcloud_moveit_filter.h.

unsigned int jsk_pcl_ros::PointCloudMoveitFilter::point_subsample_
protected

Definition at line 188 of file pointcloud_moveit_filter.h.

ros::NodeHandle jsk_pcl_ros::PointCloudMoveitFilter::private_nh_
protected

Definition at line 178 of file pointcloud_moveit_filter.h.

ros::NodeHandle jsk_pcl_ros::PointCloudMoveitFilter::root_nh_
protected

Definition at line 177 of file pointcloud_moveit_filter.h.

double jsk_pcl_ros::PointCloudMoveitFilter::scale_
protected

Definition at line 185 of file pointcloud_moveit_filter.h.

boost::scoped_ptr<point_containment_filter::ShapeMask> jsk_pcl_ros::PointCloudMoveitFilter::shape_mask_
protected

Definition at line 199 of file pointcloud_moveit_filter.h.

boost::shared_ptr<tf::Transformer> jsk_pcl_ros::PointCloudMoveitFilter::tf_
protected

Definition at line 182 of file pointcloud_moveit_filter.h.

bool jsk_pcl_ros::PointCloudMoveitFilter::use_color_
protected

Definition at line 202 of file pointcloud_moveit_filter.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:48