Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
hector_barrel_detection_nodelet::BarrelDetection Class Reference

#include <hector_barrel_detection_nodelet.h>

Inheritance diagram for hector_barrel_detection_nodelet::BarrelDetection:
Inheritance graph
[legend]

Public Member Functions

 BarrelDetection ()
 
virtual void onInit ()
 
virtual ~BarrelDetection ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

void findCylinder (const sensor_msgs::PointCloud2::ConstPtr &pc_msg, float xKey, float yKey, const geometry_msgs::PointStamped cut_around_keypoint)
 
void imageCallback (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
 
void PclCallback (const sensor_msgs::PointCloud2::ConstPtr &pc_msg)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Private Types

typedef boost::shared_ptr< image_geometry::PinholeCameraModelCameraModelPtr
 

Private Member Functions

void dynamic_recf_cb (hector_barrel_detection_nodelet::BarrelDetectionConfig &config, uint32_t level)
 
void publish_rectangle_for_recf (std::vector< cv::KeyPoint > keypoints, const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info, cv::Mat &img_filtered)
 

Private Attributes

ros::Publisher barrel_marker_publisher_
 
image_transport::CameraPublisher black_white_image_pub_
 
double bluePart
 
ros::Publisher cloud_filtered_publisher_
 
sensor_msgs::PointCloud2::ConstPtr current_pc_msg_
 
ros::Publisher debug_imagePoint_pub_
 
dynamic_reconfigure::Server< hector_barrel_detection_nodelet::BarrelDetectionConfig > dynamic_recf_server
 
dynamic_reconfigure::Server< hector_barrel_detection_nodelet::BarrelDetectionConfig >::CallbackType dynamic_recf_type
 
int h_max
 
int h_min
 
image_transport::CameraSubscriber image_sub
 
ros::Publisher imagePercept_pub_
 
tf::TransformListener listener_
 
double maxRadius
 
double minRadius
 
pcl::PassThrough< pcl::PointXYZ > pass_
 
ros::Publisher pcl_debug_pub_
 
ros::Subscriber pcl_sub
 
ros::Publisher pose_publisher_
 
ros::Publisher posePercept_pub_
 
image_transport::CameraPublisher pub_imageDetection
 
int s_max
 
int s_min
 
Eigen::Affine3d to_map_
 
int v_max
 
int v_min
 
ros::ServiceClient worldmodel_srv_client_
 

Detailed Description

Definition at line 50 of file hector_barrel_detection_nodelet.h.

Member Typedef Documentation

Definition at line 63 of file hector_barrel_detection_nodelet.h.

Constructor & Destructor Documentation

hector_barrel_detection_nodelet::BarrelDetection::BarrelDetection ( )

Definition at line 7 of file hector_barrel_detection_nodelet.cpp.

hector_barrel_detection_nodelet::BarrelDetection::~BarrelDetection ( )
virtual

Definition at line 10 of file hector_barrel_detection_nodelet.cpp.

Member Function Documentation

void hector_barrel_detection_nodelet::BarrelDetection::dynamic_recf_cb ( hector_barrel_detection_nodelet::BarrelDetectionConfig &  config,
uint32_t  level 
)
private

Definition at line 448 of file hector_barrel_detection_nodelet.cpp.

void hector_barrel_detection_nodelet::BarrelDetection::findCylinder ( const sensor_msgs::PointCloud2::ConstPtr &  pc_msg,
float  xKey,
float  yKey,
const geometry_msgs::PointStamped  cut_around_keypoint 
)
protected

Definition at line 192 of file hector_barrel_detection_nodelet.cpp.

void hector_barrel_detection_nodelet::BarrelDetection::imageCallback ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
)
protected

Definition at line 49 of file hector_barrel_detection_nodelet.cpp.

void hector_barrel_detection_nodelet::BarrelDetection::onInit ( )
virtual

Implements nodelet::Nodelet.

Definition at line 13 of file hector_barrel_detection_nodelet.cpp.

void hector_barrel_detection_nodelet::BarrelDetection::PclCallback ( const sensor_msgs::PointCloud2::ConstPtr &  pc_msg)
protected

