Application to test and visualize the different type of feature detectors. More...
#include <feature_viewer.h>
Public Member Functions | |
FeatureViewer (const ros::NodeHandle &nh, const ros::NodeHandle &nh_private) | |
Constructor from ROS nodehandles. | |
virtual | ~FeatureViewer () |
Default destructor. | |
Private Member Functions | |
void | gftReconfigCallback (GftDetectorConfig &config, uint32_t level) |
ROS dynamic reconfigure callback function for GFT. | |
void | initParams () |
Initializes all the parameters from the ROS param server. | |
void | orbReconfigCallback (OrbDetectorConfig &config, uint32_t level) |
ROS dynamic reconfigure callback function for ORB. | |
void | publishFeatureCloud (RGBDFrame &frame) |
Publish the feature point cloud. | |
void | publishFeatureCovariances (RGBDFrame &frame) |
Publish the feature covariance markers. | |
void | reconfigCallback (FeatureDetectorConfig &config, uint32_t level) |
ROS dynamic reconfigure callback function. | |
void | resetDetector () |
Re-instantiates the feature detector based on the detector type parameter. | |
void | RGBDCallback (const ImageMsg::ConstPtr &rgb_msg, const ImageMsg::ConstPtr &depth_msg, const CameraInfoMsg::ConstPtr &info_msg) |
Main callback for RGB, Depth, and CameraInfo messages. | |
void | showKeypointImage (RGBDFrame &frame) |
Show the image with keypoints. | |
void | starReconfigCallback (StarDetectorConfig &config, uint32_t level) |
ROS dynamic reconfigure callback function for STAR. | |
void | surfReconfigCallback (SurfDetectorConfig &config, uint32_t level) |
ROS dynamic reconfigure callback function for SURF. | |
Private Attributes | |
ros::Publisher | cloud_publisher_ |
publisher for feature point cloud | |
FeatureDetectorConfigServer | config_server_ |
ROS dynamic reconfigure server. | |
ros::Publisher | covariances_publisher_ |
publisher for feature covariances | |
boost::shared_ptr< ImageTransport > | depth_it_ |
Image transport for depth message subscription. | |
std::string | detector_type_ |
Feature detector type parameter. | |
FeatureDetectorPtr | feature_detector_ |
The feature detector object. | |
int | frame_count_ |
RGBD frame counter. | |
GftDetectorConfigServerPtr | gft_config_server_ |
ROS dynamic reconfigure server for GFT params. | |
boost::mutex | mutex_ |
state mutex | |
ros::NodeHandle | nh_ |
the public nodehandle | |
ros::NodeHandle | nh_private_ |
the private nodehandle | |
OrbDetectorConfigServerPtr | orb_config_server_ |
ROS dynamic reconfigure server for ORB params. | |
bool | publish_cloud_ |
If true, publish the pcl feature cloud. | |
bool | publish_covariances_ |
If true, publish the covariance markers. | |
int | queue_size_ |
Subscription queue size. | |
boost::shared_ptr< ImageTransport > | rgb_it_ |
Image transport for RGB message subscription. | |
bool | show_keypoints_ |
If true, show an OpenCV window with the features. | |
StarDetectorConfigServerPtr | star_config_server_ |
ROS dynamic reconfigure server for STAR params. | |
ImageSubFilter | sub_depth_ |
Depth message subscriber. | |
CameraInfoSubFilter | sub_info_ |
Camera info message subscriber. | |
ImageSubFilter | sub_rgb_ |
RGB message subscriber. | |
SurfDetectorConfigServerPtr | surf_config_server_ |
ROS dynamic reconfigure server for SURF params. | |
boost::shared_ptr < RGBDSynchronizer3 > | sync_ |
Callback syncronizer. |
Application to test and visualize the different type of feature detectors.
Definition at line 54 of file feature_viewer.h.
ccny_rgbd::FeatureViewer::FeatureViewer | ( | const ros::NodeHandle & | nh, |
const ros::NodeHandle & | nh_private | ||
) |
Constructor from ROS nodehandles.
nh | the public nodehandle |
nh_private | the private nodehandle |
Definition at line 28 of file feature_viewer.cpp.
ccny_rgbd::FeatureViewer::~FeatureViewer | ( | ) | [virtual] |
Default destructor.
Definition at line 73 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::gftReconfigCallback | ( | GftDetectorConfig & | config, |
uint32_t | level | ||
) | [private] |
ROS dynamic reconfigure callback function for GFT.
Definition at line 307 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::initParams | ( | ) | [private] |
Initializes all the parameters from the ROS param server.
Definition at line 80 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::orbReconfigCallback | ( | OrbDetectorConfig & | config, |
uint32_t | level | ||
) | [private] |
ROS dynamic reconfigure callback function for ORB.
Definition at line 333 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::publishFeatureCloud | ( | RGBDFrame & | frame | ) | [private] |
Publish the feature point cloud.
Note: this might decrease performance
Definition at line 210 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::publishFeatureCovariances | ( | RGBDFrame & | frame | ) | [private] |
Publish the feature covariance markers.
Note: this might decrease performance
Definition at line 218 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::reconfigCallback | ( | FeatureDetectorConfig & | config, |
uint32_t | level | ||
) | [private] |
ROS dynamic reconfigure callback function.
Definition at line 287 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::resetDetector | ( | ) | [private] |
Re-instantiates the feature detector based on the detector type parameter.
Definition at line 94 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::RGBDCallback | ( | const ImageMsg::ConstPtr & | rgb_msg, |
const ImageMsg::ConstPtr & | depth_msg, | ||
const CameraInfoMsg::ConstPtr & | info_msg | ||
) | [private] |
Main callback for RGB, Depth, and CameraInfo messages.
rgb_msg | RGB message (8UC3) |
depth_msg | Depth message (16UC1, in mm) |
info_msg | CameraInfo message, applies to both RGB and depth images |
Definition at line 163 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::showKeypointImage | ( | RGBDFrame & | frame | ) | [private] |
Show the image with keypoints.
Note: this might decrease performance
Definition at line 201 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::starReconfigCallback | ( | StarDetectorConfig & | config, |
uint32_t | level | ||
) | [private] |
ROS dynamic reconfigure callback function for STAR.
Definition at line 316 of file feature_viewer.cpp.
void ccny_rgbd::FeatureViewer::surfReconfigCallback | ( | SurfDetectorConfig & | config, |
uint32_t | level | ||
) | [private] |
ROS dynamic reconfigure callback function for SURF.
Definition at line 325 of file feature_viewer.cpp.
publisher for feature point cloud
Definition at line 76 of file feature_viewer.h.
ROS dynamic reconfigure server.
Definition at line 79 of file feature_viewer.h.
publisher for feature covariances
Definition at line 77 of file feature_viewer.h.
boost::shared_ptr<ImageTransport> ccny_rgbd::FeatureViewer::depth_it_ [private] |
Image transport for depth message subscription.
Definition at line 90 of file feature_viewer.h.
std::string ccny_rgbd::FeatureViewer::detector_type_ [private] |
Feature detector type parameter.
Possible values:
Definition at line 114 of file feature_viewer.h.
The feature detector object.
Definition at line 141 of file feature_viewer.h.
int ccny_rgbd::FeatureViewer::frame_count_ [private] |
RGBD frame counter.
Definition at line 139 of file feature_viewer.h.
ROS dynamic reconfigure server for GFT params.
Definition at line 81 of file feature_viewer.h.
boost::mutex ccny_rgbd::FeatureViewer::mutex_ [private] |
state mutex
Definition at line 138 of file feature_viewer.h.
ros::NodeHandle ccny_rgbd::FeatureViewer::nh_ [private] |
the public nodehandle
Definition at line 73 of file feature_viewer.h.
the private nodehandle
Definition at line 74 of file feature_viewer.h.
ROS dynamic reconfigure server for ORB params.
Definition at line 84 of file feature_viewer.h.
bool ccny_rgbd::FeatureViewer::publish_cloud_ [private] |
If true, publish the pcl feature cloud.
Note: this might slightly decrease performance
Definition at line 128 of file feature_viewer.h.
bool ccny_rgbd::FeatureViewer::publish_covariances_ [private] |
If true, publish the covariance markers.
Note: this might decrease performance
Definition at line 134 of file feature_viewer.h.
int ccny_rgbd::FeatureViewer::queue_size_ [private] |
Subscription queue size.
Definition at line 116 of file feature_viewer.h.
boost::shared_ptr<ImageTransport> ccny_rgbd::FeatureViewer::rgb_it_ [private] |
Image transport for RGB message subscription.
Definition at line 87 of file feature_viewer.h.
bool ccny_rgbd::FeatureViewer::show_keypoints_ [private] |
If true, show an OpenCV window with the features.
Note: this might slightly decrease performance
Definition at line 122 of file feature_viewer.h.
ROS dynamic reconfigure server for STAR params.
Definition at line 82 of file feature_viewer.h.
Depth message subscriber.
Definition at line 99 of file feature_viewer.h.
Camera info message subscriber.
Definition at line 102 of file feature_viewer.h.
RGB message subscriber.
Definition at line 96 of file feature_viewer.h.
ROS dynamic reconfigure server for SURF params.
Definition at line 83 of file feature_viewer.h.
boost::shared_ptr<RGBDSynchronizer3> ccny_rgbd::FeatureViewer::sync_ [private] |
Callback syncronizer.
Definition at line 93 of file feature_viewer.h.