ViSP  2.6.2
vpRobotAfma6.h
1 /****************************************************************************
2  *
3  * $Id: vpRobotAfma6.h 3530 2012-01-03 10:52:12Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Interface for the Irisa's Afma6 robot controlled by an Adept MotionBlox.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
42 #ifndef vpRobotAfma6_h
43 #define vpRobotAfma6_h
44 
45 #include <visp/vpConfig.h>
46 
47 #ifdef VISP_HAVE_AFMA6
48 
49 #include <iostream>
50 #include <stdio.h>
51 
52 #include <visp/vpRobot.h>
53 #include <visp/vpColVector.h>
54 #include <visp/vpPoseVector.h>
55 #include <visp/vpDebug.h>
56 #include <visp/vpAfma6.h>
57 
58 // low level controller api
59 extern "C" {
60 # include "irisa_Afma6.h"
61 # include "trycatch.h"
62 }
63 
64 
214 class VISP_EXPORT vpRobotAfma6
215  :
216  public vpAfma6,
217  public vpRobot
218 {
219 
220 private: /* Not allowed functions. */
221 
225  vpRobotAfma6 (const vpRobotAfma6 & robot);
226 
227 private: /* Attributs prives. */
228 
238  static bool robotAlreadyCreated;
239 
240  double positioningVelocity;
241 
242  // Variables used to compute the measured velocities (see getVelocity() )
243  vpColVector q_prev_getvel;
244  vpHomogeneousMatrix fMc_prev_getvel;
245  double time_prev_getvel;
246  bool first_time_getvel;
247 
248  // Variables used to compute the measured displacement (see
249  // getDisplacement() )
250  vpColVector q_prev_getdis;
251  bool first_time_getdis;
252  vpHomogeneousMatrix fMc_prev_getdis;
253 
254 
255 public: /* Constantes */
256 
257  /* Vitesse maximale par default lors du positionnement du robot.
258  * C'est la valeur a la construction de l'attribut prive \a
259  * positioningVelocity. Cette valeur peut etre changee par la fonction
260  * #setPositioningVelocity.
261  */
262  static const double defaultPositioningVelocity; // = 20.0;
263 
264 public: /* Methode publiques */
265 
266  vpRobotAfma6 (void);
267  virtual ~vpRobotAfma6 (void);
268 
269  void init (void);
270  void init (vpAfma6::vpAfma6ToolType tool,
273 
274  /* --- ETAT ------------------------------------------------------------- */
275 
277 
278  /* --- POSITIONNEMENT --------------------------------------------------- */
279  void setPosition (const vpRobot::vpControlFrameType frame,
280  const vpPoseVector & pose );
281  void setPosition(const vpRobot::vpControlFrameType frame,
282  const vpColVector &position) ;
283  void setPosition (const vpRobot::vpControlFrameType frame,
284  const double pos1, const double pos2, const double pos3,
285  const double pos4, const double pos5, const double pos6) ;
286  void setPosition(const char *filename) ;
287  void setPositioningVelocity (const double velocity);
288 
289  void getPosition (const vpRobot::vpControlFrameType frame,
290  vpColVector &position);
291  void getPosition (const vpRobot::vpControlFrameType frame,
292  vpPoseVector &position);
293 
294  double getPositioningVelocity (void);
295 
296  /* --- VITESSE ---------------------------------------------------------- */
297 
298  void setVelocity (const vpRobot::vpControlFrameType frame,
299  const vpColVector & velocity);
300 
301 
302  void getVelocity (const vpRobot::vpControlFrameType frame,
303  vpColVector & velocity);
304 
305  vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
306 
307 public:
308  void get_cMe(vpHomogeneousMatrix &_cMe) ;
309  void get_cVe(vpVelocityTwistMatrix &_cVe) ;
310  void get_eJe(vpMatrix &_eJe) ;
311  void get_fJe(vpMatrix &_fJe) ;
312 
313  void stopMotion() ;
314  void powerOn() ;
315  void powerOff() ;
316  bool getPowerState();
317 
318  void move(const char *filename) ;
319  void move(const char *filename, const double velocity) ;
320  static bool readPosFile(const char *filename, vpColVector &q) ;
321  static bool savePosFile(const char *filename, const vpColVector &q) ;
322 
323  void openGripper() ;
324  void closeGripper() ;
325 
326  void getCameraDisplacement(vpColVector &displacement);
327  void getArticularDisplacement(vpColVector &displacement);
329  vpColVector &displacement);
330 
331  bool checkJointLimits(vpColVector& jointsStatus);
332 };
333 
334 
335 
336 
337 
338 /*
339  * Local variables:
340  * c-basic-offset: 2
341  * End:
342  */
343 
344 #endif
345 #endif /* #ifndef vpRobotAfma6_h */
Modelisation of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:69
Definition of the vpMatrix class.
Definition: vpMatrix.h:96
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.
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
void get_cVe(vpVelocityTwistMatrix &cVe)
Definition: vpAfma6.cpp:860
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:108
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:60
vpControlFrameType
Definition: vpRobot.h:83
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:152
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:214
void get_cMe(vpHomogeneousMatrix &cMe)
Definition: vpAfma6.cpp:845
virtual void getArticularDisplacement(vpColVector &qdot)=0
Get a displacement expressed in the joint space between two successive position control.
virtual void getCameraDisplacement(vpColVector &v)=0
Get a displacement expressed in the camera frame between two successive position control.
void get_eJe(const vpColVector &q, vpMatrix &eJe)
Definition: vpAfma6.cpp:883
vpRobotStateType
Definition: vpRobot.h:66
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Get the robot position (frame has to be specified).
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
The pose is a complete representation of every rigid motion in the euclidian space.
Definition: vpPoseVector.h:92
void get_fJe(const vpColVector &q, vpMatrix &fJe)
Definition: vpAfma6.cpp:950
void init(void)
Definition: vpAfma6.cpp:196
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...
static const double defaultPositioningVelocity
Definition: vpRobotAfma6.h:262