Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
servoAfma6SquareLines2DCamVelocity.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * tests the control law
32 * eye-in-hand control
33 * velocity computed in the camera frame
34 */
35
45
54
55#include <iostream>
56#include <visp3/core/vpConfig.h>
57
58#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_AFMA6)
59
60#include <visp3/core/vpImage.h>
61#include <visp3/core/vpHomogeneousMatrix.h>
62#include <visp3/core/vpLine.h>
63#include <visp3/core/vpMath.h>
64#include <visp3/gui/vpDisplayFactory.h>
65#include <visp3/robot/vpRobotAfma6.h>
66#include <visp3/sensor/vpRealSense2.h>
67#include <visp3/me/vpMeLine.h>
68#include <visp3/visual_features/vpFeatureBuilder.h>
69#include <visp3/visual_features/vpFeatureLine.h>
70#include <visp3/vs/vpServo.h>
71#include <visp3/vs/vpServoDisplay.h>
72
73int main()
74{
75#ifdef ENABLE_VISP_NAMESPACE
76 using namespace VISP_NAMESPACE_NAME;
77#endif
78
79 try {
80 vpRealSense2 rs;
81 rs2::config config;
82 unsigned int width = 640, height = 480, fps = 60;
83 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
84 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
85 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
86 rs.open(config);
87
89
90 // Warm up camera
91 for (size_t i = 0; i < 10; ++i) {
92 rs.acquire(I);
93 }
94
95 std::shared_ptr<vpDisplay> d = vpDisplayFactory::createDisplay(I, 10, 10, "Current image");
96
99
100 std::cout << "-------------------------------------------------------" << std::endl;
101 std::cout << " Test program for vpServo " << std::endl;
102 std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl;
103 std::cout << " Simulation " << std::endl;
104 std::cout << " task : servo a line " << std::endl;
105 std::cout << "-------------------------------------------------------" << std::endl;
106
107 int nb_lines = 4;
108
109 std::vector<vpMeLine> line(nb_lines);
110
111 vpMe me;
112 me.setRange(10);
113 me.setPointsToTrack(100);
115 me.setThreshold(20);
116 me.setSampleStep(10);
117
118 // Initialize the tracking. Define the four lines to track.
119 for (int i = 0; i < nb_lines; ++i) {
120 line[i].setDisplay(vpMeSite::RANGE_RESULT);
121 line[i].setMe(&me);
122
123 line[i].initTracking(I);
124 line[i].track(I);
125 }
126
127 vpRobotAfma6 robot;
129
130 // Get camera intrinsics
132 robot.getCameraParameters(cam, I);
133
134 // Sets the current position of the visual feature
135 std::vector<vpFeatureLine> s_line(nb_lines);
136 for (int i = 0; i < nb_lines; ++i)
137 vpFeatureBuilder::create(s_line[i], cam, line[i]);
138
139 // Sets the desired position of the visual feature
140 std::vector<vpLine> line_d(nb_lines);
141 line_d[0].setWorldCoordinates(1, 0, 0, 0.05, 0, 0, 1, 0);
142 line_d[1].setWorldCoordinates(0, 1, 0, 0.05, 0, 0, 1, 0);
143 line_d[2].setWorldCoordinates(1, 0, 0, -0.05, 0, 0, 1, 0);
144 line_d[3].setWorldCoordinates(0, 1, 0, -0.05, 0, 0, 1, 0);
145
146 vpHomogeneousMatrix c_M_o(0, 0, 0.5, 0, 0, vpMath::rad(0));
147
148 line_d[0].project(c_M_o);
149 line_d[1].project(c_M_o);
150 line_d[2].project(c_M_o);
151 line_d[3].project(c_M_o);
152
153 // Those lines are needed to keep the conventions define in vpMeLine
154 // (Those in vpLine are less restrictive) Another way to have the
155 // coordinates of the desired features is to learn them before executing
156 // the program.
157 line_d[0].setRho(-fabs(line_d[0].getRho()));
158 line_d[0].setTheta(0);
159 line_d[1].setRho(-fabs(line_d[1].getRho()));
160 line_d[1].setTheta(M_PI / 2);
161 line_d[2].setRho(-fabs(line_d[2].getRho()));
162 line_d[2].setTheta(M_PI);
163 line_d[3].setRho(-fabs(line_d[3].getRho()));
164 line_d[3].setTheta(-M_PI / 2);
165
166 std::vector<vpFeatureLine> s_line_d(nb_lines);
167
168 vpFeatureBuilder::create(s_line_d[0], line_d[0]);
169 vpFeatureBuilder::create(s_line_d[1], line_d[1]);
170 vpFeatureBuilder::create(s_line_d[2], line_d[2]);
171 vpFeatureBuilder::create(s_line_d[3], line_d[3]);
172
173 // Define the task
174 // - we want an eye-in-hand control law
175 // - robot is controlled in the camera frame
178 task.setInteractionMatrixType(vpServo::DESIRED, vpServo::PSEUDO_INVERSE);
179
180 // - we want to see 4 lines on 4 lines
181 for (int i = 0; i < nb_lines; ++i) {
182 task.addFeature(s_line[i], s_line_d[i]);
183 }
184
185 // - set the gain
186 task.setLambda(0.2);
187
188 // - display task information
189 task.print();
190
191 robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
192
193 bool quit = false;
194 while (!quit) {
195 rs.acquire(I);
197
198 // Track the lines and update the features
199 for (int i = 0; i < nb_lines; ++i) {
200 line[i].track(I);
201 line[i].display(I, vpColor::red);
202
203 vpFeatureBuilder::create(s_line[i], cam, line[i]);
204
205 s_line[i].display(cam, I, vpColor::red);
206 s_line_d[i].display(cam, I, vpColor::green);
207 }
208
209 vpColVector v_c = task.computeControlLaw();
210
211 robot.setVelocity(vpRobot::CAMERA_FRAME, v_c);
212
213 vpDisplay::displayText(I, 20, 20, "Click to quit...", vpColor::red);
214 if (vpDisplay::getClick(I, false)) {
215 quit = true;
216 }
217
219 }
220
221 // Display task information
222 task.print();
223 return EXIT_SUCCESS;
224 }
225 catch (const vpException &e) {
226 std::cout << "Visual servo failed with exception: " << e << std::endl;
227 return EXIT_FAILURE;
228 }
229}
230
231#else
232int main()
233{
234 std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
235 return EXIT_SUCCESS;
236}
237
238#endif
@ TOOL_INTEL_D435_CAMERA
Definition vpAfma6.h:129
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
static const vpColor red
Definition vpColor.h:198
static const vpColor green
Definition vpColor.h:201
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
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 vpDot &d)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Definition of the vpImage class member functions.
Definition vpImage.h:131
static double rad(double deg)
Definition vpMath.h:129
@ RANGE_RESULT
Definition vpMeSite.h:85
Definition vpMe.h:143
void setPointsToTrack(const int &points_to_track)
Definition vpMe.h:431
void setRange(const unsigned int &range)
Definition vpMe.h:438
void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type)
Definition vpMe.h:531
void setThreshold(const double &threshold)
Definition vpMe.h:489
void setSampleStep(const double &sample_step)
Definition vpMe.h:445
@ NORMALIZED_THRESHOLD
Definition vpMe.h:154
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
bool open(const rs2::config &cfg=rs2::config())
Control of Irisa's gantry robot named Afma6.
void init(void)
@ CAMERA_FRAME
Definition vpRobot.h:81
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ EYEINHAND_CAMERA
Definition vpServo.h:176
@ PSEUDO_INVERSE
Definition vpServo.h:250
@ DESIRED
Definition vpServo.h:223
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.