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


jsk_perception
Author(s): Manabu Saito
autogenerated on Mon Oct 6 2014 01:16:59