tutorial-ros-pioneer-visual-servo.cpp
Go to the documentation of this file.
00001 
00021 #include <iostream>
00022 
00023 #include <visp/vpCameraParameters.h>
00024 #include <visp/vpDisplayX.h>
00025 #include <visp/vpDot2.h>
00026 #include <visp/vpFeatureBuilder.h>
00027 #include <visp/vpFeatureDepth.h>
00028 #include <visp/vpFeaturePoint.h>
00029 #include <visp/vpHomogeneousMatrix.h>
00030 #include <visp/vpImage.h>
00031 #include <visp/vpImageConvert.h>
00032 #include <visp/vpServo.h>
00033 #include <visp/vpVelocityTwistMatrix.h>
00034 
00035 #include <visp_ros/vpROSGrabber.h>
00036 #include <visp_ros/vpROSRobotPioneer.h>
00037 
00038 #if defined(VISP_HAVE_DC1394_2) && defined(VISP_HAVE_X11)
00039 #  define TEST_COULD_BE_ACHIEVED
00040 #endif
00041 
00042 #ifdef TEST_COULD_BE_ACHIEVED
00043 int main(int argc, char **argv)
00044 {
00045   try {
00046     vpImage<unsigned char> I; // Create a gray level image container
00047     double depth = 1.;
00048     double lambda = 0.6;
00049     double coef = 1./6.77; // Scale parameter used to estimate the depth Z of the blob from its surface
00050 
00051     vpROSRobotPioneer robot;
00052     robot.setCmdVelTopic("/RosAria/cmd_vel");
00053     robot.init();
00054 
00055     // Wait 3 sec to be sure that the low level Aria thread used to control
00056     // the robot is started. Without this delay we experienced a delay (arround 2.2 sec)
00057     // between the velocity send to the robot and the velocity that is really applied
00058     // to the wheels.
00059     vpTime::sleepMs(3000);
00060 
00061     std::cout << "Robot connected" << std::endl;
00062 
00063     // Camera parameters. In this experiment we don't need a precise calibration of the camera
00064     vpCameraParameters cam;
00065 
00066     // Create a grabber based on libdc1394-2.x third party lib (for firewire cameras under Linux)
00067     vpROSGrabber g;
00068     g.setCameraInfoTopic("/camera/camera_info");
00069     g.setImageTopic("/camera/image_raw");
00070     g.setRectify(true);
00071 
00072     // Get camera parameters from /camera/camera_info topic
00073     if (g.getCameraInfo(cam) == false)
00074       cam.initPersProjWithoutDistortion(600,600,I.getWidth()/2, I.getHeight()/2);
00075 
00076     g.acquire(I);
00077 
00078     // Create an image viewer
00079     vpDisplayX d(I, 10, 10, "Current frame");
00080     vpDisplay::display(I);
00081     vpDisplay::flush(I);
00082 
00083     // Create a blob tracker
00084     vpDot2 dot;
00085     dot.setGraphics(true);
00086     dot.setComputeMoments(true);
00087     dot.setEllipsoidShapePrecision(0.);  // to track a blob without any constraint on the shape
00088     dot.setGrayLevelPrecision(0.9);  // to set the blob gray level bounds for binarisation
00089     dot.setEllipsoidBadPointsPercentage(0.5); // to be accept 50% of bad inner and outside points with bad gray level
00090     dot.initTracking(I);
00091     vpDisplay::flush(I);
00092 
00093     vpServo task;
00094     task.setServo(vpServo::EYEINHAND_L_cVe_eJe) ;
00095     task.setInteractionMatrixType(vpServo::DESIRED, vpServo::PSEUDO_INVERSE) ;
00096     task.setLambda(lambda) ;
00097     vpVelocityTwistMatrix cVe ;
00098     cVe = robot.get_cVe() ;
00099     task.set_cVe(cVe) ;
00100 
00101     std::cout << "cVe: \n" << cVe << std::endl;
00102 
00103     vpMatrix eJe;
00104     robot.get_eJe(eJe) ;
00105     task.set_eJe(eJe) ;
00106     std::cout << "eJe: \n" << eJe << std::endl;
00107 
00108     // Current and desired visual feature associated to the x coordinate of the point
00109     vpFeaturePoint s_x, s_xd;
00110 
00111     // Create the current x visual feature
00112     vpFeatureBuilder::create(s_x, cam, dot);
00113 
00114     // Create the desired x* visual feature
00115     s_xd.buildFrom(0, 0, depth);
00116 
00117     // Add the feature
00118     task.addFeature(s_x, s_xd) ;
00119 
00120     // Create the current log(Z/Z*) visual feature
00121     vpFeatureDepth s_Z, s_Zd;
00122     // Surface of the blob estimated from the image moment m00 and converted in meters
00123     double surface = 1./sqrt(dot.m00/(cam.get_px()*cam.get_py()));
00124     double Z, Zd;
00125     // Initial depth of the blob in from of the camera
00126     Z = coef * surface ;
00127     // Desired depth Z* of the blob. This depth is learned and equal to the initial depth
00128     Zd = Z;
00129 
00130     std::cout << "Z " << Z << std::endl;
00131     s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z , 0); // log(Z/Z*) = 0 that's why the last parameter is 0
00132     s_Zd.buildFrom(s_x.get_x(), s_x.get_y(), Zd , 0); // log(Z/Z*) = 0 that's why the last parameter is 0
00133 
00134     // Add the feature
00135     task.addFeature(s_Z, s_Zd) ;
00136 
00137     vpColVector v; // vz, wx
00138 
00139     while(1)
00140     {
00141       // Acquire a new image
00142       g.acquire(I);
00143 
00144       // Set the image as background of the viewer
00145       vpDisplay::display(I);
00146 
00147       // Does the blob tracking
00148       dot.track(I);
00149       // Update the current x feature
00150       vpFeatureBuilder::create(s_x, cam, dot);
00151 
00152       // Update log(Z/Z*) feature. Since the depth Z change, we need to update the intection matrix
00153       surface = 1./sqrt(dot.m00/(cam.get_px()*cam.get_py()));
00154       Z = coef * surface ;
00155       s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)) ;
00156 
00157       robot.get_cVe(cVe) ;
00158       task.set_cVe(cVe) ;
00159 
00160       robot.get_eJe(eJe) ;
00161       task.set_eJe(eJe) ;
00162 
00163       // Compute the control law. Velocities are computed in the mobile robot reference frame
00164       v = task.computeControlLaw() ;
00165 
00166       std::cout << "Send velocity to the pionner: " << v[0] << " m/s "
00167                 << vpMath::deg(v[1]) << " deg/s" << std::endl;
00168 
00169       // Send the velocity to the robot
00170       robot.setVelocity(vpRobot::REFERENCE_FRAME, v);
00171 
00172       // Draw a vertical line which corresponds to the desired x coordinate of the dot cog
00173       vpDisplay::displayLine(I, 0, 320, 479, 320, vpColor::red);
00174       vpDisplay::flush(I);
00175 
00176       // A click in the viewer to exit
00177       if ( vpDisplay::getClick(I, false) )
00178         break;
00179     }
00180 
00181     std::cout << "Ending robot thread..." << std::endl;
00182 
00183     // Kill the servo task
00184     task.print() ;
00185     task.kill();
00186   }
00187   catch(vpException e) {
00188     std::cout << "Catch an exception: " << e << std::endl;
00189     return 1;
00190   }
00191 }
00192 #else
00193 int main()
00194 {
00195   std::cout << "You don't have the right 3rd party libraries to run this example..." << std::endl;
00196 }
00197 #endif


visp_ros
Author(s): Francois Pasteau, Fabien Spindler
autogenerated on Wed Aug 26 2015 16:44:33