Visual Servoing Platform  version 3.6.1 under development (2024-06-12)
vpRobotAfma6.h
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Irisa's Afma6 robot controlled by an Adept MotionBlox.
33  *
34 *****************************************************************************/
35 
36 #ifndef vpRobotAfma6_h
37 #define vpRobotAfma6_h
38 
39 #include <visp3/core/vpConfig.h>
40 
41 #ifdef VISP_HAVE_AFMA6
42 
43 #include <iostream>
44 #include <stdio.h>
45 
46 #include <visp3/core/vpColVector.h>
47 #include <visp3/core/vpDebug.h>
48 #include <visp3/core/vpPoseVector.h>
49 #include <visp3/robot/vpAfma6.h>
50 #include <visp3/robot/vpRobot.h>
51 
52 // low level controller api
53 extern "C" {
54 #include "irisa_Afma6.h"
55 #include "trycatch.h"
56 }
57 
209 class VISP_EXPORT vpRobotAfma6 : public vpAfma6, public vpRobot
210 {
211 
212 private: /* Not allowed functions. */
216  vpRobotAfma6(const vpRobotAfma6 &robot);
217 
218 private: /* Attributs prives. */
228  static bool robotAlreadyCreated;
229 
230  double positioningVelocity;
231 
232  // Variables used to compute the measured velocities (see getVelocity() )
233  vpColVector q_prev_getvel;
234  vpHomogeneousMatrix fMc_prev_getvel;
235  double time_prev_getvel;
236  bool first_time_getvel;
237 
238  // Variables used to compute the measured displacement (see
239  // getDisplacement() )
240  vpColVector q_prev_getdis;
241  bool first_time_getdis;
242  vpHomogeneousMatrix fMc_prev_getdis;
243 
244 public: /* Constantes */
245  /* Vitesse maximale par default lors du positionnement du robot.
246  * C'est la valeur a la construction de l'attribut prive \a
247  * positioningVelocity. Cette valeur peut etre changee par la fonction
248  * #setPositioningVelocity.
249  */
250  static const double defaultPositioningVelocity; // = 20.0;
251 
252 public: /* Methode publiques */
253  explicit vpRobotAfma6(bool verbose = true);
254  virtual ~vpRobotAfma6(void);
255 
256  bool checkJointLimits(vpColVector &jointsStatus);
257 
258  void closeGripper();
259 
260  void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement);
261 
262  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) vp_override;
263  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp);
264  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position);
265  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp);
266 
267  double getPositioningVelocity(void);
268  bool getPowerState();
269  double getTime() const;
270 
271  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity);
272  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp);
273 
274  vpColVector getVelocity(const vpRobot::vpControlFrameType frame);
275  vpColVector getVelocity(const vpRobot::vpControlFrameType frame, double &timestamp);
276 
277  void get_cMe(vpHomogeneousMatrix &_cMe) const;
278  void get_cVe(vpVelocityTwistMatrix &_cVe) const;
279  void get_eJe(vpMatrix &_eJe) vp_override;
280  void get_fJe(vpMatrix &_fJe) vp_override;
281 
282  void init(void);
283  void init(vpAfma6::vpAfma6ToolType tool, const vpHomogeneousMatrix &eMc);
284  void init(vpAfma6::vpAfma6ToolType tool, const std::string &filename);
285  void
288 
289  void move(const std::string &filename);
290  void move(const std::string &filename, double velocity);
291 
292  void openGripper();
293 
294  void powerOn();
295  void powerOff();
296 
297  static bool readPosFile(const std::string &filename, vpColVector &q);
298  static bool savePosFile(const std::string &filename, const vpColVector &q);
299 
300  /* --- POSITIONNEMENT --------------------------------------------------- */
301  void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose);
302  void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) vp_override;
303  void setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4,
304  double pos5, double pos6);
305  void setPosition(const std::string &filename);
306  void setPositioningVelocity(double velocity);
307  void set_eMc(const vpHomogeneousMatrix &eMc);
308 
309  /* --- ETAT ------------------------------------------------------------- */
310 
312 
313  /* --- VITESSE ---------------------------------------------------------- */
314 
315  void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) vp_override;
316 
317  void stopMotion();
318 };
320 #endif
321 #endif /* #ifndef vpRobotAfma6_h */
Modelization of Irisa's gantry robot named Afma6.
Definition: vpAfma6.h:78
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition: vpAfma6.cpp:1193
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpAfma6.cpp:916
void init(void)
Definition: vpAfma6.cpp:158
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpAfma6.cpp:894
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpAfma6.cpp:938
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpAfma6.cpp:1008
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpAfma6.h:126
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:171
Implementation of an homogeneous matrix and operations on such kind of matrices.
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:151
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:187
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:210
static const double defaultPositioningVelocity
Definition: vpRobotAfma6.h:250
Class that defines a generic virtual robot.
Definition: vpRobot.h:59
vpControlFrameType
Definition: vpRobot.h:77
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)=0
Get the robot position (frame has to be specified).
vpRobotStateType
Definition: vpRobot.h:65
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:198
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.