1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357
|
/*
* ViSP, open source Visual Servoing Platform software.
* Copyright (C) 2005 - 2025 by Inria. All rights reserved.
*
* This software is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
* See the file LICENSE.txt at the root directory of this source
* distribution for additional information about the GNU GPL.
*
* For using ViSP with software that can not be combined with the GNU
* GPL, please contact Inria about acquiring a ViSP Professional
* Edition License.
*
* See https://visp.inria.fr for more information.
*
* This software was developed at:
* Inria Rennes - Bretagne Atlantique
* Campus Universitaire de Beaulieu
* 35042 Rennes Cedex
* France
*
* If you have questions regarding the use of this file, please contact
* Inria at visp@inria.fr
*
* This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
* WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*
* Description:
* tests the control law
* eye-in-hand control
* velocity computed in articular
*/
/*!
* \file servoBiclopsPoint2DArtVelocity.cpp
* \example servoBiclopsPoint2DArtVelocity.cpp
*
* Example of eye-in-hand control law. We control here a real robot, the
* Biclops robot (pan-tilt head provided by Traclabs). The velocity is computed
* in articular. The visual feature is the center of gravity of a point.
*/
#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
#include <visp3/core/vpDisplay.h>
#include <visp3/core/vpException.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/core/vpImage.h>
#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/gui/vpDisplayFactory.h>
#include <visp3/io/vpParseArgv.h>
#include <visp3/robot/vpRobotBiclops.h>
#include <visp3/sensor/vpRealSense2.h>
#include <visp3/visual_features/vpFeatureBuilder.h>
#include <visp3/visual_features/vpFeaturePoint.h>
#include <visp3/vs/vpServo.h>
#include <visp3/vs/vpServoDisplay.h>
// List of allowed command line options
#define GETOPTARGS "c:d:h"
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
/*!
* Print the program options.
*
* \param name : Program name.
* \param badparam : Bad parameter name.
* \param conf : Robot configuration file.
*/
void usage(const char *name, const char *badparam, std::string &conf)
{
fprintf(stdout, "\n\
Example of eye-in-hand control law. We control here a real robot, the biclops\n\
robot (pan-tilt head provided by Traclabs) equipped with a Realsense camera\n\
mounted on its end-effector. The velocity to apply to the PT head is joint\n\
velocity. The visual feature is a point corresponding to the center of\n\
gravity of an AprilTag. \n\
\n\
SYNOPSIS\n\
%s [-c <Biclops configuration file>] [-h]\n",
name);
fprintf(stdout, "\n\
OPTIONS: Default\n\
-c <Biclops configuration file> %s\n\
Sets the Biclops robot configuration file.\n",
conf.c_str());
if (badparam) {
fprintf(stderr, "ERROR: \n");
fprintf(stderr, "\nBad parameter [%s]\n", badparam);
}
}
/*!
* Set the program options.
*
* \param argc : Command line number of parameters.
* \param argv : Array of command line parameters.
* \param conf : Robot configuration file.
*
* \return false if the program has to be stopped, true otherwise.
*
*/
bool getOptions(int argc, const char **argv, std::string &conf)
{
const char *optarg_;
int c;
while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
switch (c) {
case 'c':
conf = optarg_;
break;
case 'h':
usage(argv[0], nullptr, conf);
return false;
default:
usage(argv[0], optarg_, conf);
return false;
}
}
if ((c == 1) || (c == -1)) {
// standalone param or error
usage(argv[0], nullptr, conf);
std::cerr << "ERROR: " << std::endl;
std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
return false;
}
return true;
}
int main(int argc, const char **argv)
{
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
std::shared_ptr<vpDisplay> display;
#else
vpDisplay *display = nullptr;
#endif
try {
// Default unix configuration file path
std::string opt_conf = "/usr/share/BiclopsDefault.cfg";
// Read the command line options
if (getOptions(argc, argv, opt_conf) == false) {
return EXIT_FAILURE;
}
// Initialize PTU
vpRobotBiclops robot(opt_conf);
/*
* Biclops DH2 has the following axis orientation
*
* tilt + <---- (end-effector-frame)
* |
* \/ pan +
*
* The end-effector-frame from PT unit rear view is the following
*
* /\ x
* |
* (e) ----> y
*
*
*
* The camera frame attached to the PT unit is the following (rear view)
*
* (c) ----> x
* |
* \/ y
*
* The corresponding cRe (camera to end-effector rotation matrix) is then the following
*
* ( 0 1 0)
* cRe = (-1 0 0)
* ( 0 0 1)
*
* Translation cte (camera to end-effector) can be neglected
*
* (0)
* cte = (0)
* (0)
*/
robot.setDenavitHartenbergModel(vpBiclops::DH2);
vpRotationMatrix cRe;
cRe[0][0] = 0; cRe[0][1] = 1; cRe[0][2] = 0;
cRe[1][0] = -1; cRe[1][1] = 0; cRe[1][2] = 0;
cRe[2][0] = 0; cRe[2][1] = 0; cRe[2][2] = 1;
vpTranslationVector cte; // By default set to 0
// Robot Jacobian (expressed in the end-effector frame)
vpMatrix eJe;
// Camera to end-effector frame transformation
vpHomogeneousMatrix cMe(cte, cRe);
// Velocity twist transformation to express a velocity from end-effector to camera frame
vpVelocityTwistMatrix cVe(cMe);
// Initialize grabber
vpRealSense2 g;
rs2::config config;
config.disable_stream(RS2_STREAM_DEPTH);
config.disable_stream(RS2_STREAM_INFRARED);
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
g.open(config);
std::cout << "Read camera parameters from Realsense device" << std::endl;
vpCameraParameters cam;
cam = g.getCameraParameters(RS2_STREAM_COLOR, vpCameraParameters::perspectiveProjWithoutDistortion);
vpColVector q(vpBiclops::ndof);
q = 0;
std::cout << "Move PT to initial position: " << q.t() << std::endl;
robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);
robot.setPosition(vpRobot::JOINT_STATE, q);
vpImage<unsigned char> I;
g.acquire(I);
// We open a window using either X11 or GTK or GDI.
// Its size is automatically defined by the image (I) size
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
display = vpDisplayFactory::createDisplay(I, 100, 100, "Display GDI...");
#else
display = vpDisplayFactory::allocateDisplay(I, 100, 100, "Display GDI...");
#endif
vpDisplay::display(I);
vpDisplay::flush(I);
vpDetectorAprilTag detector;
vpServo task;
// Create current and desired point visual feature
vpFeaturePoint p, pd;
// Sets the desired position of the visual feature
// Here we set Z desired to 1 meter, and (x,y)=(0,0) to center the tag in the image
pd.buildFrom(0, 0, 1);
// Define the task
// - we want an eye-in-hand control law
// - joint velocities are computed
// - interaction matrix is the one at desired position
task.setServo(vpServo::EYEINHAND_L_cVe_eJe);
task.setInteractionMatrixType(vpServo::DESIRED, vpServo::PSEUDO_INVERSE);
task.set_cVe(cVe);
// We want to see a point on a point
task.addFeature(p, pd);
// Set the gain
task.setLambda(0.2);
robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
bool quit = false;
bool send_velocities = false;
vpColVector q_dot;
while (!quit) {
g.acquire(I);
vpDisplay::display(I);
{
std::stringstream ss;
ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
}
if (detector.detect(I)) {
// We consider the first tag only
vpImagePoint cog = detector.getCog(0); // 0 is the id of the first tag
vpFeatureBuilder::create(p, cam, cog);
// Get the jacobian
robot.get_eJe(eJe);
task.set_eJe(eJe);
q_dot = task.computeControlLaw();
vpServoDisplay::display(task, cam, I);
vpDisplay::flush(I);
std::cout << "q_dot: " << q_dot.t() << std::endl;
std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl;
}
else {
q_dot = 0;
}
if (!send_velocities) {
q_dot = 0;
}
robot.setVelocity(vpRobot::JOINT_STATE, q_dot);
vpDisplay::flush(I);
vpMouseButton::vpMouseButtonType button;
if (vpDisplay::getClick(I, button, false)) {
switch (button) {
case vpMouseButton::button1:
send_velocities = !send_velocities;
break;
case vpMouseButton::button3:
quit = true;
q_dot = 0;
break;
default:
break;
}
}
}
std::cout << "Stop the robot " << std::endl;
robot.setRobotState(vpRobot::STATE_STOP);
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_SUCCESS;
}
catch (const vpException &e) {
std::cout << "Catch an exception: " << e.getMessage() << std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_FAILURE;
}
}
#else
int main()
{
std::cout << "You do not have an Biclops PT robot connected to your computer..." << std::endl;
return EXIT_SUCCESS;
}
#endif
|