Go to the documentation of this file.
55 #include "visp_camera_calibration/calibrate.h"
56 #include <visp/vpImage.h>
57 #include <visp/vpDot2.h>
58 #include <visp/vpCalibration.h>
63 #include <visp/vpDisplayX.h>
64 #include "visp/vpTrackingException.h"
65 #include <boost/format.hpp>
77 std::string images_path;
91 reader_.setFileName(images_path.c_str());
96 vpDisplay* disp =
new vpDisplayX();
98 disp->setTitle(
"camera");
100 vpDisplay::display(
img_);
101 vpDisplay::displayText(
img_,
img_.getHeight()/2,
img_.getWidth()/4,
"Click to publish camera feed.",vpColor::red);
102 vpDisplay::flush(
img_);
108 double gray_level_precision;
109 double size_precision;
113 ROS_INFO(
"Click to start sending image data");
114 while(
ros::ok() && !vpDisplay::getClick(
img_,
false));
116 for(
unsigned int i=0;i<(
unsigned int)
reader_.getLastFrameIndex() &&
ros::ok();i++){
118 sensor_msgs::Image image;
122 vpDisplay::display(
img_);
125 vpDisplay::flush(
img_);
133 ROS_INFO(
"When finished selecting points, click on the camera window for calibration");
134 vpDisplay::displayText(
img_,
img_.getHeight()/2+30,
img_.getWidth()/4,
"When finished selecting points, click here for calibration",vpColor::red);
135 vpDisplay::flush(
img_);
136 while(
ros::ok() && !vpDisplay::getClick(
img_,
false));
137 visp_camera_calibration::calibrate calibrate_comm;
138 calibrate_comm.request.method = vpCalibration::CALIB_VIRTUAL_VS_DIST;
139 calibrate_comm.request.sample_width=
img_.getWidth();
140 calibrate_comm.request.sample_height =
img_.getHeight();
142 ROS_INFO(
"service called successfully");
144 ROS_INFO(
"standard deviation with distorsion:");
145 for(std::vector<double>::iterator i = calibrate_comm.response.stdDevErrs.begin();i!=calibrate_comm.response.stdDevErrs.end();i++)
153 sensor_msgs::SetCameraInfo::Response &res){
154 std::string calib_info;
155 std::stringstream ss(calib_info);
164 ROS_INFO(
"end of setting camera info");
ros::ServiceServer set_camera_info_service_
std::string size_precision_param
std::string raw_image_topic
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
boost::function< bool(sensor_msgs::SetCameraInfo::Request &, sensor_msgs::SetCameraInfo::Response &res)> set_camera_info_service_callback_t
service type declaration for calibrate service
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
ROSCPP_DECL bool getCached(const std::string &key, bool &b)
std::string calibrate_service
std::string gray_level_precision_param
ros::ServiceClient calibrate_service_
sensor_msgs::Image toSensorMsgsImage(const vpImage< unsigned char > &src)
#define ROS_INFO_STREAM(args)
std::string images_path_param
std::string getTopic() const
vpImage< unsigned char > img_
std::string set_camera_info_service
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
bool writeCalibrationIni(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
File containing names of topics or services used all accross the package.
bool setCameraInfoCallback(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
service setting camera parameters.
ros::AsyncSpinner spinner
ros::Publisher raw_image_publisher_