Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 #include <ucl_drone/computer_vision/computer_vision.h>
00012 #include <ucl_drone/read_from_launch.h>
00013 
00014 ImageProcessor::ImageProcessor()
00015   : it_(nh_), pose_publishing(false), video_publishing(false), pending_reset(false)
00016 {
00017   cv::initModule_nonfree();  
00018 
00019   
00020 
00021   
00022   ros::param::get("~use_OpticalFlowPyrLK", this->use_OpticalFlowPyrLK);
00023 
00024   
00025   
00026   bool autonomy_unavailable = false;  
00027   bool flag_autonomy_unavailable = ros::param::get("~autonomy_unavailable", autonomy_unavailable);
00028 
00029   
00030   std::string drone_prefix = "/";  
00031   bool flag_drone_prefix = ros::param::get("~drone_prefix", drone_prefix);
00032 
00033   
00034   std::string cam_type;  
00035   bool flag_cam_type = ros::param::get("~cam_type", cam_type);
00036   std::string video_channel;  
00037   bool flag_video_channel = ros::param::get("~video_channel", video_channel);
00038   if (!flag_video_channel)
00039   {
00040     if (cam_type == "front")
00041     {
00042       video_channel = drone_prefix + "ardrone/front/image_raw";
00043     }
00044     else
00045     {
00046       cam_type = "bottom";
00047       video_channel = drone_prefix + "ardrone/bottom/image_raw";
00048     }
00049   }
00050 
00051   
00052   if (!Read::CamMatrixParams("cam_matrix"))
00053   {
00054     ROS_ERROR("cam_matrix not properly transmitted");
00055   }
00056   if (!Read::ImgSizeParams("img_size"))
00057   {
00058     ROS_ERROR("img_size not properly transmitted");
00059   }
00060 
00061   video_channel_ = nh_.resolveName(drone_prefix + video_channel);
00062 
00063   if (!autonomy_unavailable)  
00064   {
00065     ros::ServiceClient client =
00066         nh_.serviceClient< ardrone_autonomy::CamSelect >(drone_prefix + "ardrone/setcamchannel");
00067     ardrone_autonomy::CamSelect srv;
00068     if (cam_type == "bottom")
00069     {
00070       srv.request.channel = 1;
00071     }
00072     else
00073     {
00074       srv.request.channel = 0;
00075     }
00076     int counter_call_success = 0;
00077     ros::Rate r(1 / 2.0);
00078     while (counter_call_success < 2)
00079     {
00080       ros::spinOnce();
00081       r.sleep();
00082       if (client.call(srv))
00083       {
00084         ROS_INFO("Camera toggled ?");
00085         if (srv.response.result)
00086           counter_call_success += 1;
00087       }
00088       else
00089       {
00090         ROS_INFO("Failed to call service setcamchannel, try it again in 1sec...");
00091       }
00092     }
00093   }
00094 
00095   
00096   image_sub_ =
00097       it_.subscribe(video_channel_, 1, &ImageProcessor::imageCb, this);  
00098 
00099   
00100   pose_channel = nh_.resolveName("pose_estimation");
00101   pose_sub = nh_.subscribe(pose_channel, 1, &ImageProcessor::poseCb, this);
00102 
00103   
00104   reset_pose_channel = nh_.resolveName("reset_pose");
00105   reset_pose_sub = nh_.subscribe(reset_pose_channel, 1, &ImageProcessor::resetPoseCb, this);
00106 
00107   
00108   end_reset_pose_channel = nh_.resolveName("end_reset_pose");
00109   end_reset_pose_sub =
00110       nh_.subscribe(end_reset_pose_channel, 1, &ImageProcessor::endResetPoseCb, this);
00111 
00112   
00113   processed_image_channel_out = nh_.resolveName("processed_image");
00114   processed_image_pub =
00115       nh_.advertise< ucl_drone::ProcessedImageMsg >(processed_image_channel_out, 1);
00116 
00117   
00118   this->prev_cam_img = new ProcessedImage();
00119 
00120 #ifdef DEBUG_TARGET
00121   cv::namedWindow(OPENCV_WINDOW);
00122 #endif 
00123 
00124   
00125   target_loaded = target.init(TARGET_RELPATH);
00126 }
00127 
00128 ImageProcessor::~ImageProcessor()
00129 {
00130 #ifdef DEBUG_TARGET
00131   cv::destroyWindow(OPENCV_WINDOW);
00132 #endif 
00133   delete this->prev_cam_img;
00134 }
00135 
00136 void ImageProcessor::resetPoseCb(const std_msgs::Empty& msg)
00137 {
00138   pending_reset = true;
00139   this->prev_cam_img = new ProcessedImage();
00140 }
00141 
00142 void ImageProcessor::endResetPoseCb(const std_msgs::Empty& msg)
00143 {
00144   pending_reset = false;
00145 }
00146 
00147 
00148 void ImageProcessor::imageCb(const sensor_msgs::Image::ConstPtr& msg)
00149 {
00150   if (pending_reset)
00151     return;
00152   ROS_DEBUG("ImageProcessor::imageCb");
00153   this->lastImageReceived = msg;
00154   this->video_publishing = true;
00155 }
00156 
00157 
00158 void ImageProcessor::poseCb(const ucl_drone::Pose3D::ConstPtr& posePtr)
00159 {
00160   if (pending_reset)
00161     return;
00162   ROS_DEBUG("ImageProcessor::poseCb");
00163   lastPoseReceived = posePtr;
00164   pose_publishing = true;
00165 }
00166 
00167 
00168 void ImageProcessor::publishProcessedImg()
00169 {
00170   if (pending_reset)
00171     return;
00172   ROS_DEBUG("ImageProcessor::publishProcessedImg");
00173 
00174   TIC(processed_image);
00175   
00176   ProcessedImage cam_img(*lastImageReceived, *lastPoseReceived, *prev_cam_img,
00177                          this->use_OpticalFlowPyrLK);
00178   
00179   ucl_drone::ProcessedImageMsg::Ptr msg(new ucl_drone::ProcessedImageMsg);
00180   
00181   cam_img.convertToMsg(msg, target);
00182   TOC(processed_image, "processedImage");
00183 
00184   TIC(publish);
00185   
00186   processed_image_pub.publish(msg);
00187   TOC(publish, "publisher");
00188 
00189   
00190   delete this->prev_cam_img;
00191   this->prev_cam_img = new ProcessedImage(cam_img);
00192 }
00193 
00194 int main(int argc, char** argv)
00195 {
00196   ros::init(argc, argv, "computer_vision");
00197 
00198   
00199   
00200   
00201   
00202 
00203   
00204   ImageProcessor ic;
00205 
00206   
00207   ros::Rate r(6);  
00208 
00209   
00210   while ((!ic.pose_publishing || !ic.video_publishing) && ros::ok())
00211   {
00212     ros::spinOnce();
00213     r.sleep();
00214   }
00215 
00216   while (ros::ok())  
00217   {
00218     ros::spinOnce();
00219     ic.publishProcessedImg();
00220     r.sleep();
00221   }
00222 
00223   return 0;
00224 }