#include <border_estimator.h>
|
| virtual void | computeBorder (const pcl::RangeImage &image, const std_msgs::Header &header) |
| |
| virtual void | configCallback (Config &config, uint32_t level) |
| |
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::CameraInfo::ConstPtr &caminfo) |
| |
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &msg) |
| |
| virtual void | onInit () |
| |
| virtual void | publishCloud (ros::Publisher &pub, const pcl::PointIndices &inlier, const std_msgs::Header &header) |
| |
| virtual void | subscribe () |
| |
| virtual void | unsubscribe () |
| |
| ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size) |
| |
| image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
| |
| image_transport::CameraPublisher | advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
| |
| image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size) |
| |
| image_transport::Publisher | advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size) |
| |
| virtual void | cameraConnectionBaseCallback () |
| |
| virtual void | cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
| |
| virtual void | cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub) |
| |
| virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
| |
| virtual void | imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
| |
| virtual bool | isSubscribed () |
| |
| virtual void | onInitPostProcess () |
| |
| virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) |
| |
| virtual void | warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event) |
| |
| ros::CallbackQueueInterface & | getMTCallbackQueue () const |
| |
| ros::NodeHandle & | getMTNodeHandle () const |
| |
| ros::NodeHandle & | getMTPrivateNodeHandle () const |
| |
| const V_string & | getMyArgv () const |
| |
| const std::string & | getName () const |
| |
| ros::NodeHandle & | getNodeHandle () const |
| |
| ros::NodeHandle & | getPrivateNodeHandle () const |
| |
| const M_string & | getRemappingArgs () const |
| |
| ros::CallbackQueueInterface & | getSTCallbackQueue () const |
| |
| std::string | getSuffixedName (const std::string &suffix) const |
| |
Definition at line 59 of file border_estimator.h.
| void jsk_pcl_ros::BorderEstimator::computeBorder |
( |
const pcl::RangeImage & |
image, |
|
|
const std_msgs::Header & |
header |
|
) |
| |
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::estimate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const sensor_msgs::CameraInfo::ConstPtr & |
caminfo |
|
) |
| |
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::estimate |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::onInit |
( |
void |
| ) |
|
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::subscribe |
( |
| ) |
|
|
protectedvirtual |
| void jsk_pcl_ros::BorderEstimator::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
| double jsk_pcl_ros::BorderEstimator::angular_resolution_ |
|
protected |
| int jsk_pcl_ros::BorderEstimator::border_size_ |
|
protected |
| double jsk_pcl_ros::BorderEstimator::max_angle_height_ |
|
protected |
| double jsk_pcl_ros::BorderEstimator::max_angle_width_ |
|
protected |
| double jsk_pcl_ros::BorderEstimator::min_range_ |
|
protected |
| double jsk_pcl_ros::BorderEstimator::noise_level_ |
|
protected |
The documentation for this class was generated from the following files: