Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes
semanticmodel::Segmenter Class Reference

#include <segmenter.hh>

Inheritance diagram for semanticmodel::Segmenter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void convex_hulls (const vector< PointCloud::Ptr > &planes, vector< PointCloud::Ptr > &hulls)
void fit_planes (PointCloud::ConstPtr in, pcl16::PointCloud< pcl16::Normal >::ConstPtr normals, const tf::Transform &trans, vector< PointCloud::Ptr > &good_planes, vector< pcl16::ModelCoefficients > &good_models, vector< pcl16::ModelCoefficients > &bad_models)
void get_aboves (const vector< PointCloud::Ptr > &hulls, const vector< pcl16::ModelCoefficients > &coeffs, const PointCloud::Ptr &densecloud, PointCloud::Ptr &out)
void lose_bads (const PointCloud::ConstPtr &aboves, PointCloud::Ptr good_aboves, const vector< pcl16::ModelCoefficients > &bad_coeffs)
void passthrough (PointCloud::Ptr &in, PointCloud::Ptr &out)
void publish_planes (const vector< PointCloud::Ptr > &planes, const vector< PointCloud::Ptr > &hulls, const vector< pcl16::ModelCoefficients > &coeffs, vector< semanticmodel::Plane > &outputs)
void publishLatestPlanes (const ros::WallTimerEvent &e)
 Segmenter (const std::string &name_space, const std::string &cloud_input_topic, const std::string &camera_input_topic, const std::string &depth_input_topic, const std::string &planecloud_output_topic, const std::string &plane_output_topic, const std::string &object_output_topic, const std::string &plane_service_topic)
void synchronized_pipeline_callback (const sensor_msgs::ImageConstPtr &rgb_img, const sensor_msgs::CameraInfoConstPtr &rgb_info, const sensor_msgs::ImageConstPtr &depth_image, const sensor_msgs::CameraInfoConstPtr &depth_info, const PointCloud::ConstPtr &cloud)

Private Types

typedef pcl16::PointXYZRGB Point
typedef pcl16::PointCloud< PointPointCloud
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
PointCloud
Sync

Private Member Functions

void camera_cb (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
void cloud_cb (const PointCloud::ConstPtr &cloud)
void depth_cb (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
void dynamic_reconfigure_callback (const FilterConfig &config, uint32_t level)
bool isGroundPlane (const pcl16::ModelCoefficients &coeffs) const
bool isHorizontal (const pcl16::ModelCoefficients &coeffs) const
pcl16::ModelCoefficients transformCoeffs (const btTransform &trans, const pcl16::ModelCoefficients &in)

Private Attributes

boost::scoped_ptr
< tf::TransformBroadcaster
broadcaster
image_transport::CameraSubscriber cam_sub
ros::Subscriber cloud_sub
boost::shared_ptr
< pcl16::EdgeAwarePlaneComparator
< Point, pcl16::Normal > > 
comp_
FilterConfig config
boost::mutex config_mutex
image_transport::CameraSubscriber depth_sub
image_transport::ImageTransport depth_transport
dynamic_reconfigure::Server
< FilterConfig >::CallbackType 
dynparam_func
dynamic_reconfigure::Server
< FilterConfig > 
dynparam_srv
ros::NodeHandle handle
ros::Publisher latest_plane_pub_
ros::WallTimer latest_plane_timer_
boost::circular_buffer
< PointCloud::Ptr > 
latest_planes_
boost::scoped_ptr
< tf::TransformListener
listener
ros::Publisher map_points_pub
pcl16::IntegralImageNormalEstimation
< Point, pcl16::Normal > 
normal_estimator_
ros::Publisher object_pub
ros::Publisher plane_pub
pcl16::OrganizedMultiPlaneSegmentation
< Point, pcl16::Normal,
pcl16::Label > 
plane_segmenter_
ros::Publisher planecloud_pub
ros::ServiceClient planetracker_srv
int processed
image_transport::ImageTransport rgb_transport
bool short_circuit
int skipped
boost::scoped_ptr
< message_filters::Synchronizer
< Sync > > 
sync

Static Private Attributes

static const int QUEUE_SIZE = 100

Detailed Description

Definition at line 53 of file segmenter.hh.


Member Typedef Documentation

typedef pcl16::PointXYZRGB semanticmodel::Segmenter::Point [private]

Definition at line 58 of file segmenter.hh.

Definition at line 59 of file segmenter.hh.

typedef message_filters::sync_policies:: ApproximateTime<sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::Image, sensor_msgs::CameraInfo, PointCloud> semanticmodel::Segmenter::Sync [private]

Definition at line 73 of file segmenter.hh.


Constructor & Destructor Documentation

semanticmodel::Segmenter::Segmenter ( const std::string &  name_space,
const std::string &  cloud_input_topic,
const std::string &  camera_input_topic,
const std::string &  depth_input_topic,
const std::string &  planecloud_output_topic,
const std::string &  plane_output_topic,
const std::string &  object_output_topic,
const std::string &  plane_service_topic 
)

Definition at line 79 of file segmenter.cc.


Member Function Documentation

void semanticmodel::Segmenter::camera_cb ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
) [private]

Definition at line 677 of file segmenter.cc.

void semanticmodel::Segmenter::cloud_cb ( const PointCloud::ConstPtr &  cloud) [private]

Definition at line 672 of file segmenter.cc.

void semanticmodel::Segmenter::convex_hulls ( const vector< PointCloud::Ptr > &  planes,
vector< PointCloud::Ptr > &  hulls 
)

Definition at line 329 of file segmenter.cc.

void semanticmodel::Segmenter::depth_cb ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
) [private]

