Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes
opencv_apps::LKFlowNodelet Class Reference
Inheritance diagram for opencv_apps::LKFlowNodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void onInit ()
 Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.

Private Types

typedef opencv_apps::LKFlowConfig Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer

Private Member Functions

bool deletePointsCb (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void doWork (const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
const std::string & frameWithDefault (const std::string &frame, const std::string &image_frame)
void imageCallback (const sensor_msgs::ImageConstPtr &msg)
void imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
bool initializePointsCb (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void reconfigureCallback (Config &new_config, uint32_t level)
void subscribe ()
 This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
bool toggleNightModeCb (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
void unsubscribe ()
 This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.

Static Private Member Functions

static void trackbarCallback (int, void *)

Private Attributes

bool addRemovePt
int block_size_
image_transport::CameraSubscriber cam_sub_
Config config_
bool debug_view_
ros::ServiceServer delete_points_service_
cv::Mat gray
float harris_k_
image_transport::Publisher img_pub_
image_transport::Subscriber img_sub_
ros::ServiceServer initialize_points_service_
boost::shared_ptr
< image_transport::ImageTransport
it_
int MAX_COUNT
int min_distance_
ros::Publisher msg_pub_
bool needToInit
bool nightMode
cv::Point2f point
std::vector< cv::Point2f > points [2]
ros::Time prev_stamp_
cv::Mat prevGray
float quality_level_
int queue_size_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
ros::ServiceServer toggle_night_mode_service_
std::string window_name_

Static Private Attributes

static bool need_config_update_ = false

Detailed Description

Definition at line 58 of file lk_flow_nodelet.cpp.


Member Typedef Documentation

typedef opencv_apps::LKFlowConfig opencv_apps::LKFlowNodelet::Config [private]

Definition at line 70 of file lk_flow_nodelet.cpp.

typedef dynamic_reconfigure::Server<Config> opencv_apps::LKFlowNodelet::ReconfigureServer [private]

Definition at line 71 of file lk_flow_nodelet.cpp.


Member Function Documentation

bool opencv_apps::LKFlowNodelet::deletePointsCb ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [inline, private]

Definition at line 284 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::doWork ( const sensor_msgs::ImageConstPtr &  msg,
const std::string &  input_frame_from_msg 
) [inline, private]

Create Trackbars for Thresholds

Definition at line 135 of file lk_flow_nodelet.cpp.

const std::string& opencv_apps::LKFlowNodelet::frameWithDefault ( const std::string &  frame,
const std::string &  image_frame 
) [inline, private]

Definition at line 104 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::imageCallback ( const sensor_msgs::ImageConstPtr &  msg) [inline, private]

Definition at line 116 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::imageCallbackWithInfo ( const sensor_msgs::ImageConstPtr &  msg,
const sensor_msgs::CameraInfoConstPtr &  cam_info 
) [inline, private]

Definition at line 111 of file lk_flow_nodelet.cpp.

bool opencv_apps::LKFlowNodelet::initializePointsCb ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [inline, private]

Definition at line 278 of file lk_flow_nodelet.cpp.

virtual void opencv_apps::LKFlowNodelet::onInit ( ) [inline, virtual]

Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.

Reimplemented from opencv_apps::Nodelet.

Reimplemented in lk_flow::LKFlowNodelet.

Definition at line 314 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::reconfigureCallback ( Config new_config,
uint32_t  level 
) [inline, private]

Definition at line 95 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::subscribe ( ) [inline, private, virtual]

This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.

Implements opencv_apps::Nodelet.

Definition at line 297 of file lk_flow_nodelet.cpp.

bool opencv_apps::LKFlowNodelet::toggleNightModeCb ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
) [inline, private]

Definition at line 291 of file lk_flow_nodelet.cpp.

static void opencv_apps::LKFlowNodelet::trackbarCallback ( int  ,
void *   
) [inline, static, private]

Definition at line 130 of file lk_flow_nodelet.cpp.

void opencv_apps::LKFlowNodelet::unsubscribe ( ) [inline, private, virtual]

This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.

Implements opencv_apps::Nodelet.

Definition at line 306 of file lk_flow_nodelet.cpp.


Member Data Documentation

Definition at line 86 of file lk_flow_nodelet.cpp.

Definition at line 92 of file lk_flow_nodelet.cpp.

Definition at line 62 of file lk_flow_nodelet.cpp.

Definition at line 72 of file lk_flow_nodelet.cpp.

Definition at line 76 of file lk_flow_nodelet.cpp.

Definition at line 65 of file lk_flow_nodelet.cpp.

Definition at line 87 of file lk_flow_nodelet.cpp.

Definition at line 93 of file lk_flow_nodelet.cpp.

Definition at line 60 of file lk_flow_nodelet.cpp.

Definition at line 61 of file lk_flow_nodelet.cpp.

Definition at line 64 of file lk_flow_nodelet.cpp.

Definition at line 68 of file lk_flow_nodelet.cpp.

Definition at line 82 of file lk_flow_nodelet.cpp.

Definition at line 91 of file lk_flow_nodelet.cpp.

Definition at line 63 of file lk_flow_nodelet.cpp.

bool opencv_apps::LKFlowNodelet::need_config_update_ = false [static, private]

Definition at line 80 of file lk_flow_nodelet.cpp.

Definition at line 83 of file lk_flow_nodelet.cpp.

Definition at line 84 of file lk_flow_nodelet.cpp.

cv::Point2f opencv_apps::LKFlowNodelet::point [private]

Definition at line 85 of file lk_flow_nodelet.cpp.

std::vector<cv::Point2f> opencv_apps::LKFlowNodelet::points[2] [private]

Definition at line 88 of file lk_flow_nodelet.cpp.

Definition at line 77 of file lk_flow_nodelet.cpp.

Definition at line 87 of file lk_flow_nodelet.cpp.

Definition at line 90 of file lk_flow_nodelet.cpp.

Definition at line 75 of file lk_flow_nodelet.cpp.

Definition at line 73 of file lk_flow_nodelet.cpp.

Definition at line 66 of file lk_flow_nodelet.cpp.

Definition at line 79 of file lk_flow_nodelet.cpp.


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


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26