Visual Servoing Platform  version 3.6.1 under development (2024-12-09)
vpRobotViper850.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 Viper S850 robot controlled by an Adept
33  *MotionBlox.
34  *
35 *****************************************************************************/
36 
37 #ifndef vpRobotViper850_h
38 #define vpRobotViper850_h
39 
40 #include <visp3/core/vpConfig.h>
41 
42 #ifdef VISP_HAVE_VIPER850
43 
44 #include <iostream>
45 #include <stdio.h>
46 
47 #include <visp3/core/vpColVector.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/robot/vpRobot.h>
50 #include <visp3/robot/vpViper850.h>
51 
52 // low level controller api
53 extern "C" {
54 #include "irisa_Viper850.h"
55 #include "trycatch.h"
56 }
57 
58 // If USE_ATI_DAQ defined, use DAQ board instead of serial connexion to
59 // acquire data using comedi
60 #define USE_ATI_DAQ
61 
62 #ifdef USE_ATI_DAQ
63 #include <visp3/sensor/vpForceTorqueAtiSensor.h>
64 #endif
65 
66 BEGIN_VISP_NAMESPACE
365 class VISP_EXPORT vpRobotViper850 : public vpViper850, public vpRobot
366 {
367 
368 public: /* Constantes */
370  typedef enum
371  {
373  MANUAL,
375  ESTOP
376  } vpControlModeType;
377 
378  /* Max velocity used during robot control in position.
379  * this value could be changed using setPositioningVelocity().
380  */
381  static const double m_defaultPositioningVelocity; // = 20.0;
382 
383 private: /* Not allowed functions. */
387  vpRobotViper850(const vpRobotViper850 &robot);
388 
389 private: /* Attributs prives. */
399  static bool m_robotAlreadyCreated;
400 
401  double m_positioningVelocity;
402 
403  // Variables used to compute the measured velocities (see getVelocity() )
404  vpColVector m_q_prev_getvel;
405  vpHomogeneousMatrix m_fMc_prev_getvel;
406  vpHomogeneousMatrix m_fMe_prev_getvel;
407  double m_time_prev_getvel;
408  bool m_first_time_getvel;
409 
410  // Variables used to compute the measured displacement (see
411  // getDisplacement() )
412  vpColVector m_q_prev_getdis;
413  bool m_first_time_getdis;
414  vpControlModeType m_controlMode;
415 
416 #if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
418 #endif
419 
420 public: /* Methode publiques */
421  VP_EXPLICIT vpRobotViper850(bool verbose = true);
422  virtual ~vpRobotViper850(void);
423 
424  // Force/Torque control
425  void biasForceTorqueSensor();
426 
427  void closeGripper() const;
428 
429  void disableJoint6Limits() const;
430  void enableJoint6Limits() const;
431 
432  void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement);
437  vpControlModeType getControlMode() const { return m_controlMode; }
438 
439  void getForceTorque(vpColVector &H) const;
440  vpColVector getForceTorque() const;
441 
442  double getMaxRotationVelocityJoint6() const;
443  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE;
444  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp);
445  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position);
446  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp);
447 
448  double getPositioningVelocity(void) const;
449  bool getPowerState() const;
450 
451  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity);
452  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp);
453 
454  vpColVector getVelocity(const vpRobot::vpControlFrameType frame);
455  vpColVector getVelocity(const vpRobot::vpControlFrameType frame, double &timestamp);
456 
457  double getTime() const;
458 
459  void get_cMe(vpHomogeneousMatrix &cMe) const;
460  void get_cVe(vpVelocityTwistMatrix &cVe) const;
461  void get_eJe(vpMatrix &eJe) VP_OVERRIDE;
462  void get_fJe(vpMatrix &fJe) VP_OVERRIDE;
463 
464  void init(void);
465  void
468  void init(vpViper850::vpToolType tool, const std::string &filename);
469  void init(vpViper850::vpToolType tool, const vpHomogeneousMatrix &eMc_);
470 
471  void move(const std::string &filename);
472 
473  void openGripper();
474 
475  void powerOn();
476  void powerOff();
477 
478  static bool readPosFile(const std::string &filename, vpColVector &q);
479  static bool savePosFile(const std::string &filename, const vpColVector &q);
480 
481  void set_eMc(const vpHomogeneousMatrix &eMc_);
482  void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
483 
484  void setMaxRotationVelocity(double w_max);
485  void setMaxRotationVelocityJoint6(double w6_max);
486 
487  // Position control
488  void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE;
489  void setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4,
490  double pos5, double pos6);
491  void setPosition(const std::string &filename);
492  void setPositioningVelocity(double velocity);
493 
494  // State
496 
497  // Velocity control
498  void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE;
499 
500  void stopMotion();
501  void unbiasForceTorqueSensor();
502 
503 private:
504  double maxRotationVelocity_joint6;
505 };
506 END_VISP_NAMESPACE
507 #endif
508 #endif /* #ifndef vpRobotViper850_h */
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
Implementation of an homogeneous matrix and operations on such kind of matrices.
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
Control of Irisa's Viper S850 robot named Viper850.
static const double m_defaultPositioningVelocity
@ AUTO
Automatic control mode (default).
vpControlModeType getControlMode() const
Class that defines a generic virtual robot.
Definition: vpRobot.h:59
vpControlFrameType
Definition: vpRobot.h:77
virtual void get_eJe(vpMatrix &_eJe)=0
Get the robot Jacobian expressed in the end-effector frame.
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:202
virtual void init()=0
virtual void get_fJe(vpMatrix &_fJe)=0
virtual void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q)=0
void setMaxRotationVelocity(double maxVr)
Definition: vpRobot.cpp:261
virtual void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)=0
Set a displacement (frame has to be specified) in position control.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:183
Class that consider the case of a translation vector.
Modelization of the ADEPT Viper 850 robot.
Definition: vpViper850.h:95
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper850.h:120
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition: vpViper.cpp:1229
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition: vpViper.cpp:921
void get_cVe(vpVelocityTwistMatrix &cVe) const
Definition: vpViper.cpp:937