Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
tutorial-simu-pioneer-continuous-gain-constant.cpp
1 
19 #include <iostream>
20 
21 #include <visp3/core/vpConfig.h>
22 #include <visp3/core/vpHomogeneousMatrix.h>
23 #include <visp3/core/vpVelocityTwistMatrix.h>
24 #include <visp3/gui/vpPlot.h>
25 #include <visp3/robot/vpSimulatorPioneer.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 
31 int main()
32 {
33 #if defined(ENABLE_VISP_NAMESPACE)
34  using namespace VISP_NAMESPACE_NAME;
35 #endif
36  try {
38  cdMo[1][3] = 1.2;
39  cdMo[2][3] = 0.5;
40 
42  cMo[0][3] = 0.3;
43  cMo[1][3] = cdMo[1][3];
44  cMo[2][3] = 1.;
45  vpRotationMatrix cRo(0, atan2(cMo[0][3], cMo[1][3]), 0);
46  cMo.insert(cRo);
47 
48  vpSimulatorPioneer robot;
49  robot.setSamplingTime(0.04);
50  vpHomogeneousMatrix wMc, wMo;
51  robot.getPosition(wMc);
52  wMo = wMc * cMo;
53 
54  vpPoint point(0, 0, 0);
55  point.track(cMo);
56 
57  vpServo task;
60  task.setLambda(0.2);
62  cVe = robot.get_cVe();
63  task.set_cVe(cVe);
64 
65  vpMatrix eJe;
66  robot.get_eJe(eJe);
67  task.set_eJe(eJe);
68 
69  vpFeaturePoint s_x, s_xd;
70  vpFeatureBuilder::create(s_x, point);
71  s_xd.buildFrom(0, 0, cdMo[2][3]);
72  task.addFeature(s_x, s_xd, vpFeaturePoint::selectX());
73 
74  vpFeatureDepth s_Z, s_Zd;
75  double Z = point.get_Z();
76  double Zd = cdMo[2][3];
77  s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd));
78  s_Zd.buildFrom(0, 0, Zd, 0);
79  task.addFeature(s_Z, s_Zd);
80 
81 #ifdef VISP_HAVE_DISPLAY
82  // Create a window (800 by 500) at position (400, 10) with 3 graphics
83  vpPlot graph(3, 800, 500, 400, 10, "Curves...");
84 
85  // Init the curve plotter
86  graph.initGraph(0, 2);
87  graph.initGraph(1, 2);
88  graph.initGraph(2, 1);
89  graph.setTitle(0, "Velocities");
90  graph.setTitle(1, "Error s-s*");
91  graph.setTitle(2, "Depth");
92  graph.setLegend(0, 0, "vx");
93  graph.setLegend(0, 1, "wz");
94  graph.setLegend(1, 0, "x");
95  graph.setLegend(1, 1, "log(Z/Z*)");
96  graph.setLegend(2, 0, "Z");
97 #endif
98 
99  int iter = 0;
100  for (;;) {
101  robot.getPosition(wMc);
102  cMo = wMc.inverse() * wMo;
103 
104  point.track(cMo);
105 
106  vpFeatureBuilder::create(s_x, point);
107 
108  Z = point.get_Z();
109  s_Z.buildFrom(s_x.get_x(), s_x.get_y(), Z, log(Z / Zd));
110 
111  robot.get_cVe(cVe);
112  task.set_cVe(cVe);
113  robot.get_eJe(eJe);
114  task.set_eJe(eJe);
115 
116  vpColVector v = task.computeControlLaw(iter * robot.getSamplingTime());
118 
119 #ifdef VISP_HAVE_DISPLAY
120  graph.plot(0, iter, v); // plot velocities applied to the robot
121  graph.plot(1, iter, task.getError()); // plot error vector
122  graph.plot(2, 0, iter, Z); // plot the depth
123 #endif
124 
125  iter++;
126 
127  if (task.getError().sumSquare() < 0.0001) {
128  std::cout << "Reached a small error. We stop the loop... " << std::endl;
129  break;
130  }
131  }
132 #ifdef VISP_HAVE_DISPLAY
133  graph.saveData(0, "./v2.dat");
134  graph.saveData(1, "./error2.dat");
135 
136  const char *legend = "Click to quit...";
137  vpDisplay::displayText(graph.I, (int)graph.I.getHeight() - 60, (int)graph.I.getWidth() - 150, legend, vpColor::red);
138  vpDisplay::flush(graph.I);
139  vpDisplay::getClick(graph.I);
140 #endif
141 
142  // Kill the servo task
143  task.print();
144  }
145  catch (const vpException &e) {
146  std::cout << "Catch an exception: " << e << std::endl;
147  }
148 }
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
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 emitted by ViSP classes.
Definition: vpException.h:60
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
Class that defines a 3D point visual feature which is composed by one parameters that is that defin...
vpFeatureDepth & buildFrom(const double &x, const double &y, const double &Z, const double &LogZoverZstar)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
vpFeaturePoint & buildFrom(const double &x, const double &y, const 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:169
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:112
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
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:380
@ EYEINHAND_L_cVe_eJe
Definition: vpServo.h:168
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:331
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition: vpServo.h:1038
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:171
void setLambda(double c)
Definition: vpServo.h:986
void set_eJe(const vpMatrix &eJe_)
Definition: vpServo.h:1101
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:134
vpColVector getError() const
Definition: vpServo.h:510
@ PSEUDO_INVERSE
Definition: vpServo.h:235
vpColVector computeControlLaw()
Definition: vpServo.cpp:705
@ DESIRED
Definition: vpServo.h:208
Class that defines the Pioneer mobile robot simulator equipped with a static camera.
vpVelocityTwistMatrix get_cVe() const
Definition: vpUnicycle.h:72