This file is indexed.

/usr/include/visp/vpRobotAfma4.h is in libvisp-dev 2.9.0-3+b2.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

  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
/****************************************************************************
 *
 * $Id: vpRobotAfma4.h 4574 2014-01-09 08:48:51Z fspindle $
 *
 * This file is part of the ViSP software.
 * Copyright (C) 2005 - 2014 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
 * ("GPL") version 2 as published by the Free Software Foundation.
 * 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 http://www.irisa.fr/lagadic/visp/visp.html for more information.
 * 
 * This software was developed at:
 * INRIA Rennes - Bretagne Atlantique
 * Campus Universitaire de Beaulieu
 * 35042 Rennes Cedex
 * France
 * http://www.irisa.fr/lagadic
 *
 * 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:
 * Interface for the Irisa's Afma4 robot.
 *
 * Authors:
 * Fabien Spindler
 *
 *****************************************************************************/

#ifndef vpRobotAfma4_h
#define vpRobotAfma4_h

#include <visp/vpConfig.h>

#ifdef VISP_HAVE_AFMA4

#include <iostream>
#include <stdio.h>

#include <visp/vpRobot.h>
#include <visp/vpColVector.h>
#include <visp/vpDebug.h>
#include <visp/vpAfma4.h>

// low level controller api
extern "C" {
#  include "irisa_Afma4.h"
#  include "trycatch.h"
}


