Visual Servoing Platform  version 3.1.0
vpRobotViper850.h
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 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 http://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 Viper S850 robot controlled by an Adept
33  *MotionBlox.
34  *
35  * Authors:
36  * Fabien Spindler
37  *
38  *****************************************************************************/
39 
40 #ifndef vpRobotViper850_h
41 #define vpRobotViper850_h
42 
43 #include <visp3/core/vpConfig.h>
44 
45 #ifdef VISP_HAVE_VIPER850
46 
47 #include <iostream>
48 #include <stdio.h>
49 
50 #include <visp3/core/vpColVector.h>
51 #include <visp3/core/vpDebug.h>
52 #include <visp3/robot/vpRobot.h>
53 #include <visp3/robot/vpViper850.h>
54 
55 // low level controller api
56 extern "C" {
57 #include "irisa_Viper850.h"
58 #include "trycatch.h"
59 }
60 
61 // If USE_ATI_DAQ defined, use DAQ board instead of serial connexion to
62 // acquire data using comedi
63 #define USE_ATI_DAQ
64 
65 #ifdef USE_ATI_DAQ
66 #include <visp3/sensor/vpForceTorqueAtiSensor.h>
67 #endif
68 
345 class VISP_EXPORT vpRobotViper850 : public vpViper850, public vpRobot
346 {
347 
348 public: /* Constantes */
350  typedef enum {
352  MANUAL,
353  ESTOP
356 
357  /* Vitesse maximale par default lors du positionnement du robot.
358  * C'est la valeur a la construction de l'attribut prive \a
359  * positioningVelocity. Cette valeur peut etre changee par la fonction
360  * #setPositioningVelocity.
361  */
362  static const double defaultPositioningVelocity; // = 20.0;
363 
364 private: /* Not allowed functions. */
368  vpRobotViper850(const vpRobotViper850 &robot);
369 
370 private: /* Attributs prives. */
380  static bool robotAlreadyCreated;
381 
382  double positioningVelocity;
383 
384  // Variables used to compute the measured velocities (see getVelocity() )
385  vpColVector q_prev_getvel;
386  vpHomogeneousMatrix fMc_prev_getvel;
387  double time_prev_getvel;
388  bool first_time_getvel;
389 
390  // Variables used to compute the measured displacement (see
391  // getDisplacement() )
392  vpColVector q_prev_getdis;
393  bool first_time_getdis;
394  vpControlModeType controlMode;
395 
396 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
398 #endif
399 
400 public: /* Methode publiques */
401  explicit vpRobotViper850(bool verbose = true);
402  virtual ~vpRobotViper850(void);
403 
404  // Force/Torque control
405  void biasForceTorqueSensor();
406 
407  void closeGripper() const;
408 
409  void disableJoint6Limits() const;
410  void enableJoint6Limits() const;
411 
412  void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement);
417  vpControlModeType getControlMode() const { return controlMode; }
418 
419  void getForceTorque(vpColVector &H) const;
420  vpColVector getForceTorque() const;
421 
422  double getMaxRotationVelocityJoint6() const;
423  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position);
424  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp);
425  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position);
426  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp);
427 
428  double getPositioningVelocity(void) const;
429  bool getPowerState() const;
430 
431  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity);
432  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp);
433 
434  vpColVector getVelocity(const vpRobot::vpControlFrameType frame);
435  vpColVector getVelocity(const vpRobot::vpControlFrameType frame, double &timestamp);
436 
437  double getTime() const;
438 
439  void get_cMe(vpHomogeneousMatrix &cMe) const;
440  void get_cVe(vpVelocityTwistMatrix &cVe) const;
441  void get_eJe(vpMatrix &eJe);
442  void get_fJe(vpMatrix &fJe);
443 
444  void init(void);
445  void
448  void init(vpViper850::vpToolType tool, const std::string &filename);
449  void init(vpViper850::vpToolType tool, const vpHomogeneousMatrix &eMc_);
450 
451  void move(const std::string &filename);
452 
453  void openGripper();
454 
455  void powerOn();
456  void powerOff();
457 
458  static bool readPosFile(const std::string &filename, vpColVector &q);
459  static bool savePosFile(const std::string &filename, const vpColVector &q);
460 
461  void set_eMc(const vpHomogeneousMatrix &eMc_);
462  void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
463 
464  void setMaxRotationVelocity(double w_max);
465  void setMaxRotationVelocityJoint6(double w6_max);
466 
467  // Position control
468  void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position);
469  void setPosition(const vpRobot::vpControlFrameType frame, const double pos1, const double pos2, const double pos3,
470  const double pos4, const double pos5, const double pos6);
471  void setPosition(const std::string &filename);
472  void setPositioningVelocity(const double velocity);
473 
474  // State
476 
477  // Velocity control
478  void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity);
479 
480  void stopMotion();
481  void unbiasForceTorqueSensor();
482 
483 private:
484  double maxRotationVelocity_joint6;
485 };
486 
487 #endif
488 #endif /* #ifndef vpRobotViper850_h */
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:104
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Implementation of an homogeneous matrix and operations on such kind of matrices.
Control of Irisa&#39;s Viper S850 robot named Viper850.
virtual void get_eJe(vpMatrix &_eJe)=0
Get the robot Jacobian expressed in the end-effector frame.
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:75
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
vpRobotStateType
Definition: vpRobot.h:64
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1230
virtual void init()=0
virtual void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
Get the robot position (frame has to be specified).
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:128
virtual void get_fJe(vpMatrix &_fJe)=0
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:103
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:922
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:260
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
static const double defaultPositioningVelocity
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:92
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:938
vpControlModeType getControlMode() const
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:156
Automatic control mode (default).
virtual void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)=0
Class that consider the case of a translation vector.