Public Member Functions | Private Member Functions | Private Attributes | List of all members
OpticalFlow Class Reference
Inheritance diagram for OpticalFlow:
Inheritance graph
[legend]

Public Member Functions

 OpticalFlow ()
 
- 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 ()
 

Private Member Functions

geometry_msgs::Vector3Stamped calcFlowGyro (const std::string &frame_id, const ros::Time &prev, const ros::Time &curr)
 
void drawFlow (Mat &frame, double x, double y, double quality) const
 
void flow (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cinfo)
 
void onInit ()
 
void parseCameraInfo (const sensor_msgs::CameraInfoConstPtr &cinfo)
 

Private Attributes

bool calc_flow_gyro_
 
Mat camera_matrix_
 
Mat curr_
 
Mat dist_coeffs_
 
std::string fcu_frame_id_
 
mavros_msgs::OpticalFlowRad flow_
 
ros::Publisher flow_pub_
 
Mat hann_
 
image_transport::Publisher img_pub_
 
image_transport::CameraSubscriber img_sub_
 
std::string local_frame_id_
 
Mat prev_
 
ros::Time prev_stamp_
 
cv::Rect roi_
 
int roi_px_
 
double roi_rad_
 
ros::Publisher shift_pub_
 
std::unique_ptr< tf2_ros::Buffertf_buffer_
 
std::unique_ptr< tf2_ros::TransformListenertf_listener_
 
ros::Publisher velo_pub_
 

Additional Inherited Members

- 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
 

Detailed Description

Definition at line 33 of file optical_flow.cpp.

Constructor & Destructor Documentation

◆ OpticalFlow()

OpticalFlow::OpticalFlow ( )
inline

Definition at line 36 of file optical_flow.cpp.

Member Function Documentation

◆ calcFlowGyro()

geometry_msgs::Vector3Stamped OpticalFlow::calcFlowGyro ( const std::string &  frame_id,
const ros::Time prev,
const ros::Time curr 
)
inlineprivate

Definition at line 246 of file optical_flow.cpp.

◆ drawFlow()

void OpticalFlow::drawFlow ( Mat &  frame,
double  x,
double  y,
double  quality 
) const
inlineprivate

Definition at line 98 of file optical_flow.cpp.

◆ flow()

void OpticalFlow::flow ( const sensor_msgs::ImageConstPtr &  msg,
const sensor_msgs::CameraInfoConstPtr &  cinfo 
)
inlineprivate

Definition at line 110 of file optical_flow.cpp.

◆ onInit()

void OpticalFlow::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 57 of file optical_flow.cpp.

◆ parseCameraInfo()

void OpticalFlow::parseCameraInfo ( const sensor_msgs::CameraInfoConstPtr &  cinfo)
inlineprivate

Definition at line 89 of file optical_flow.cpp.

Member Data Documentation

◆ calc_flow_gyro_

bool OpticalFlow::calc_flow_gyro_
private

Definition at line 55 of file optical_flow.cpp.

◆ camera_matrix_

Mat OpticalFlow::camera_matrix_
private

Definition at line 52 of file optical_flow.cpp.

◆ curr_

Mat OpticalFlow::curr_
private

Definition at line 51 of file optical_flow.cpp.

◆ dist_coeffs_

Mat OpticalFlow::dist_coeffs_
private

Definition at line 52 of file optical_flow.cpp.

◆ fcu_frame_id_

std::string OpticalFlow::fcu_frame_id_
private

Definition at line 43 of file optical_flow.cpp.

◆ flow_

mavros_msgs::OpticalFlowRad OpticalFlow::flow_
private

Definition at line 46 of file optical_flow.cpp.

◆ flow_pub_

ros::Publisher OpticalFlow::flow_pub_
private

Definition at line 41 of file optical_flow.cpp.

◆ hann_

Mat OpticalFlow::hann_
private

Definition at line 50 of file optical_flow.cpp.

◆ img_pub_

image_transport::Publisher OpticalFlow::img_pub_
private

Definition at line 45 of file optical_flow.cpp.

◆ img_sub_

image_transport::CameraSubscriber OpticalFlow::img_sub_
private

Definition at line 44 of file optical_flow.cpp.

◆ local_frame_id_

std::string OpticalFlow::local_frame_id_
private

Definition at line 43 of file optical_flow.cpp.

◆ prev_

Mat OpticalFlow::prev_
private

Definition at line 51 of file optical_flow.cpp.

◆ prev_stamp_

ros::Time OpticalFlow::prev_stamp_
private

Definition at line 42 of file optical_flow.cpp.

◆ roi_

cv::Rect OpticalFlow::roi_
private

Definition at line 49 of file optical_flow.cpp.

◆ roi_px_

int OpticalFlow::roi_px_
private

Definition at line 47 of file optical_flow.cpp.

◆ roi_rad_

double OpticalFlow::roi_rad_
private

Definition at line 48 of file optical_flow.cpp.

◆ shift_pub_

ros::Publisher OpticalFlow::shift_pub_
private

Definition at line 41 of file optical_flow.cpp.

◆ tf_buffer_

std::unique_ptr<tf2_ros::Buffer> OpticalFlow::tf_buffer_
private

Definition at line 53 of file optical_flow.cpp.

◆ tf_listener_

std::unique_ptr<tf2_ros::TransformListener> OpticalFlow::tf_listener_
private

Definition at line 54 of file optical_flow.cpp.

◆ velo_pub_

ros::Publisher OpticalFlow::velo_pub_
private

Definition at line 41 of file optical_flow.cpp.


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


clover
Author(s): Oleg Kalachev , Artem Smirnov
autogenerated on Mon Feb 28 2022 22:08:29