Visual Servoing Platform version 3.5.0
tutorial-simu-pioneer-pan.cpp
1
20#include <iostream>
21
22#include <visp3/core/vpHomogeneousMatrix.h>
23#include <visp3/core/vpVelocityTwistMatrix.h>
24#include <visp3/gui/vpPlot.h>
25#include <visp3/robot/vpSimulatorPioneerPan.h>
26#include <visp3/visual_features/vpFeatureBuilder.h>
27#include <visp3/visual_features/vpFeatureDepth.h>
28#include <visp3/visual_features/vpFeaturePoint.h>
29#include <visp3/vs/vpServo.h>
30
31int main()
32{
33 try {
34 // Set the position the camera has to reach
36 cdMo[1][3] = 1.2; // t_y should be different from zero to be non singular
37 cdMo[2][3] = 0.5;
38
39 // Set the initial camera position
41 cMo[0][3] = 0.3;
42 cMo[1][3] = cdMo[1][3];
43 cMo[2][3] = 1.;
44 vpRotationMatrix cdRo(0, atan2(cMo[0][3], cMo[1][3]), 0);
45 cMo.insert(cdRo);
46
48 robot.setSamplingTime(0.04);
49 vpHomogeneousMatrix wMc, wMo;
50
51 // Get robot position world frame
52 robot.getPosition(wMc);
53
54 // Compute the position of the object in the world frame
55 wMo = wMc * cMo;
56
57 // Define the target
58 vpPoint point(0, 0, 0); // Coordinates in the object frame
59 point.track(cMo);
60
61 vpServo task;
64 task.setLambda(0.2);
65
67 cVe = robot.get_cVe();
68 task.set_cVe(cVe);
69
70 vpMatrix eJe;
71 robot.get_eJe(eJe);
72 task.set_eJe(eJe);
73
74 // Current and desired visual feature associated later to the x coordinate
75 // of the point
76 vpFeaturePoint s_x, s_xd;
77
78 // Create the current x visual feature
79 vpFeatureBuilder::create(s_x, point);
80
81 // Create the desired x* visual feature
82 s_xd.buildFrom(0, 0, cdMo[2][3]);
83
84 // Add the feature
85 task.addFeature(s_x, s_xd, vpFeaturePoint::selectX());
86
87 // Create the current and desired log(Z/Z*) visual feature
88 vpFeatureDepth s_Z, s_Zd;
89 // Initial depth of the target in front of the camera
90 double Z = point.get_Z();
91 // Desired depth Z* of the target.
92 double Zd = cdMo[2][3];
93 s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd));
94 s_Zd.buildFrom(0, 0, Zd,
95 0); // log(Z/Z*) = 0 that's why the last parameter is 0
96
97 // Add the feature
98 task.addFeature(s_Z, s_Zd);
99
100#ifdef VISP_HAVE_DISPLAY
101 // Create a window (800 by 500) at position (400, 10) with 3 graphics
102 vpPlot graph(3, 800, 500, 400, 10, "Curves...");
103
104 // Init the curve plotter
105 graph.initGraph(0, 3);
106 graph.initGraph(1, 2);
107 graph.initGraph(2, 1);
108 graph.setTitle(0, "Velocities");
109 graph.setTitle(1, "Error s-s*");
110 graph.setTitle(2, "Depth");
111 graph.setLegend(0, 0, "vx");
112 graph.setLegend(0, 1, "wz");
113 graph.setLegend(0, 2, "qdot_pan");
114 graph.setLegend(1, 0, "x");
115 graph.setLegend(1, 1, "log(Z/Z*)");
116 graph.setLegend(2, 0, "Z");
117#endif
118
119 int iter = 0;
120 for (;;) {
121 robot.getPosition(wMc);
122 cMo = wMc.inverse() * wMo;
123
124 point.track(cMo);
125
126 // Update the current x feature
127 vpFeatureBuilder::create(s_x, point);
128
129 // Update log(Z/Z*) feature. Since the depth Z change, we need to update
130 // the intection matrix
131 Z = point.get_Z();
132 s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd));
133
134 robot.get_cVe(cVe);
135 task.set_cVe(cVe);
136 robot.get_eJe(eJe);
137 task.set_eJe(eJe);
138
139 // Compute the control law. Velocities are computed in the mobile robot
140 // reference frame
142
143 // Send the velocity to the robot
145
146#ifdef VISP_HAVE_DISPLAY
147 graph.plot(0, iter, v); // plot velocities applied to the robot
148 graph.plot(1, iter, task.getError()); // plot error vector
149 graph.plot(2, 0, iter, Z); // plot the depth
150#endif
151 iter++;
152
153 if (task.getError().sumSquare() < 0.0001) {
154 std::cout << "Reached a small error. We stop the loop... " << std::endl;
155 break;
156 }
157 }
158#ifdef VISP_HAVE_DISPLAY
159 const char *legend = "Click to quit...";
160 vpDisplay::displayText(graph.I, (int)graph.I.getHeight() - 60, (int)graph.I.getWidth() - 150, legend, vpColor::red);
161 vpDisplay::flush(graph.I);
162 vpDisplay::getClick(graph.I);
163#endif
164
165 // Kill the servo task
166 task.print();
167 } catch (const vpException &e) {
168 std::cout << "Catch an exception: " << e << std::endl;
169 }
170}
Implementation of column vector and the associated operations.
Definition: vpColVector.h:131
double sumSquare() const
static const vpColor red
Definition: vpColor.h:217
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emited by ViSP classes.
Definition: vpException.h:72
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Class that defines a 3D point visual feature which is composed by one parameters that is that defin...
void buildFrom(double x, double y, double Z, double LogZoverZstar)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
void buildFrom(double x, double y, double Z)
static unsigned int selectX()
double get_y() const
double get_x() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void insert(const vpRotationMatrix &R)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:154
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:116
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:82
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
void get_eJe(vpMatrix &eJe)
@ ARTICULAR_FRAME
Definition: vpRobot.h:78
Implementation of a rotation matrix and operations on such kind of matrices.
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:567
@ EYEINHAND_L_cVe_eJe
Definition: vpServo.h:159
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition: vpServo.h:448
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:306
void setLambda(double c)
Definition: vpServo.h:404
void set_eJe(const vpMatrix &eJe_)
Definition: vpServo.h:506
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:218
vpColVector getError() const
Definition: vpServo.h:278
@ PSEUDO_INVERSE
Definition: vpServo.h:202
vpColVector computeControlLaw()
Definition: vpServo.cpp:929
@ CURRENT
Definition: vpServo.h:182
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:490
Class that defines the Pioneer mobile robot simulator equipped with a camera able to move in pan.
vpVelocityTwistMatrix get_cVe() const
Definition: vpUnicycle.h:82