Definition at line 187 of file hector_barrel_detection_nodelet.cpp.

void hector_barrel_detection_nodelet::BarrelDetection::publish_rectangle_for_recf ( std::vector< cv::KeyPoint >  keypoints,
const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info,
cv::Mat &  img_filtered 
)
private

Definition at line 397 of file hector_barrel_detection_nodelet.cpp.

Member Data Documentation

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::barrel_marker_publisher_
private

Definition at line 69 of file hector_barrel_detection_nodelet.h.

image_transport::CameraPublisher hector_barrel_detection_nodelet::BarrelDetection::black_white_image_pub_
private

Definition at line 79 of file hector_barrel_detection_nodelet.h.

double hector_barrel_detection_nodelet::BarrelDetection::bluePart
private

Definition at line 96 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::cloud_filtered_publisher_
private

Definition at line 67 of file hector_barrel_detection_nodelet.h.

sensor_msgs::PointCloud2::ConstPtr hector_barrel_detection_nodelet::BarrelDetection::current_pc_msg_
private

Definition at line 81 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::debug_imagePoint_pub_
private

Definition at line 77 of file hector_barrel_detection_nodelet.h.

dynamic_reconfigure::Server<hector_barrel_detection_nodelet::BarrelDetectionConfig> hector_barrel_detection_nodelet::BarrelDetection::dynamic_recf_server
private

Definition at line 84 of file hector_barrel_detection_nodelet.h.

dynamic_reconfigure::Server<hector_barrel_detection_nodelet::BarrelDetectionConfig>::CallbackType hector_barrel_detection_nodelet::BarrelDetection::dynamic_recf_type
private

Definition at line 85 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::h_max
private

Definition at line 95 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::h_min
private

Definition at line 94 of file hector_barrel_detection_nodelet.h.

image_transport::CameraSubscriber hector_barrel_detection_nodelet::BarrelDetection::image_sub
private

Definition at line 66 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::imagePercept_pub_
private

Definition at line 70 of file hector_barrel_detection_nodelet.h.

tf::TransformListener hector_barrel_detection_nodelet::BarrelDetection::listener_
private

Definition at line 73 of file hector_barrel_detection_nodelet.h.

double hector_barrel_detection_nodelet::BarrelDetection::maxRadius
private

Definition at line 98 of file hector_barrel_detection_nodelet.h.

double hector_barrel_detection_nodelet::BarrelDetection::minRadius
private

Definition at line 97 of file hector_barrel_detection_nodelet.h.

pcl::PassThrough<pcl::PointXYZ> hector_barrel_detection_nodelet::BarrelDetection::pass_
private

Definition at line 75 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::pcl_debug_pub_
private

Definition at line 78 of file hector_barrel_detection_nodelet.h.

ros::Subscriber hector_barrel_detection_nodelet::BarrelDetection::pcl_sub
private

Definition at line 65 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::pose_publisher_
private

Definition at line 68 of file hector_barrel_detection_nodelet.h.

ros::Publisher hector_barrel_detection_nodelet::BarrelDetection::posePercept_pub_
private

Definition at line 71 of file hector_barrel_detection_nodelet.h.

image_transport::CameraPublisher hector_barrel_detection_nodelet::BarrelDetection::pub_imageDetection
private

Definition at line 87 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::s_max
private

Definition at line 93 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::s_min
private

Definition at line 92 of file hector_barrel_detection_nodelet.h.

Eigen::Affine3d hector_barrel_detection_nodelet::BarrelDetection::to_map_
private

Definition at line 74 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::v_max
private

Definition at line 91 of file hector_barrel_detection_nodelet.h.

int hector_barrel_detection_nodelet::BarrelDetection::v_min
private

Definition at line 90 of file hector_barrel_detection_nodelet.h.

ros::ServiceClient hector_barrel_detection_nodelet::BarrelDetection::worldmodel_srv_client_
private

Definition at line 72 of file hector_barrel_detection_nodelet.h.


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


hector_barrel_detection_nodelet
Author(s):
autogenerated on Mon Jun 10 2019 13:36:28