Visual Servoing Platform  version 3.6.1 under development (2024-05-09)
moveBiclops.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 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  */
33 
44 #include <iostream>
45 
46 #include <visp3/core/vpConfig.h>
47 
48 #ifdef VISP_HAVE_BICLOPS
49 
50 #include <visp3/robot/vpRobotBiclops.h>
51 #include <visp3/io/vpParseArgv.h>
52 
53 // List of allowed command line options
54 #define GETOPTARGS "c:h"
55 
56 /*
57  * Print the program options.
58  *
59  * \param name : Program name.
60  * \param badparam : Bad parameter name.
61  * \param conf : Biclops configuration file.
62  */
63 void usage(const char *name, const char *badparam, std::string conf)
64 {
65  fprintf(stdout, "\n\
66 Move the Biclops robot\n\
67 \n\
68 SYNOPSIS\n\
69  %s [-c <Biclops configuration file>] [-h]\n\
70 ",
71 name);
72 
73  fprintf(stdout, "\n\
74 OPTIONS: Default\n\
75  -c <Biclops configuration file> %s\n\
76  Sets the Biclops robot configuration file.\n\n",
77  conf.c_str());
78 
79  if (badparam) {
80  fprintf(stderr, "ERROR: \n");
81  fprintf(stderr, "\nBad parameter [%s]\n", badparam);
82  }
83 }
84 
94 bool getOptions(int argc, const char **argv, std::string &conf)
95 {
96  const char *optarg_;
97  int c;
98  while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
99 
100  switch (c) {
101  case 'c':
102  conf = optarg_;
103  break;
104  case 'h':
105  usage(argv[0], nullptr, conf);
106  return false;
107  break;
108 
109  default:
110  usage(argv[0], optarg_, conf);
111  return false;
112  break;
113  }
114  }
115 
116  if ((c == 1) || (c == -1)) {
117  // standalone param or error
118  usage(argv[0], nullptr, conf);
119  std::cerr << "ERROR: " << std::endl;
120  std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
121  return false;
122  }
123 
124  return true;
125 }
126 
127 int main(int argc, const char **argv)
128 {
129  std::string opt_conf = "/usr/share/BiclopsDefault.cfg";
130 
131  // Read the command line options
132  if (getOptions(argc, argv, opt_conf) == false) {
133  return EXIT_FAILURE;
134  }
135  try {
136  vpRobotBiclops robot(opt_conf);
137 
138  vpColVector q(vpBiclops::ndof); // desired position
139  vpColVector qdot(vpBiclops::ndof); // desired velocity
140  vpColVector qm(vpBiclops::ndof); // measured position
141  vpColVector qm_dot(vpBiclops::ndof); // measured velocity
142 
144 
145  q = 0;
146  q[0] = vpMath::rad(-10);
147  q[1] = vpMath::rad(-20);
148  std::cout << "Set Joint position "
149  << " pan: " << vpMath::deg(q[0]) << " deg"
150  << " tilt: " << vpMath::deg(q[1]) << " deg" << std::endl;
151  robot.setPositioningVelocity(30.);
152  robot.setPosition(vpRobot::JOINT_STATE, q);
153 
154  robot.getPosition(vpRobot::JOINT_STATE, qm);
155  std::cout << " Joint position "
156  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
158  std::cout << " Joint velocity "
159  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
160 
161  q[0] = vpMath::rad(10);
162  q[1] = vpMath::rad(20);
163  std::cout << "Set Joint position "
164  << " pan: " << vpMath::deg(q[0]) << " deg"
165  << " tilt: " << vpMath::deg(q[1]) << " deg" << std::endl;
166  robot.setPositioningVelocity(10);
167  robot.setPosition(vpRobot::JOINT_STATE, q);
168 
169  robot.getPosition(vpRobot::JOINT_STATE, qm);
170  std::cout << " Joint position: "
171  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
173  std::cout << " Joint velocity: "
174  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
175 
176  std::cout << "Set STATE_VELOCITY_CONTROL" << std::endl;
178 
179  robot.getPosition(vpRobot::JOINT_STATE, qm);
180  std::cout << " Joint position: "
181  << " pan: " << vpMath::deg(qm[0]) << " deg"
182  << " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
184  std::cout << " Joint velocity "
185  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
186 
187  qdot = 0;
188  // qdot[0] = vpMath::rad(0.1) ;
189  qdot[1] = vpMath::rad(25);
190  std::cout << "Set joint velocity for 5 sec"
191  << " pan: " << vpMath::deg(qdot[0]) << " deg/s"
192  << " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
193  robot.setVelocity(vpRobot::JOINT_STATE, qdot);
194 
195  // waits 5000ms
196  vpTime::wait(5000.0);
197 
198  robot.getPosition(vpRobot::JOINT_STATE, qm);
199  std::cout << " Joint position "
200  << " pan: " << vpMath::deg(qm[0]) << " deg"
201  << " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
203  std::cout << " Joint velocity "
204  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
205 
206  qdot = 0;
207  // qdot[0] = vpMath::rad(0.1) ;
208  qdot[1] = -vpMath::rad(25);
209  std::cout << "Set joint velocity for 3 sec"
210  << " pan: " << vpMath::deg(qdot[0]) << " deg/s"
211  << " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
212  robot.setVelocity(vpRobot::JOINT_STATE, qdot);
213 
214  // waits 3000 ms
215  vpTime::wait(3000.0);
216 
217  robot.getPosition(vpRobot::JOINT_STATE, qm);
218  std::cout << " Joint position "
219  << " pan: " << vpMath::deg(qm[0]) << " deg"
220  << " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
222  std::cout << " Joint velocity "
223  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
224 
225  qdot = 0;
226  // qdot[0] = vpMath::rad(0.1) ;
227  qdot[1] = vpMath::rad(10);
228  std::cout << "Set joint velocity for 2 sec"
229  << " pan: " << vpMath::deg(qdot[0]) << " deg/s"
230  << " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
231  robot.setVelocity(vpRobot::JOINT_STATE, qdot);
232 
233  // waits 2000 ms
234  vpTime::wait(2000.0);
235 
236  robot.getPosition(vpRobot::JOINT_STATE, qm);
237  std::cout << " Joint position "
238  << " pan: " << vpMath::deg(qm[0]) << " deg"
239  << " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
241  std::cout << " Joint velocity "
242  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
243 
244  qdot = 0;
245  qdot[0] = vpMath::rad(-5);
246  // qdot[1] = vpMath::rad(-5);
247 
248  std::cout << "Set joint velocity for 2 sec"
249  << " pan: " << vpMath::deg(qdot[0]) << " deg/s"
250  << " tilt: " << vpMath::deg(qdot[1]) << " deg/s" << std::endl;
251  robot.setVelocity(vpRobot::JOINT_STATE, qdot);
252 
253  // waits 2000 ms
254  vpTime::wait(2000.0);
255 
256  robot.getPosition(vpRobot::JOINT_STATE, qm);
257  std::cout << " Joint position "
258  << " pan: " << vpMath::deg(qm[0]) << " deg"
259  << " tilt: " << vpMath::deg(qm[1]) << " deg" << std::endl;
261  std::cout << " Joint velocity "
262  << " pan: " << vpMath::deg(qm[0]) << " tilt: " << vpMath::deg(qm[1]) << std::endl;
263  return EXIT_SUCCESS;
264  }
265  catch (const vpException &e) {
266  std::cout << "Catch an exception: " << e.getMessage() << std::endl;
267  return EXIT_FAILURE;
268  }
269 }
270 #else
271 int main()
272 {
273  std::cout << "You do not have an Biclops PT robot connected to your computer..." << std::endl;
274  return EXIT_SUCCESS;
275 }
276 
277 #endif
static const unsigned int ndof
Number of dof.
Definition: vpBiclops.h:99
Implementation of column vector and the associated operations.
Definition: vpColVector.h:163
error that can be emitted by ViSP classes.
Definition: vpException.h:59
const char * getMessage() const
Definition: vpException.cpp:64
static double rad(double deg)
Definition: vpMath.h:127
static double deg(double rad)
Definition: vpMath.h:117
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:69
Interface for the Biclops, pan, tilt head control.
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
@ JOINT_STATE
Definition: vpRobot.h:80
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:66
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:65
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:198
VISP_EXPORT int wait(double t0, double t)