51 #include "visp/vpTrackingException.h" 52 #include "visp_camera_calibration/CalibPointArray.h" 53 #include "visp_camera_calibration/CalibPoint.h" 54 #include "visp_camera_calibration/calibrate.h" 55 #include "visp/vpMouseButton.h" 59 #include "sensor_msgs/SetCameraInfo.h" 62 #include "visp/vpDisplayX.h" 63 #include "visp/vpImagePoint.h" 64 #include "visp/vpPixelMeterConversion.h" 65 #include "visp/vpMeterPixelConversion.h" 66 #include "visp/vpPose.h" 67 #include "visp/vpHomogeneousMatrix.h" 68 #include "visp/vpDot.h" 69 #include "visp/vpDot2.h" 70 #include "visp/vpCalibration.h" 71 #include <boost/format.hpp> 109 ROS_ASSERT(model_points_x_list.
size() == model_points_y_list.
size() && model_points_x_list.
size()==model_points_z_list.
size());
110 for(
int i=0;i<model_points_x_list.
size();i++){
114 double X =
static_cast<double>(model_points_x_list[i]);
115 double Y =
static_cast<double>(model_points_y_list[i]);
116 double Z =
static_cast<double>(model_points_z_list[i]);
118 p.setWorldCoordinates(X,Y,Z);
130 ROS_ASSERT(selected_points_x_list.
size() == selected_points_y_list.
size() && selected_points_x_list.
size()==selected_points_z_list.
size());
132 for(
int i=0;i<selected_points_x_list.
size();i++){
136 double X =
static_cast<double>(selected_points_x_list[i]);
137 double Y =
static_cast<double>(selected_points_y_list[i]);
138 double Z =
static_cast<double>(selected_points_z_list[i]);
140 p.setWorldCoordinates(X,Y,Z);
149 vpDisplay* disp =
new vpDisplayX();
151 disp->setTitle(
"Image processing initialisation interface");
152 vpDisplay::flush(
img_);
153 vpDisplay::display(
img_);
154 vpDisplay::displayCharString(
img_,
img_.getHeight()/2-10,
img_.getWidth()/4,
"Waiting for the camera feed.",vpColor::red);
155 vpDisplay::displayCharString(
img_,
img_.getHeight()/2+10,
img_.getWidth()/4,
"If you are using the example camera, you should click on it's window",vpColor::red);
157 vpDisplay::flush(
img_);
160 double px =
cam_.get_px();
161 double py =
cam_.get_px();
162 double u0 =
img_.getWidth()/2;
163 double v0 =
img_.getHeight()/2;
164 cam_.initPersProjWithoutDistortion(px, py, u0, v0);
171 sensor_msgs::SetCameraInfo::Response &res){
172 std::string calibration_path;
174 ROS_INFO(
"saving calibration file to %s",calibration_path.c_str());
181 double gray_level_precision;
182 double size_precision;
183 bool pause_at_each_frame =
false;
192 visp_camera_calibration::CalibPointArray calib_all_points;
198 vpDisplay::display(
img_);
199 vpDisplay::flush(
img_);
201 if(!pause_at_each_frame){
203 vpDisplay::displayRectangle(
img_,0,0,
img_.getWidth(),15,vpColor::black,
true);
204 vpDisplay::displayCharString(
img_,10,10,
"Click on the window to select the current image",vpColor::red);
205 vpDisplay::flush(
img_);
222 d.setGrayLevelPrecision(gray_level_precision);
223 d.setSizePrecision(size_precision);
226 vpDisplay::displayRectangle(
img_,0,0,
img_.getWidth(),15,vpColor::black,
true);
227 vpDisplay::displayCharString(
img_,10,10,boost::str(boost::format(
"click on point %1%") % (i+1)).c_str(),vpColor::red);
228 vpDisplay::flush(
img_);
229 while(
ros::ok() && !vpDisplay::getClick(
img_,ip,
false));
231 d.initTracking(
img_, ip);
233 ip.set_ij(d.getCog().get_i(),d.getCog().get_j());
235 vpPixelMeterConversion::convertPoint(
cam_, ip, x, y);
241 vpDisplay::displayCross(
img_, d.getCog(), 10, vpColor::red);
242 vpDisplay::flush(
img_);
243 }
catch(vpTrackingException e){
249 vpHomogeneousMatrix cMo;
250 pose.computePose(vpPose::LAGRANGE, cMo) ;
251 pose.computePose(vpPose::VIRTUAL_VS, cMo) ;
252 vpHomogeneousMatrix cMoTmp = cMo;
254 vpCameraParameters camTmp =
cam_;
257 calib.computeCalibration(vpCalibration::CALIB_VIRTUAL_VS,cMoTmp,camTmp,
false);
262 for (std::vector<vpPoint>::iterator model_point_iter=
model_points_.begin();
266 vpColVector _cP, _p ;
268 model_point_iter->changeFrame(cMoTmp,_cP) ;
269 model_point_iter->projection(_cP,_p) ;
270 vpMeterPixelConversion::convertPoint(camTmp,_p[0],_p[1], ip);
271 if (10 < ip.get_u() && ip.get_u() <
img_.getWidth()-10 &&
272 10 < ip.get_v() && ip.get_v() <
img_.getHeight()-10) {
276 md.setGrayLevelPrecision(gray_level_precision);
277 md.setSizePrecision(size_precision);
279 md.initTracking(
img_, ip);
283 vpRect bbox = md.getBBox();
284 vpImagePoint cog = md.getCog();
285 if(bbox.getLeft()<5 || bbox.getRight()>(double)
img_.getWidth()-5 ||
286 bbox.getTop()<5 || bbox.getBottom()>(double)
img_.getHeight()-5||
287 vpMath::abs(ip.get_u() - cog.get_u()) > 10 ||
288 vpMath::abs(ip.get_v() - cog.get_v()) > 10){
289 ROS_DEBUG(
"tracking failed[suspicious point location].");
293 vpPixelMeterConversion::convertPoint(camTmp, cog, x, y) ;
294 model_point_iter->set_x(x) ;
295 model_point_iter->set_y(y) ;
297 md.display(
img_,vpColor::yellow, 2);
298 visp_camera_calibration::CalibPoint cp;
301 cp.X = model_point_iter->get_oX();
302 cp.Y = model_point_iter->get_oY();
303 cp.Z = model_point_iter->get_oZ();
305 calib_all_points.points.push_back(cp);
307 model_point_iter->display(
img_,cMoTmp,camTmp) ;
309 vpDisplay::flush(
img_);
319 ROS_INFO(
"Left click on the interface window to continue, right click to restart");
320 vpDisplay::displayRectangle(
img_,0,0,
img_.getWidth(),15,vpColor::black,
true);
321 vpDisplay::displayCharString(
img_,10,10,
"Left click on the interface window to continue, right click to restart",vpColor::red);
322 vpDisplay::flush(
img_);
324 vpMouseButton::vpMouseButtonType btn;
325 while(
ros::ok() && !vpDisplay::getClick(
img_,ip,btn,
false));
327 if(btn==vpMouseButton::button1)
343 if(vpDisplay::getClick(
img_,ip,
false))
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::vector< vpPoint > selected_points_
ros::Subscriber raw_image_subscriber_
unsigned long queue_size_
std::string raw_image_topic
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string size_precision_param
std::string selected_points_y_param
std::string model_points_z_param
vpImage< unsigned char > img_
virtual ~ImageProcessing()
std::string model_points_x_param
vpImage< unsigned char > toVispImage(const sensor_msgs::Image &src)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
boost::function< void(const sensor_msgs::Image::ConstPtr &)> raw_image_subscriber_callback_t
subscriber type declaration for raw_image topic subscriber
std::string point_correspondence_topic
std::string calibrate_service
void rawImageCallback(const sensor_msgs::Image::ConstPtr &image)
callback corresponding to the raw_image topic. Computes a cMo from selected points on the image...
std::string set_camera_info_bis_service
std::string gray_level_precision_param
ROSCPP_DECL bool get(const std::string &key, std::string &s)
bool setCameraInfoBisCallback(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res)
service displaying.
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
std::string model_points_y_param
ros::Publisher point_correspondence_publisher_
std::string pause_at_each_frame_param
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::function< bool(sensor_msgs::SetCameraInfo::Request &, sensor_msgs::SetCameraInfo::Response &res)> set_camera_info_bis_service_callback_t
service type declaration for calibrate service
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
std::vector< vpPoint > model_points_
#define ROS_DEBUG_STREAM(args)
ros::ServiceServer set_camera_info_bis_service_
ros::ServiceClient calibrate_service_
std::string calibration_path_param
ROSCPP_DECL void spinOnce()
std::string selected_points_z_param
std::string selected_points_x_param
ROSCPP_DECL void waitForShutdown()