Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
servoAfma6Line2DCamVelocity.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
44
45#include <iostream>
46#include <visp3/core/vpConfig.h>
47
48#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_AFMA6)
49
50#include <visp3/core/vpImage.h>
51#include <visp3/core/vpHomogeneousMatrix.h>
52#include <visp3/core/vpLine.h>
53#include <visp3/core/vpMath.h>
54#include <visp3/gui/vpDisplayFactory.h>
55#include <visp3/robot/vpRobotAfma6.h>
56#include <visp3/sensor/vpRealSense2.h>
57#include <visp3/me/vpMeLine.h>
58#include <visp3/visual_features/vpFeatureBuilder.h>
59#include <visp3/visual_features/vpFeatureLine.h>
60#include <visp3/vs/vpServo.h>
61#include <visp3/vs/vpServoDisplay.h>
62
63int main()
64{
65#ifdef ENABLE_VISP_NAMESPACE
66 using namespace VISP_NAMESPACE_NAME;
67#endif
68 vpRobotAfma6 robot;
70
71 // Load the end-effector to camera frame transformation obtained
72 // using a camera intrinsic model with distortion
73 robot.init(vpAfma6::TOOL_INTEL_D435_CAMERA, projModel);
74
75 try {
76 std::cout << "WARNING: This example will move the robot! "
77 << "Please make sure to have the user stop button at hand!" << std::endl
78 << "Press Enter to continue..." << std::endl;
79 std::cin.ignore();
80
81 vpRealSense2 rs;
82 rs2::config config;
83 unsigned int width = 640, height = 480, fps = 60;
84 config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, fps);
85 config.enable_stream(RS2_STREAM_DEPTH, width, height, RS2_FORMAT_Z16, fps);
86 config.enable_stream(RS2_STREAM_INFRARED, width, height, RS2_FORMAT_Y8, fps);
87 rs.open(config);
88
89 // Warm up camera
91 for (size_t i = 0; i < 10; ++i) {
92 rs.acquire(I);
93 }
94
95 // Get camera intrinsics
97 robot.getCameraParameters(cam, I);
98 std::cout << "cam:\n" << cam << std::endl;
99
100 std::shared_ptr<vpDisplay> d = vpDisplayFactory::createDisplay(I, 10, 10, "Current image");
101
104
105 vpMe me;
106 me.setRange(10);
107 me.setPointsToTrack(100);
109 me.setThreshold(10);
110 me.setSampleStep(10);
111
112 vpMeLine line;
114 line.setMe(&me);
115
116 // Initialize the tracking. Define the line to track.
117 line.initTracking(I);
118 line.track(I);
120
121 // Sets the current position of the visual feature
122 vpFeatureLine s_line;
123 vpFeatureBuilder::create(s_line, cam, line);
124
125 // Sets the desired position of the visual feature
126 vpLine line_d;
127 line_d.setWorldCoordinates(1, 0, 0, 0, 0, 0, 1, 0);
128 vpHomogeneousMatrix c_M_o(0, 0, 0.3, vpMath::rad(0), vpMath::rad(0), vpMath::rad(0));
129 line_d.project(c_M_o);
130
131 vpFeatureLine s_line_d;
132 vpFeatureBuilder::create(s_line_d, line_d);
133
134 // Define the task
136 // - We want an eye-in-hand control law
137 // - Robot is controlled in the camera frame
139 // - We want to see a line on a line
140 task.addFeature(s_line, s_line_d);
141 // - Set the gain
142 task.setLambda(0.5);
143 // - Display task information
144 task.print();
145
146 robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
147
148 bool final_quit = false;
149 bool send_velocities = false;
150
151 while (!final_quit) {
152 double t_start = vpTime::measureTimeMs();
153 rs.acquire(I);
155
156 // Track the line
157 line.track(I);
158 line.display(I, vpColor::red);
159
160 // Update the current line feature
161 vpFeatureBuilder::create(s_line, cam, line);
162
163 // Display the current and the desired features
164 s_line.display(cam, I, vpColor::red);
165 s_line_d.display(cam, I, vpColor::green);
166
167 vpColVector v = task.computeControlLaw();
168
169 if (!send_velocities) {
170 v = 0;
171 }
172
173 // Send camera frame velocities to the robot
174 robot.setVelocity(vpRobot::CAMERA_FRAME, v);
175
176 {
177 std::stringstream ss;
178 ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
179 vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
180 ss.clear();
181 ss.str("");
182 ss << "Loop time: " << vpTime::measureTimeMs() - t_start << " ms";
183 vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red);
184 }
185
187
189 if (vpDisplay::getClick(I, button, false)) {
190 switch (button) {
192 send_velocities = !send_velocities;
193 break;
194
196 final_quit = true;
197 break;
198
199 default:
200 break;
201 }
202 }
203 }
204
205 std::cout << "Stop the robot " << std::endl;
206 robot.setRobotState(vpRobot::STATE_STOP);
207
208 if (!final_quit) {
209 while (!final_quit) {
210 rs.acquire(I);
212
213 vpDisplay::displayText(I, 20, 20, "Click to quit the program.", vpColor::red);
214
215 if (vpDisplay::getClick(I, false)) {
216 final_quit = true;
217 }
218
220 }
221 }
222
223 // Display task information
224 task.print();
225 return EXIT_SUCCESS;
226 }
227 catch (const vpException &e) {
228 std::cout << "Test failed with exception: " << e << std::endl;
229 return EXIT_FAILURE;
230 }
231}
232
233#else
234int main()
235{
236 std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
237 return EXIT_SUCCESS;
238}
239
240#endif
@ TOOL_INTEL_D435_CAMERA
Definition vpAfma6.h:129
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with 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)
Class that defines a 2D line visual feature which is composed by two parameters that are and ,...
void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpColor &color=vpColor::green, unsigned int thickness=1) const VP_OVERRIDE
Implementation of an homogeneous matrix and operations on such kind of matrices.
Definition of the vpImage class member functions.
Definition vpImage.h:131
Class that defines a 3D line in the object frame and allows forward projection of the line in the cam...
Definition vpLine.h:103
void setWorldCoordinates(const double &oA1, const double &oB1, const double &oC1, const double &oD1, const double &oA2, const double &oB2, const double &oC2, const double &oD2)
Definition vpLine.cpp:87
static double rad(double deg)
Definition vpMath.h:129
Class that tracks in an image a line moving edges.
Definition vpMeLine.h:157
void display(const vpImage< unsigned char > &I, const vpColor &color, unsigned int thickness=1)
Definition vpMeLine.cpp:177
void track(const vpImage< unsigned char > &I)
Definition vpMeLine.cpp:607
void initTracking(const vpImage< unsigned char > &I)
Definition vpMeLine.cpp:187
@ RANGE_RESULT
Definition vpMeSite.h:85
void setDisplay(vpMeSite::vpMeSiteDisplayType select)
void setMe(vpMe *me)
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.
@ CAMERA_FRAME
Definition vpRobot.h:81
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
@ EYEINHAND_CAMERA
Definition vpServo.h:176
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT double measureTimeMs()