| Public Member Functions | |
| void | callback (const sensor_msgs::ImageConstPtr &img_msg, const sensor_msgs::ImageConstPtr &depth_msg) | 
| DepthSaliencyNode (ros::NodeHandle &n) | |
| void | spin () | 
| cv::Mat | upSampleResponse (cv::Mat &m_s, int s, cv::Size size0) | 
| Protected Attributes | |
| cpl_visual_features::CenterSurroundMapper | csm | 
| message_filters::Subscriber < sensor_msgs::Image > | depth_sub_ | 
| message_filters::Subscriber < sensor_msgs::Image > | image_sub_ | 
| int | img_count_ | 
| ros::NodeHandle | n_ | 
| message_filters::Synchronizer < MySyncPolicy > | sync_ | 
Definition at line 61 of file depth_saliency_node.cpp.
| DepthSaliencyNode::DepthSaliencyNode | ( | ros::NodeHandle & | n | ) |  [inline] | 
Definition at line 64 of file depth_saliency_node.cpp.
| void DepthSaliencyNode::callback | ( | const sensor_msgs::ImageConstPtr & | img_msg, | 
| const sensor_msgs::ImageConstPtr & | depth_msg | ||
| ) |  [inline] | 
Definition at line 76 of file depth_saliency_node.cpp.
| void DepthSaliencyNode::spin | ( | ) |  [inline] | 
Executive control function for launching the node.
Definition at line 168 of file depth_saliency_node.cpp.
| cv::Mat DepthSaliencyNode::upSampleResponse | ( | cv::Mat & | m_s, | 
| int | s, | ||
| cv::Size | size0 | ||
| ) |  [inline] | 
Definition at line 135 of file depth_saliency_node.cpp.
Definition at line 182 of file depth_saliency_node.cpp.
| message_filters::Subscriber<sensor_msgs::Image> DepthSaliencyNode::depth_sub_  [protected] | 
Definition at line 180 of file depth_saliency_node.cpp.
| message_filters::Subscriber<sensor_msgs::Image> DepthSaliencyNode::image_sub_  [protected] | 
Definition at line 179 of file depth_saliency_node.cpp.
| int DepthSaliencyNode::img_count_  [protected] | 
Definition at line 184 of file depth_saliency_node.cpp.
| ros::NodeHandle DepthSaliencyNode::n_  [protected] | 
Definition at line 178 of file depth_saliency_node.cpp.
Definition at line 181 of file depth_saliency_node.cpp.