Definition at line 684 of file segmenter.cc.

void semanticmodel::Segmenter::dynamic_reconfigure_callback ( const FilterConfig &  config,
uint32_t  level 
) [private]

Definition at line 662 of file segmenter.cc.

void semanticmodel::Segmenter::fit_planes ( PointCloud::ConstPtr  in,
pcl16::PointCloud< pcl16::Normal >::ConstPtr  normals,
const tf::Transform trans,
vector< PointCloud::Ptr > &  good_planes,
vector< pcl16::ModelCoefficients > &  good_models,
vector< pcl16::ModelCoefficients > &  bad_models 
)

Definition at line 233 of file segmenter.cc.

void semanticmodel::Segmenter::get_aboves ( const vector< PointCloud::Ptr > &  hulls,
const vector< pcl16::ModelCoefficients > &  coeffs,
const PointCloud::Ptr &  densecloud,
PointCloud::Ptr &  out 
)

Definition at line 420 of file segmenter.cc.

Definition at line 196 of file segmenter.cc.

Definition at line 191 of file segmenter.cc.

void semanticmodel::Segmenter::lose_bads ( const PointCloud::ConstPtr &  aboves,
PointCloud::Ptr  good_aboves,
const vector< pcl16::ModelCoefficients > &  bad_coeffs 
)

Definition at line 459 of file segmenter.cc.

void semanticmodel::Segmenter::passthrough ( PointCloud::Ptr &  in,
PointCloud::Ptr &  out 
)

Definition at line 182 of file segmenter.cc.

void semanticmodel::Segmenter::publish_planes ( const vector< PointCloud::Ptr > &  planes,
const vector< PointCloud::Ptr > &  hulls,
const vector< pcl16::ModelCoefficients > &  coeffs,
vector< semanticmodel::Plane > &  outputs 
)

Definition at line 343 of file segmenter.cc.

Definition at line 484 of file segmenter.cc.

void semanticmodel::Segmenter::synchronized_pipeline_callback ( const sensor_msgs::ImageConstPtr &  rgb_img,
const sensor_msgs::CameraInfoConstPtr &  rgb_info,
const sensor_msgs::ImageConstPtr &  depth_image,
const sensor_msgs::CameraInfoConstPtr &  depth_info,
const PointCloud::ConstPtr &  cloud 
)

Definition at line 496 of file segmenter.cc.

Definition at line 203 of file segmenter.cc.


Member Data Documentation

Definition at line 205 of file segmenter.hh.

Definition at line 221 of file segmenter.hh.

Definition at line 219 of file segmenter.hh.

boost::shared_ptr<pcl16::EdgeAwarePlaneComparator<Point, pcl16::Normal> > semanticmodel::Segmenter::comp_ [private]

Definition at line 252 of file segmenter.hh.

FilterConfig semanticmodel::Segmenter::config [private]

Definition at line 183 of file segmenter.hh.

Definition at line 186 of file segmenter.hh.

Definition at line 223 of file segmenter.hh.

Definition at line 222 of file segmenter.hh.

Definition at line 185 of file segmenter.hh.

Definition at line 184 of file segmenter.hh.

Definition at line 180 of file segmenter.hh.

Definition at line 238 of file segmenter.hh.

Definition at line 256 of file segmenter.hh.

boost::circular_buffer<PointCloud::Ptr> semanticmodel::Segmenter::latest_planes_ [private]

Definition at line 255 of file segmenter.hh.

Definition at line 204 of file segmenter.hh.

Definition at line 234 of file segmenter.hh.

pcl16::IntegralImageNormalEstimation<Point, pcl16::Normal> semanticmodel::Segmenter::normal_estimator_ [private]

Definition at line 248 of file segmenter.hh.

Definition at line 237 of file segmenter.hh.

Definition at line 236 of file segmenter.hh.

pcl16::OrganizedMultiPlaneSegmentation<Point, pcl16::Normal, pcl16::Label> semanticmodel::Segmenter::plane_segmenter_ [private]

Definition at line 245 of file segmenter.hh.

Definition at line 235 of file segmenter.hh.

Definition at line 241 of file segmenter.hh.

Definition at line 264 of file segmenter.hh.

const int semanticmodel::Segmenter::QUEUE_SIZE = 100 [static, private]

Definition at line 177 of file segmenter.hh.

Definition at line 220 of file segmenter.hh.

Definition at line 261 of file segmenter.hh.

Definition at line 265 of file segmenter.hh.

Definition at line 209 of file segmenter.hh.


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


semanticmodel
Author(s): Julian ("Mac") Mason
autogenerated on Thu Dec 12 2013 12:39:10