23 #include <visp/vp1394TwoGrabber.h>
24 #include <visp/vpCameraParameters.h>
25 #include <visp/vpDisplayX.h>
26 #include <visp/vpDot2.h>
27 #include <visp/vpFeatureBuilder.h>
28 #include <visp/vpFeatureDepth.h>
29 #include <visp/vpFeaturePoint.h>
30 #include <visp/vpHomogeneousMatrix.h>
31 #include <visp/vpImage.h>
32 #include <visp/vpImageConvert.h>
33 #include <visp/vpRobotPioneer.h>
34 #include <visp/vpServo.h>
35 #include <visp/vpVelocityTwistMatrix.h>
37 #if defined( VISP_HAVE_DC1394_2 ) && defined( VISP_HAVE_X11 ) || defined( VISP_HAVE_PIONEER )
38 #define TEST_COULD_BE_ACHIEVED
41 #ifdef TEST_COULD_BE_ACHIEVED
43 main(
int argc,
char **argv )
47 vpImage< unsigned char > I;
50 double coef = 1. / 6.77;
53 ArArgumentParser
parser( &argc, argv );
54 parser.loadDefaultArguments();
58 ArRobotConnector robotConnector( &
parser, &robot );
59 if ( !robotConnector.connectRobot() )
61 ArLog::log( ArLog::Terse,
"Could not connect to the robot." );
62 if (
parser.checkHelpAndWarnUnparsed() )
68 if ( !Aria::parseArgs() )
79 vpTime::sleepMs( 3000 );
81 std::cout <<
"Robot connected" << std::endl;
84 vpCameraParameters cam;
87 vp1394TwoGrabber g(
false );
88 g.setVideoMode( vp1394TwoGrabber::vpVIDEO_MODE_640x480_MONO8 );
89 g.setFramerate( vp1394TwoGrabber::vpFRAMERATE_30 );
91 cam.initPersProjWithoutDistortion( 800, 795, 320, 216 );
96 vpDisplayX
d( I, 10, 10,
"Current frame" );
97 vpDisplay::display( I );
98 vpDisplay::flush( I );
102 dot.setGraphics(
true );
103 dot.setComputeMoments(
true );
104 dot.setEllipsoidShapePrecision( 0. );
105 dot.setGrayLevelPrecision( 0.9 );
106 dot.setEllipsoidBadPointsPercentage( 0.5 );
107 dot.initTracking( I );
108 vpDisplay::flush( I );
111 task.setServo( vpServo::EYEINHAND_L_cVe_eJe );
112 task.setInteractionMatrixType( vpServo::DESIRED, vpServo::PSEUDO_INVERSE );
113 task.setLambda( lambda );
114 vpVelocityTwistMatrix cVe;
115 cVe = robot.get_cVe();
118 std::cout <<
"cVe: \n" << cVe << std::endl;
121 robot.get_eJe( eJe );
123 std::cout <<
"eJe: \n" << eJe << std::endl;
126 vpFeaturePoint s_x, s_xd;
129 vpFeatureBuilder::create( s_x, cam,
dot );
132 s_xd.buildFrom( 0, 0, depth );
135 task.addFeature( s_x, s_xd );
138 vpFeatureDepth s_Z, s_Zd;
140 double surface = 1. / sqrt(
dot.m00 / ( cam.get_px() * cam.get_py() ) );
147 std::cout <<
"Z " << Z << std::endl;
148 s_Z.buildFrom( s_x.get_x(), s_x.get_y(), Z, 0 );
149 s_Zd.buildFrom( s_x.get_x(), s_x.get_y(), Zd, 0 );
152 task.addFeature( s_Z, s_Zd );
162 vpDisplay::display( I );
167 vpFeatureBuilder::create( s_x, cam,
dot );
170 surface = 1. / sqrt(
dot.m00 / ( cam.get_px() * cam.get_py() ) );
172 s_Z.buildFrom( s_x.get_x(), s_x.get_y(), Z, log( Z / Zd ) );
174 robot.get_cVe( cVe );
177 robot.get_eJe( eJe );
181 v = task.computeControlLaw();
183 std::cout <<
"Send velocity to the pionner: " << v[0] <<
" m/s " << vpMath::deg( v[1] ) <<
" deg/s" << std::endl;
186 robot.setVelocity( vpRobot::REFERENCE_FRAME, v );
189 vpDisplay::displayLine( I, 0, 320, 479, 320, vpColor::red );
190 vpDisplay::flush( I );
193 if ( vpDisplay::getClick( I,
false ) )
197 std::cout <<
"Ending robot thread..." << std::endl;
201 robot.waitForRunExit();
207 catch ( vpException e )
209 std::cout <<
"Catch an exception: " << e << std::endl;
217 std::cout <<
"You don't have the right 3rd party libraries to run this example..." << std::endl;