23 #include <visp/vpCameraParameters.h> 24 #include <visp/vpDisplayX.h> 25 #include <visp/vpDot2.h> 26 #include <visp/vpFeatureBuilder.h> 27 #include <visp/vpFeatureDepth.h> 28 #include <visp/vpFeaturePoint.h> 29 #include <visp/vpHomogeneousMatrix.h> 30 #include <visp/vpImage.h> 31 #include <visp/vpImageConvert.h> 32 #include <visp/vpServo.h> 33 #include <visp/vpVelocityTwistMatrix.h> 38 #if defined(VISP_HAVE_DC1394_2) && defined(VISP_HAVE_X11) 39 # define TEST_COULD_BE_ACHIEVED 42 #ifdef TEST_COULD_BE_ACHIEVED 43 int main(
int argc,
char **argv)
46 vpImage<unsigned char> I;
49 double coef = 1./6.77;
59 vpTime::sleepMs(3000);
61 std::cout <<
"Robot connected" << std::endl;
64 vpCameraParameters cam;
74 cam.initPersProjWithoutDistortion(600,600,I.getWidth()/2, I.getHeight()/2);
79 vpDisplayX
d(I, 10, 10,
"Current frame");
80 vpDisplay::display(I);
85 dot.setGraphics(
true);
86 dot.setComputeMoments(
true);
87 dot.setEllipsoidShapePrecision(0.);
88 dot.setGrayLevelPrecision(0.9);
89 dot.setEllipsoidBadPointsPercentage(0.5);
94 task.setServo(vpServo::EYEINHAND_L_cVe_eJe) ;
95 task.setInteractionMatrixType(vpServo::DESIRED, vpServo::PSEUDO_INVERSE) ;
96 task.setLambda(lambda) ;
97 vpVelocityTwistMatrix cVe ;
98 cVe = robot.get_cVe() ;
101 std::cout <<
"cVe: \n" << cVe << std::endl;
106 std::cout <<
"eJe: \n" << eJe << std::endl;
109 vpFeaturePoint s_x, s_xd;
112 vpFeatureBuilder::create(s_x, cam, dot);
115 s_xd.buildFrom(0, 0, depth);
118 task.addFeature(s_x, s_xd) ;
121 vpFeatureDepth s_Z, s_Zd;
123 double surface = 1./sqrt(dot.m00/(cam.get_px()*cam.get_py()));
130 std::cout <<
"Z " << Z << std::endl;
131 s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z , 0);
132 s_Zd.buildFrom(s_x.get_x(), s_x.get_y(), Zd , 0);
135 task.addFeature(s_Z, s_Zd) ;
145 vpDisplay::display(I);
150 vpFeatureBuilder::create(s_x, cam, dot);
153 surface = 1./sqrt(dot.m00/(cam.get_px()*cam.get_py()));
155 s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z/Zd)) ;
164 v = task.computeControlLaw() ;
166 std::cout <<
"Send velocity to the pionner: " << v[0] <<
" m/s " 167 << vpMath::deg(v[1]) <<
" deg/s" << std::endl;
173 vpDisplay::displayLine(I, 0, 320, 479, 320, vpColor::red);
177 if ( vpDisplay::getClick(I,
false) )
181 std::cout <<
"Ending robot thread..." << std::endl;
187 catch(vpException e) {
188 std::cout <<
"Catch an exception: " << e << std::endl;
195 std::cout <<
"You don't have the right 3rd party libraries to run this example..." << std::endl;
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Class for cameras video capture for ROS cameras.
void setCmdVelTopic(std::string topic_name)
void setRectify(bool rectify)
void init()
basic initialization
void setCameraInfoTopic(std::string topic_name)
int main(int argc, char **argv)
bool getCameraInfo(vpCameraParameters &cam)
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
class for Camera video capture for ROS middleware.
void get_eJe(vpMatrix &eJe)
Interface for Pioneer mobile robots based on ROS.
void setImageTopic(std::string topic_name)
void acquire(vpImage< unsigned char > &I)