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
|
/****************************************************************************
*
* ViSP, open source Visual Servoing Platform software.
* Copyright (C) 2005 - 2023 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
* Authors:
*
*****************************************************************************/
/*!
\file moveBiclops.cpp
\brief Example of a real robot control, the biclops robot (pan-tilt turret)
by Traclabs. The robot is controlled first in position, then in velocity.
See http://www.traclabs.com/tracbiclops.htm for more details.
*/
/*!
\example moveBiclops.cpp
Example of a real robot control, the biclops robot (pan-tilt turret) by
Traclabs. The robot is controlled first in position, then in velocity.
See http://www.traclabs.com/tracbiclops.htm for more details.
*/
#include <stdlib.h>
#include <visp3/core/vpColVector.h>
#include <visp3/core/vpDebug.h>
#include <visp3/core/vpTime.h>
#include <visp3/io/vpParseArgv.h>
#ifdef VISP_HAVE_BICLOPS
#include <visp3/robot/vpRobotBiclops.h>
// List of allowed command line options
#define GETOPTARGS "c:h"
/*
Print the program options.
\param name : Program name.
\param badparam : Bad parameter name.
\param conf : Biclops configuration file.
*/
void usage(const char *name, const char *badparam, std::string conf)
{
fprintf(stdout, "\n\
Move the biclops robot\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\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 : Biclops 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], NULL, conf);
return false;
break;
default:
usage(argv[0], optarg_, conf);
return false;
break;
}
}
if ((c == 1) || (c == -1)) {
// standalone param or error
usage(argv[0], NULL, 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)
{
std::string opt_conf = "/usr/share/BiclopsDefault.cfg";
// Read the command line options
if (getOptions(argc, argv, opt_conf) == false) {
return EXIT_FAILURE;
}
try {
vpRobotBiclops robot(opt_conf.c_str());
vpColVector q(vpBiclops::ndof); // desired position
vpColVector qdot(vpBiclops::ndof); // desired velocity
vpColVector qm(vpBiclops::ndof); // measured position
vpColVector qm_dot(vpBiclops::ndof); // measured velocity
robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);
q = 0;
q[0] = vpMath::rad(-10);
q[1] = vpMath::rad(-20);
std::cout << "Set position in the articular frame: "
<< " pan: " << vpMath::deg(q[0]) << " deg"
<< " tilt: " << vpMath::deg(q[1]) << " deg" << std::endl;
robot.setPositioningVelocity(30.);
robot.setPosition(vpRobot::ARTICULAR_FRAME, q);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
q[0] = vpMath::rad(10);
q[1] = vpMath::rad(20);
std::cout << "Set position in the articular frame: "
<< " pan: " << vpMath::deg(q[0]) << " deg"
<< " tilt: " << vpMath::deg(q[1]) << " deg" << std::endl;
robot.setPositioningVelocity(10);
robot.setPosition(vpRobot::ARTICULAR_FRAME, q);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
std::cout << "Set STATE_VELOCITY_CONTROL" << std::endl;
robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " deg"
<< " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
qdot = 0;
// qdot[0] = vpMath::rad(0.1) ;
qdot[1] = vpMath::rad(25);
std::cout << "Set articular frame velocity "
<< " pan: " << vpMath::deg(qdot[0]) << " deg/s"
<< " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
robot.setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
// waits 5000ms
vpTime::wait(5000.0);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " deg"
<< " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
qdot = 0;
// qdot[0] = vpMath::rad(0.1) ;
qdot[1] = -vpMath::rad(25);
std::cout << "Set articular frame velocity "
<< " pan: " << vpMath::deg(qdot[0]) << " deg/s"
<< " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
robot.setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
// waits 3000 ms
vpTime::wait(3000.0);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " deg"
<< " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
qdot = 0;
// qdot[0] = vpMath::rad(0.1) ;
qdot[1] = vpMath::rad(10);
std::cout << "Set articular frame velocity "
<< " pan: " << vpMath::deg(qdot[0]) << " deg/s"
<< " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
robot.setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
// waits 2000 ms
vpTime::wait(2000.0);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " deg"
<< " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
qdot = 0;
qdot[0] = vpMath::rad(-5);
// qdot[1] = vpMath::rad(-5);
std::cout << "Set articular frame velocity "
<< " pan: " << vpMath::deg(qdot[0]) << " deg/s"
<< " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
robot.setVelocity(vpRobot::ARTICULAR_FRAME, qdot);
// waits 2000 ms
vpTime::wait(2000.0);
robot.getPosition(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Position in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " deg"
<< " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
robot.getVelocity(vpRobot::ARTICULAR_FRAME, qm);
std::cout << "Velocity in the articular frame: "
<< " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
return EXIT_SUCCESS;
} catch (const vpException &e) {
std::cout << "Catch an exception: " << e.getMessage() << std::endl;
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
|