Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
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
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 Viper S850 robot controlled by an Adept MotionBlox.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #ifndef vpRobotViper850_h
39 #define vpRobotViper850_h
40 
41 #include <visp3/core/vpConfig.h>
42 
43 #ifdef VISP_HAVE_VIPER850
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/vpDebug.h>
51 #include <visp3/robot/vpViper850.h>
52 
53 // low level controller api
54 extern "C" {
55 # include "irisa_Viper850.h"
56 # include "trycatch.h"
57 }
58 
59 // If USE_ATI_DAQ defined, use DAQ board instead of serial connexion to acquire data using comedi
60 #define USE_ATI_DAQ
61 
62 #ifdef USE_ATI_DAQ
63 # include <visp3/sensor/vpForceTorqueAtiSensor.h>
64 #endif
65 
342 class VISP_EXPORT vpRobotViper850
343  :
344  public vpViper850,
345  public vpRobot
346 {
347 
348 public: /* Constantes */
349 
351  typedef enum {
354  ESTOP
355  } vpControlModeType;
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. */
365 
369  vpRobotViper850 (const vpRobotViper850 & robot);
370 
371 private: /* Attributs prives. */
372 
382  static bool robotAlreadyCreated;
383 
384  double positioningVelocity;
385 
386  // Variables used to compute the measured velocities (see getVelocity() )
387  vpColVector q_prev_getvel;
388  vpHomogeneousMatrix fMc_prev_getvel;
389  double time_prev_getvel;
390  bool first_time_getvel;
391 
392  // Variables used to compute the measured displacement (see
393  // getDisplacement() )
394  vpColVector q_prev_getdis;
395  bool first_time_getdis;
396  vpControlModeType controlMode;
397 
398 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
400 #endif
401 
402 public: /* Methode publiques */
403 
404  vpRobotViper850 (bool verbose=true);
405  virtual ~vpRobotViper850 (void);
406 
407  // Force/Torque control
408  void biasForceTorqueSensor();
409 
410  void closeGripper() const;
411 
412  void disableJoint6Limits() const;
413  void enableJoint6Limits() const;
414 
416  vpColVector &displacement);
422  return controlMode;
423  }
424 
425  void getForceTorque(vpColVector &H) const;
426  vpColVector getForceTorque() const;
427 
428  double getMaxRotationVelocityJoint6() const;
429  void getPosition (const vpRobot::vpControlFrameType frame,
430  vpColVector &position);
431  void getPosition (const vpRobot::vpControlFrameType frame,
432  vpColVector &position, double &timestamp);
433  void getPosition (const vpRobot::vpControlFrameType frame,
434  vpPoseVector &position);
435  void getPosition (const vpRobot::vpControlFrameType frame,
436  vpPoseVector &position, double &timestamp);
437 
438  double getPositioningVelocity (void) const;
439  bool getPowerState() const;
440 
441  void getVelocity (const vpRobot::vpControlFrameType frame,
442  vpColVector & velocity);
443  void getVelocity (const vpRobot::vpControlFrameType frame,
444  vpColVector & velocity, double &timestamp);
445 
446  vpColVector getVelocity (const vpRobot::vpControlFrameType frame);
447  vpColVector getVelocity (const vpRobot::vpControlFrameType frame, double &timestamp);
448 
449  double getTime() const;
450 
451  void get_cMe(vpHomogeneousMatrix &cMe) const;
452  void get_cVe(vpVelocityTwistMatrix &cVe) const;
453  void get_eJe(vpMatrix &eJe);
454  void get_fJe(vpMatrix &fJe);
455 
456  void init(void);
457  void init(vpViper850::vpToolType tool,
460  void init(vpViper850::vpToolType tool, const std::string &filename);
461  void init(vpViper850::vpToolType tool, const vpHomogeneousMatrix &eMc_);
462 
463  void move(const std::string &filename) ;
464 
465  void openGripper();
466 
467  void powerOn() ;
468  void powerOff() ;
469 
470  static bool readPosFile(const std::string &filename, vpColVector &q) ;
471  static bool savePosFile(const std::string &filename, const vpColVector &q) ;
472 
473  void set_eMc(const vpHomogeneousMatrix &eMc_);
474  void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
475 
476  void setMaxRotationVelocity(double w_max);
477  void setMaxRotationVelocityJoint6(double w6_max);
478 
479  // Position control
480  void setPosition(const vpRobot::vpControlFrameType frame,
481  const vpColVector &position) ;
482  void setPosition (const vpRobot::vpControlFrameType frame,
483  const double pos1, const double pos2, const double pos3,
484  const double pos4, const double pos5, const double pos6) ;
485  void setPosition(const std::string &filename) ;
486  void setPositioningVelocity (const double velocity);
487 
488  // State
490 
491  // Velocity control
492  void setVelocity (const vpRobot::vpControlFrameType frame,
493  const vpColVector & velocity);
494 
495  void stopMotion();
496  void unbiasForceTorqueSensor();
497 
498 private:
499  void getArticularDisplacement(vpColVector &displacement);
500  void getCameraDisplacement(vpColVector &displacement);
501 
502  double maxRotationVelocity_joint6;
503 };
504 
505 #endif
506 #endif /* #ifndef vpRobotViper850_h */
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:969
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:97
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.
Control of Irisa'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:76
vpControlModeType getControlMode() const
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:1279
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
Get the robot Jacobian expressed in the robot reference (or world) frame.
Modelisation of the ADEPT Viper 850 robot.
Definition: vpViper850.h:103
Implementation of a velocity twist matrix and operations on such kind of matrices.
void setMaxRotationVelocity(const double maxVr)
Definition: vpRobot.cpp:262
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:948
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Manual control mode activated when the dead man switch is in use.
static const double defaultPositioningVelocity
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:93
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
Automatic control mode (default).
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...
Class that consider the case of a translation vector.