Visual Servoing Platform  version 3.0.0
vpRobotAfma6.h
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Interface for the Irisa's Afma6 robot controlled by an Adept MotionBlox.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #ifndef vpRobotAfma6_h
39 #define vpRobotAfma6_h
40 
41 #include <visp3/core/vpConfig.h>
42 
43 #ifdef VISP_HAVE_AFMA6
44 
45 #include <iostream>
46 #include <stdio.h>
47 
48 #include <visp3/robot/vpRobot.h>
49 #include <visp3/core/vpColVector.h>
50 #include <visp3/core/vpPoseVector.h>
51 #include <visp3/core/vpDebug.h>
52 #include <visp3/robot/vpAfma6.h>
53 
54 // low level controller api
55 extern "C" {
56 # include "irisa_Afma6.h"
57 # include "trycatch.h"
58 }
59 
60 
210 class VISP_EXPORT vpRobotAfma6
211  :
212  public vpAfma6,
213  public vpRobot
214 {
215 
216 private: /* Not allowed functions. */
217 
221  vpRobotAfma6 (const vpRobotAfma6 & robot);
222 
223 private: /* Attributs prives. */
224 
234  static bool robotAlreadyCreated;
235 
236  double positioningVelocity;
237 
238  // Variables used to compute the measured velocities (see getVelocity() )
239  vpColVector q_prev_getvel;
240  vpHomogeneousMatrix fMc_prev_getvel;
241  double time_prev_getvel;
242  bool first_time_getvel;
243 
244  // Variables used to compute the measured displacement (see
245  // getDisplacement() )
246  vpColVector q_prev_getdis;
247  bool first_time_getdis;
248  vpHomogeneousMatrix fMc_prev_getdis;
249 
250 
251 public: /* Constantes */
252 
253  /* Vitesse maximale par default lors du positionnement du robot.
254  * C'est la valeur a la construction de l'attribut prive \a
255  * positioningVelocity. Cette valeur peut etre changee par la fonction
256  * #setPositioningVelocity.
257  */
258  static const double defaultPositioningVelocity; // = 20.0;
259 
260 public: /* Methode publiques */
261 
262  vpRobotAfma6 (bool verbose=true);
263  virtual ~vpRobotAfma6 (void);
264 
265  bool checkJointLimits(vpColVector& jointsStatus);
266 
267  void closeGripper() ;
268 
270  vpColVector &displacement);
271 
272  void getPosition (const vpRobot::vpControlFrameType frame,
273  vpColVector &position);
274  void getPosition (const vpRobot::vpControlFrameType frame,
275  vpColVector &position, double &timestamp);
276  void getPosition (const vpRobot::vpControlFrameType frame,
277  vpPoseVector &position);
278  void getPosition (const vpRobot::vpControlFrameType frame,
279  vpPoseVector &position, double &timestamp);
280 
281  double getPositioningVelocity (void);
282  bool getPowerState();
283  double getTime() const;
284 
285  void getVelocity (const vpRobot::vpControlFrameType frame,
286  vpColVector & velocity);
287  void getVelocity (const vpRobot::vpControlFrameType frame,
288  vpColVector & velocity, double &timestamp);
289 
290  vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
291  vpColVector getVelocity (const vpRobot::vpControlFrameType frame, double &timestamp);
292 
293  void get_cMe(vpHomogeneousMatrix &_cMe) const;
294  void get_cVe(vpVelocityTwistMatrix &_cVe) const;
295  void get_eJe(vpMatrix &_eJe);
296  void get_fJe(vpMatrix &_fJe);
297 
298  void init (void);
299  void init (vpAfma6::vpAfma6ToolType tool,
302 
303  void move(const char *filename) ;
304  void move(const char *filename, const double velocity) ;
305 
306  void openGripper() ;
307 
308  void powerOn() ;
309  void powerOff() ;
310 
311  static bool readPosFile(const char *filename, vpColVector &q) ;
312  static bool savePosFile(const char *filename, const vpColVector &q) ;
313 
314  /* --- POSITIONNEMENT --------------------------------------------------- */
315  void setPosition (const vpRobot::vpControlFrameType frame,
316  const vpPoseVector & pose );
317  void setPosition(const vpRobot::vpControlFrameType frame,
318  const vpColVector &position) ;
319  void setPosition (const vpRobot::vpControlFrameType frame,
320  const double pos1, const double pos2, const double pos3,
321  const double pos4, const double pos5, const double pos6) ;
322  void setPosition(const char *filename) ;
323  void setPositioningVelocity (const double velocity);
324 
325  /* --- ETAT ------------------------------------------------------------- */
326 
328 
329 
330  /* --- VITESSE ---------------------------------------------------------- */
331 
332  void setVelocity (const vpRobot::vpControlFrameType frame,
333  const vpColVector & velocity);
334 
335  void stopMotion() ;
336 
337 private:
338  void getArticularDisplacement(vpColVector &displacement);
339  void getCameraDisplacement(vpColVector &displacement);
340 };
341 
342 
343 
344 
345 
346 /*
347  * Local variables:
348  * c-basic-offset: 2
349  * End:
350  */
351 
352 #endif
353 #endif /* #ifndef vpRobotAfma6_h */
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:65
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpAfma6.cpp:872
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Get a displacement (frame as to ve specified) between two successive position control.
Perspective projection without distortion model.
Implementation of an homogeneous matrix and operations on such kind of matrices.
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:895
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:104
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.
class that defines a generic virtual robot
Definition: vpRobot.h:58
vpControlFrameType
Definition: vpRobot.h:76
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:210
vpRobotStateType
Definition: vpRobot.h:64
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:857
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Get the robot position (frame has to be specified).
Implementation of a velocity twist matrix and operations on such kind of matrices.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
void init(void)
Definition: vpAfma6.cpp:195
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
Set the velocity (frame has to be specified) that will be applied to the velocity controller...
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:964
static const double defaultPositioningVelocity
Definition: vpRobotAfma6.h:258