projection_2D.h
Go to the documentation of this file.
00001 
00008 #ifndef UCL_DRONE_PROJECTION_2D_H
00009 #define UCL_DRONE_PROJECTION_2D_H
00010 #define PCL_NO_PRECOMPILE
00011 
00012 /* Header files */
00013 
00014 #include <ucl_drone/ucl_drone.h>
00015 
00016 #include <ros/package.h>
00017 #include <ros/ros.h>
00018 #include <tf/transform_datatypes.h>
00019 
00020 /* Vision (OpenCV) */
00021 #include <opencv2/calib3d/calib3d.hpp>
00022 #include <opencv2/core/core.hpp>
00023 #include <opencv2/imgproc/imgproc.hpp>
00024 #include <opencv2/nonfree/features2d.hpp>
00025 #include <opencv2/nonfree/nonfree.hpp>
00026 
00027 /* Point Cloud library */
00028 #include <pcl/visualization/point_cloud_geometry_handlers.h>
00029 
00030 #include <pcl/common/common_headers.h>
00031 #include <pcl/point_types.h>  // pcl::PointXYZRGB
00032 #include <pcl/visualization/cloud_viewer.h>
00033 #include <pcl/visualization/pcl_visualizer.h>
00034 #include <pcl_conversions/pcl_conversions.h>  // pcl::fromROSMsg
00035 #include <pcl_ros/point_cloud.h>              // pcl::PointCloud
00036 
00037 /* Boost */
00038 #include <boost/shared_ptr.hpp>
00039 #include <boost/thread/thread.hpp>
00040 
00041 /* Messages */
00042 #include <sensor_msgs/image_encodings.h>
00043 
00044 /* ucl_drone */
00045 #include <ucl_drone/PointXYZRGBSIFT.h>  // pcl::PointXYZRGBSIFT
00046 #include <ucl_drone/Pose3D.h>
00047 #include <ucl_drone/ProcessedImageMsg.h>
00048 #include <ucl_drone/TargetDetected.h>
00049 #include <ucl_drone/opencv_utils.h>
00050 #include <ucl_drone/read_from_launch.h>
00051 
00058 void projection_2D(std::vector< cv::Point2f > &points_in, ucl_drone::Pose3D &pose,
00059                    std::vector< cv::Point3f > &points_out, bool h_flag = false);
00060 
00061 #endif /* UCL_DRONE_PROJECTION_2D_H */


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53