Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00051 #include "camera.h"
00052 #include "names.h"
00053 #include <sstream>
00054 #include "conversions/image.h"
00055 #include "visp_camera_calibration/calibrate.h"
00056 #include "visp/vpImage.h"
00057 #include "visp/vpDot2.h"
00058 #include "visp/vpCalibration.h"
00059 #include "camera_calibration_parsers/parse.h"
00060 #include "camera_calibration_parsers/parse_ini.h"
00061
00062
00063 #include <visp/vpDisplayX.h>
00064 #include "visp/vpTrackingException.h"
00065
00066
00067 namespace visp_camera_calibration
00068 {
00069 Camera::Camera() :
00070 spinner(0),
00071 queue_size_(1000),
00072 nb_points_(4),
00073 img_(480,640,255)
00074
00075 {
00076 std::string images_path;
00077
00078
00079 set_camera_info_service_callback_t set_camera_info_callback = boost::bind(&Camera::setCameraInfoCallback, this, _1,_2);
00080
00081
00082 set_camera_info_service_ = n_.advertiseService(visp_camera_calibration::set_camera_info_service,set_camera_info_callback);
00083
00084 raw_image_publisher_ = n_.advertise<sensor_msgs::Image>(visp_camera_calibration::raw_image_topic, queue_size_);
00085
00086 calibrate_service_ = n_.serviceClient<visp_camera_calibration::calibrate> (visp_camera_calibration::calibrate_service);
00087
00088 ros::param::getCached(visp_camera_calibration::images_path_param,images_path);
00089
00090 ROS_INFO_STREAM("str=" << images_path);
00091 vpDisplay* disp = new vpDisplayX();
00092 disp->init(img_);
00093 disp->setTitle("camera");
00094
00095 vpDisplay::display(img_);
00096 vpDisplay::displayCharString(img_,img_.getHeight()/2,img_.getWidth()/4,"Click to publish camera feed.",vpColor::red);
00097 vpDisplay::flush(img_);
00098
00099
00100 reader_.setFileName(images_path.c_str());
00101 reader_.setFirstFrameIndex(1);
00102 reader_.open(img_);
00103
00104
00105 spinner.start();
00106
00107
00108 }
00109
00110 void Camera::sendVideo(){
00111 double gray_level_precision;
00112 double size_precision;
00113
00114 ros::param::getCached(visp_camera_calibration::gray_level_precision_param,gray_level_precision);
00115 ros::param::getCached(visp_camera_calibration::size_precision_param,size_precision);
00116 ROS_INFO("Click to start sending image data");
00117 while(ros::ok() && !vpDisplay::getClick(img_,false));
00118
00119 for(unsigned int i=0;i<(unsigned int)reader_.getLastFrameIndex() && ros::ok();i++){
00120 reader_.acquire(img_);
00121 sensor_msgs::Image image;
00122
00123 image = visp_bridge::toSensorMsgsImage(img_);
00124
00125 vpDisplay::display(img_);
00126
00127 vpDisplay::displayCharString(img_,img_.getHeight()/2,img_.getWidth()/4,boost::str(boost::format("publishing frame %1% on %2%") % (i+1) % raw_image_publisher_.getTopic()).c_str(),vpColor::red);
00128 vpDisplay::flush(img_);
00129
00130 raw_image_publisher_.publish(image);
00131
00132 ROS_INFO("Sending image %d/%d",i+1,(int)reader_.getLastFrameIndex());
00133
00134 }
00135
00136 ROS_INFO("When finished selecting points, click on the camera window for calibration");
00137 vpDisplay::displayCharString(img_,img_.getHeight()/2+30,img_.getWidth()/4,"When finished selecting points, click here for calibration",vpColor::red);
00138 vpDisplay::flush(img_);
00139 while(ros::ok() && !vpDisplay::getClick(img_,false));
00140 visp_camera_calibration::calibrate calibrate_comm;
00141 calibrate_comm.request.method = vpCalibration::CALIB_VIRTUAL_VS_DIST;
00142 calibrate_comm.request.sample_width= img_.getWidth();
00143 calibrate_comm.request.sample_height = img_.getHeight();
00144 if (calibrate_service_.call(calibrate_comm)){
00145 ROS_INFO("service called successfully");
00146
00147 ROS_INFO("standard deviation with distorsion:");
00148 for(std::vector<double>::iterator i = calibrate_comm.response.stdDevErrs.begin();i!=calibrate_comm.response.stdDevErrs.end();i++)
00149 ROS_INFO("%f",*i);
00150 }else{
00151 ROS_ERROR("Failed to call service");
00152 }
00153 }
00154
00155 bool Camera::setCameraInfoCallback(sensor_msgs::SetCameraInfo::Request &req,
00156 sensor_msgs::SetCameraInfo::Response &res){
00157 std::string calib_info;
00158 std::stringstream ss(calib_info);
00159
00160
00161 ROS_INFO("setting camera info");
00162 camera_calibration_parsers::writeCalibrationIni(ss,visp_camera_calibration::raw_image_topic,req.camera_info);
00163 ROS_INFO("%s",ss.str().c_str());
00164 camera_calibration_parsers::writeCalibration("calibration.ini",visp_camera_calibration::raw_image_topic,req.camera_info);
00165
00166
00167 ROS_INFO("end of setting camera info");
00168 return true;
00169 }
00170
00171 Camera::~Camera()
00172 {
00173
00174 }
00175 }