/*!
  \class vpRobotAfma4

  \ingroup Afma4 RobotDriver

  \brief Control of Irisa's cylindrical robot named Afma4.

  Implementation of the vpRobot class in order to control Irisa's
  Afma4 robot.  This robot is a cylindrical robot with five degrees of
  freedom but only four are actuated (see vpAfma4 documentation). It
  was manufactured in 1995 by the french Afma-Robots company. In 2008,
  the low level controller change for a more recent Adept technology
  based on the MotionBlox controller. A firewire camera is mounted on
  the end-effector to allow eye-in-hand visual servoing. The control
  of this camera is achieved by the vp1394TwoGrabber class. A
  Servolens lens is attached to the camera. It allows to control the
  focal lens, the iris and the focus throw a serial link. The control
  of the lens is possible using the vpServolens class.

  This class allows to control the Afma4 cylindrical robot in position
  and velocity:
  - in the joint space (vpRobot::ARTICULAR_FRAME), 
  - in the fixed reference frame (vpRobot::REFERENCE_FRAME), 
  - in the camera frame (vpRobot::CAMERA_FRAME),

  Mixed frame (vpRobot::MIXT_FRAME) where translations are expressed 
  in the reference frame and rotations in the camera frame is not implemented.

  All the translations are expressed in meters for positions and m/s
  for the velocities. Rotations are expressed in radians for the
  positions, and rad/s for the rotation velocities.

  The Denavit-Hartenberg representation as well as the direct and
  inverse kinematics models are given and implemented in the vpAfma4
  class.

  \warning A Ctrl-C, a segmentation fault or other system errors are
  catched by this class to stop the robot.

  To communicate with the robot, you may first create an instance of this
  class by calling the default constructor:

  \code
  vpRobotAfma4 robot;
  \endcode

  This initialize the robot kinematics with the eMc extrinsic camera
  parameters.

  To control the robot in position, you may set the controller
  to position control and than send the position to reach in a specific
  frame like here in the joint space:

  \code
  vpColVector q(4);
  // Set a joint position
  q[0] =  M_PI/2; // X axis, in radian
  q[1] =  0.2;    // Y axis, in meter
  q[2] = -M_PI/2; // A axis, in radian
  q[3] =  M_PI/8; // B axis, in radian

  // Initialize the controller to position control
  robot.setRobotState(vpRobot::STATE_POSITION_CONTROL);

  // Moves the robot in the joint space
  robot.setPosition(vpRobot::ARTICULAR_FRAME, q);
  \endcode

  The robot moves to the specified position with the default
  positioning velocity vpRobotAfma4::defaultPositioningVelocity. The
  setPositioningVelocity() method allows to change the maximal
  velocity used to reach the desired position.

  \code
  // Set the max velocity to 40%
  robot.setPositioningVelocity(40);

  // Moves the robot in the joint space
  robot.setPosition(vpRobot::ARTICULAR_FRAME, q);
  \endcode

  To control the robot in velocity, you may set the controller to
  velocity control and than send the velocities. To end the velocity
  control and stop the robot you have to set the controller to the
  stop state. Here is an example of a velocity control in the joint
  space:

  \code
  vpColVector qvel(6);
  // Set a joint velocity
  qvel[0] = M_PI/8; // X axis, in rad/s
  qvel[1] = 0.2;    // Y axis, in m/s
  qvel[2] = 0;      // A axis, in rad/s
  qvel[3] = M_PI/8; // B axis, in rad/s

  // Initialize the controller to position control
  robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);

  while (...) {
    // Apply a velocity in the joint space
    robot.setVelocity(vpRobot::ARTICULAR_FRAME, qvel);

    // Compute new velocities qvel...
  }

  // Stop the robot
  robot.setRobotState(vpRobot::STATE_STOP)
  \endcode

  There is also possible to measure the robot current position with
  getPosition() method and the robot current velocities with the getVelocity()
  method.

  For convenience, there is also the ability to read/write joint
  positions from a position file with readPosFile() and writePosFile()
  methods.
*/
class VISP_EXPORT vpRobotAfma4
  :
  public vpAfma4,
  public vpRobot
{

private: /* Not allowed functions. */

  /*!
    Copy constructor not allowed.
   */
  vpRobotAfma4 (const vpRobotAfma4 & robot);

private: /* Attributs prives. */

  /** \brief Vrai ssi aucun objet de la classe vpRobotAfma4 n'existe.
   *
   * Il ne peut exister simultanement qu'un seul objet de la classe
   * vpRobotAfma4, car il correspond a un seul robot AFMA4. Creer
   * simultanement deux objets peut engendrer des conflits. Le constructeur
   * lance une erreur si le champ n'est pas FAUX puis positionne le champ
   * a VRAI. Seul le destructeur repositionne le champ a FAUX, ce qui
   * alors la creation d'un nouvel objet.
   */
  static bool robotAlreadyCreated;

  double positioningVelocity;

  // Variables used to compute the measured velocities (see getVelocity() )
  vpColVector q_prev_getvel;
  vpHomogeneousMatrix fMc_prev_getvel;
  double time_prev_getvel;
  bool first_time_getvel;

  // Variables used to compute the measured displacement (see
  // getDisplacement() )
  vpColVector q_prev_getdis;
  bool first_time_getdis;

public:  /* Constantes */

  /* Vitesse maximale par default lors du positionnement du robot.
   * C'est la valeur a la construction de l'attribut prive \a
   * positioningVelocity. Cette valeur peut etre changee par la fonction
   * #setPositioningVelocity.
   */
  static const double defaultPositioningVelocity; // = 20.0;

public:  /* Methode publiques */

  vpRobotAfma4 (bool verbose=true);
  virtual ~vpRobotAfma4 (void);

  void getDisplacement(vpRobot::vpControlFrameType frame,
                       vpColVector &displacement);
  void getPosition (const vpRobot::vpControlFrameType frame,
                    vpColVector &position);
  void getPosition (const vpRobot::vpControlFrameType frame,
                    vpColVector &position, double &timestamp);

  double getPositioningVelocity (void);
  bool getPowerState();

  double getTime() const;

  void getVelocity (const vpRobot::vpControlFrameType frame,
                    vpColVector & velocity);
  void getVelocity (const vpRobot::vpControlFrameType frame,
                    vpColVector & velocity, double &timestamp);

  vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
  vpColVector getVelocity (const vpRobot::vpControlFrameType frame, double &timestamp);

  void get_cMe(vpHomogeneousMatrix &cMe) const;
  void get_cVe(vpVelocityTwistMatrix &cVe) const;
  void get_cVf(vpVelocityTwistMatrix &cVf) const;
  void get_eJe(vpMatrix &eJe);
  void get_fJe(vpMatrix &fJe);

  void init (void);

  void move(const char *filename) ;

  void powerOn() ;
  void powerOff() ;

  static bool readPosFile(const char *filename, vpColVector &q)  ;
  static bool savePosFile(const char *filename, const vpColVector &q)  ;

  /* --- POSITIONNEMENT --------------------------------------------------- */
  void setPosition(const vpRobot::vpControlFrameType frame,
                   const vpColVector &position) ;
  void setPosition (const vpRobot::vpControlFrameType frame,
                    const double q1, const double q2,
                    const double q4, const double q5) ;
  void setPosition(const char *filename) ;
  void setPositioningVelocity (const double velocity);

  /* --- ETAT ------------------------------------------------------------- */

  vpRobot::vpRobotStateType setRobotState (vpRobot::vpRobotStateType newState);

  /* --- VITESSE ---------------------------------------------------------- */

  void setVelocity (const vpRobot::vpControlFrameType frame,
                    const vpColVector & velocity);

  void stopMotion() ;

private:
  void getArticularDisplacement(vpColVector &displacement);
  void getCameraDisplacement(vpColVector &displacement);
};

#endif
#endif /* #ifndef vpRobotAfma4_h */