Workspace transformation from the image coordinates to the world coordinates Simple ground projection is used. More...
#include <ucl_drone/ucl_drone.h>
#include <ros/package.h>
#include <ros/ros.h>
#include <tf/transform_datatypes.h>
#include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/nonfree/features2d.hpp>
#include <opencv2/nonfree/nonfree.hpp>
#include <pcl/visualization/point_cloud_geometry_handlers.h>
#include <pcl/common/common_headers.h>
#include <pcl/point_types.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_ros/point_cloud.h>
#include <boost/shared_ptr.hpp>
#include <boost/thread/thread.hpp>
#include <sensor_msgs/image_encodings.h>
#include <ucl_drone/PointXYZRGBSIFT.h>
#include <ucl_drone/Pose3D.h>
#include <ucl_drone/ProcessedImageMsg.h>
#include <ucl_drone/TargetDetected.h>
#include <ucl_drone/opencv_utils.h>
#include <ucl_drone/read_from_launch.h>
Go to the source code of this file.
Defines | |
#define | PCL_NO_PRECOMPILE |
Functions | |
void | projection_2D (std::vector< cv::Point2f > &points_in, ucl_drone::Pose3D &pose, std::vector< cv::Point3f > &points_out, bool h_flag=false) |
Workspace transformation from the image coordinates to the world coordinates Simple ground projection is used.
Definition in file projection_2D.h.
#define PCL_NO_PRECOMPILE |
Definition at line 10 of file projection_2D.h.
void projection_2D | ( | std::vector< cv::Point2f > & | points_in, |
ucl_drone::Pose3D & | pose, | ||
std::vector< cv::Point3f > & | points_out, | ||
bool | h_flag | ||
) |
This function computes the ground projection
[in] | points_in,: | OpenCV 2D points to be projected, in the OpenCV image coordinates |
[in] | pose,: | pose of the drone from which keypoints were detected |
[out] | points_out,: | OpenCV 3D points, result of the projection in world coordiantes |
[in] | h_flag,: | set this boolean to true if the drone don't publish its sensors (when not flying) |
converts a point in an image in openCV format to a mappoint in OpenCV format. 2015-2016 version
Definition at line 49 of file projection_2D.cpp.