00001 #include <ros/ros.h>
00002 #include <jsk_topic_tools/log_utils.h>
00003 #include <image_transport/image_transport.h>
00004 #include <image_geometry/pinhole_camera_model.h>
00005 #include <tf/transform_listener.h>
00006 #include <tf/transform_broadcaster.h>
00007 #include <opencv/cv.hpp>
00008 #include <opencv/highgui.h>
00009 #include <cv_bridge/cv_bridge.h>
00010
00011 #include <vector>
00012
00013 #include <geometry_msgs/Polygon.h>
00014 #include <geometry_msgs/PolygonStamped.h>
00015
00016 class VirtualCameraMono
00017 {
00018 ros::NodeHandle nh_,private_nh_;
00019 image_transport::ImageTransport it_,it_priv_;
00020 image_transport::CameraSubscriber sub_;
00021 image_transport::CameraPublisher pub_;
00022 tf::TransformListener tf_listener_;
00023 image_geometry::PinholeCameraModel cam_model_;
00024 tf::TransformBroadcaster tf_broadcaster_;
00025 ros::Subscriber sub_trans_, sub_poly_;
00026
00027 tf::StampedTransform trans_;
00028 geometry_msgs::PolygonStamped poly_;
00029
00030 public:
00031 VirtualCameraMono() : private_nh_("~"), it_(nh_), it_priv_(private_nh_)
00032 {
00033 std::string image_topic = nh_.resolveName("image");
00034 sub_ = it_.subscribeCamera(image_topic, 1, &VirtualCameraMono::imageCb, this);
00035 pub_ = it_priv_.advertiseCamera("image", 1);
00036
00037
00038 trans_.frame_id_ = "/elevator_inside_panel";
00039 trans_.child_frame_id_ = "/virtual_camera_frame";
00040 trans_.setOrigin(tf::Vector3(0.7,0,0));
00041 trans_.setRotation(tf::Quaternion(0.707,0,0,-0.707) * tf::Quaternion(0,0.707,0,-0.707));
00042
00043 poly_.header.frame_id = "/elevator_inside_panel";
00044 geometry_msgs::Point32 pt;
00045 pt.x=0, pt.y=1, pt.z=0; poly_.polygon.points.push_back(pt);
00046 pt.x=0, pt.y=-1, pt.z=0; poly_.polygon.points.push_back(pt);
00047 pt.x=0, pt.y=-1, pt.z=-1; poly_.polygon.points.push_back(pt);
00048 pt.x=0, pt.y=1, pt.z=-1; poly_.polygon.points.push_back(pt);
00049
00050
00051 sub_trans_ = nh_.subscribe<geometry_msgs::TransformStamped>("view_point", 1, &VirtualCameraMono::transCb, this);
00052 sub_poly_ = nh_.subscribe<geometry_msgs::PolygonStamped>("target_polygon", 1, &VirtualCameraMono::polyCb, this);
00053
00054 }
00055
00056 void imageCb(const sensor_msgs::ImageConstPtr& image_msg,
00057 const sensor_msgs::CameraInfoConstPtr& info_msg)
00058 {
00059
00060 if(pub_.getNumSubscribers() == 0)
00061 return;
00062
00063 cv_bridge::CvImagePtr cv_ptr;
00064 cv::Mat image;
00065 try {
00066 cv_ptr = cv_bridge::toCvCopy(image_msg, "bgr8");
00067 image = cv_ptr->image;
00068 }
00069 catch (cv_bridge::Exception& ex) {
00070 JSK_ROS_ERROR("[virtual_camera_mono] Failed to convert image");
00071 return;
00072 }
00073
00074 cam_model_.fromCameraInfo(info_msg);
00075
00076 trans_.stamp_ = ros::Time::now();
00077 tf_broadcaster_.sendTransform(trans_);
00078
00079
00080 JSK_ROS_INFO("transform image.");
00081
00082 cv::Mat outimage = image.clone();
00083 if (TransformImage(image, outimage, trans_, poly_, cam_model_)) {
00084
00085 JSK_ROS_INFO("publish image and transform.");
00086 sensor_msgs::CameraInfo virtual_info = *info_msg;
00087
00088 cv_ptr->image = outimage;
00089 sensor_msgs::Image::Ptr img_msg = cv_ptr->toImageMsg();
00090 img_msg->header.stamp = trans_.stamp_;
00091 virtual_info.header.stamp = trans_.stamp_;
00092 img_msg->header.frame_id = trans_.child_frame_id_;
00093 virtual_info.header.frame_id = trans_.child_frame_id_;
00094 pub_.publish(*img_msg, virtual_info);
00095 }
00096
00097
00098
00099 }
00100
00101
00102 void polyCb(const geometry_msgs::PolygonStampedConstPtr& poly) { poly_ = *poly; }
00103
00104 void transCb(const geometry_msgs::TransformStampedConstPtr& tf) {
00105 trans_.frame_id_ = tf->header.frame_id;
00106 trans_.child_frame_id_ = tf->child_frame_id;
00107 trans_.setOrigin(tf::Vector3(tf->transform.translation.x,
00108 tf->transform.translation.y,
00109 tf->transform.translation.z));
00110 trans_.setRotation(tf::Quaternion(tf->transform.rotation.x, tf->transform.rotation.y,
00111 tf->transform.rotation.z, tf->transform.rotation.w));
00112 }
00113
00114
00115 bool TransformImage(cv::Mat src, cv::Mat dest,
00116 tf::StampedTransform& trans, geometry_msgs::PolygonStamped& poly,
00117 image_geometry::PinholeCameraModel& cam_model_)
00118 {
00119 try {
00120
00121 std::vector<tf::Point> target_poly, target_poly_translated;
00122 for(std::vector<geometry_msgs::Point32>::iterator pit=poly.polygon.points.begin(); pit != poly.polygon.points.end(); pit++) {
00123 geometry_msgs::PointStamped point, cpoint, vpoint;
00124 point.point.x = pit->x, point.point.y = pit->y, point.point.z = pit->z;
00125 point.header = poly.header;
00126 tf_listener_.transformPoint(cam_model_.tfFrame() ,point, cpoint);
00127 tf_listener_.transformPoint(trans.frame_id_ ,point, vpoint);
00128
00129 tf::Vector3 vpt_vec = trans.inverse() * tf::Vector3(vpoint.point.x, vpoint.point.y, vpoint.point.z);
00130
00131
00132 target_poly.push_back(tf::Point(cpoint.point.x, cpoint.point.y, cpoint.point.z));
00133 target_poly_translated.push_back(tf::Point(vpt_vec.x(),vpt_vec.y(),vpt_vec.z()));
00134 }
00135
00136
00137 cv::Point2f src_pnt[4], dst_pnt[4];
00138 for(int i = 0; i < 4; i++) {
00139 cv::Point3d xyz(target_poly[i].x(),target_poly[i].y(),target_poly[i].z());
00140 cv::Point3d xyz_trans(target_poly_translated[i].x(),
00141 target_poly_translated[i].y(),
00142 target_poly_translated[i].z());
00143 cv::Point2d uv,uv_trans;
00144 uv = cam_model_.project3dToPixel(xyz);
00145 src_pnt[i] = cv::Point (uv.x, uv.y);
00146 uv_trans = cam_model_.project3dToPixel(xyz_trans);
00147 dst_pnt[i] = cv::Point (uv_trans.x, uv_trans.y);
00148 }
00149
00150 cv::Mat map_matrix = cv::getPerspectiveTransform (src_pnt, dst_pnt);
00151
00152
00153
00154
00155
00156
00157 cv::Mat to_mat = src.clone();
00158 cam_model_.rectifyImage(src, to_mat);
00159 cv::warpPerspective (src, dest, map_matrix, dest.size(), cv::INTER_LINEAR);
00160
00161 } catch ( std::runtime_error e ) {
00162
00163 return false;
00164 }
00165 return true;
00166 }
00167 };
00168
00169 int main(int argc, char **argv)
00170 {
00171 ros::init(argc, argv, "virtual_camera_mono");
00172
00173 VirtualCameraMono vcam;
00174
00175 ros::spin();
00176 }
00177