Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpRobotViper650.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 S650 robot controlled by an Adept
33  *MotionBlox.
34  *
35 *****************************************************************************/
36 
37 #ifndef vpRobotViper650_h
38 #define vpRobotViper650_h
39 
40 #include <visp3/core/vpConfig.h>
41 
42 #ifdef VISP_HAVE_VIPER650
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/vpViper650.h>
51 
52 // low level controller api
53 extern "C" {
54 #include "irisa_Viper650.h"
55 #include "trycatch.h"
56 }
57 
363 class VISP_EXPORT vpRobotViper650 : public vpViper650, public vpRobot
364 {
365 
366 public: /* Constantes */
368  typedef enum
369  {
371  MANUAL,
373  ESTOP
374  } vpControlModeType;
375 
376  /* Max velocity used during robot control in position.
377  * this value could be changed using setPositioningVelocity().
378  */
379  static const double m_defaultPositioningVelocity; // = 20.0;
380 
381 private: /* Not allowed functions. */
385  vpRobotViper650(const vpRobotViper650 &robot);
386 
387 private: /* Attributs prives. */
397  static bool m_robotAlreadyCreated;
398 
399  double m_positioningVelocity;
400 
401  // Variables used to compute the measured velocities (see getVelocity() )
402  vpColVector m_q_prev_getvel;
403  vpHomogeneousMatrix m_fMc_prev_getvel;
404  vpHomogeneousMatrix m_fMe_prev_getvel;
405  double m_time_prev_getvel;
406  bool m_first_time_getvel;
407 
408  // Variables used to compute the measured displacement (see getDisplacement() )
409  vpColVector m_q_prev_getdis;
410  bool m_first_time_getdis;
411  vpControlModeType m_controlMode;
412 
413 public: /* Methode publiques */
414  VP_EXPLICIT vpRobotViper650(bool verbose = true);
415  virtual ~vpRobotViper650(void);
416 
417  // Force/Torque control
418  void biasForceTorqueSensor() const;
419 
420  void closeGripper() const;
421 
422  void disableJoint6Limits() const;
423  void enableJoint6Limits() const;
424 
429  vpControlModeType getControlMode() const { return m_controlMode; }
430 
431  void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement);
432  void getForceTorque(vpColVector &H) const;
433  vpColVector getForceTorque() const;
434 
435  double getMaxRotationVelocityJoint6() const;
436 
437  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position);
438  void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp);
439  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position);
440  void getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp);
441 
442  double getPositioningVelocity(void) const;
443  bool getPowerState() const;
444 
445  double getTime() const;
446  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity);
447  void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp);
448 
449  vpColVector getVelocity(const vpRobot::vpControlFrameType frame);
450  vpColVector getVelocity(const vpRobot::vpControlFrameType frame, double &timestamp);
451 
452  void get_cMe(vpHomogeneousMatrix &cMe) const;
453  void get_cVe(vpVelocityTwistMatrix &cVe) const;
454  void get_eJe(vpMatrix &eJe) VP_OVERRIDE;
455  void get_fJe(vpMatrix &fJe) VP_OVERRIDE;
456 
457  void init(void);
458  void
461  void init(vpViper650::vpToolType tool, const std::string &filename);
462  void init(vpViper650::vpToolType tool, const vpHomogeneousMatrix &eMc_);
463 
464  void move(const std::string &filename);
465 
466  void openGripper();
467 
468  void powerOn();
469  void powerOff();
470 
471  static bool readPosFile(const std::string &filename, vpColVector &q);
472  static bool savePosFile(const std::string &filename, const vpColVector &q);
473 
474  void set_eMc(const vpHomogeneousMatrix &eMc_);
475  void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
476 
477  void setMaxRotationVelocity(double w_max);
478  void setMaxRotationVelocityJoint6(double w6_max);
479 
480  // Position control
481  void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE;
482  void setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3, double pos4,
483  double pos5, double pos6);
484  void setPosition(const std::string &filename);
485  void setPositioningVelocity(double velocity);
486 
487  // State
489  // Velocity control
490  void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE;
491 
492  void stopMotion();
493 
494 private:
495  double m_maxRotationVelocity_joint6;
496 };
497 END_VISP_NAMESPACE
498 #endif
499 #endif /* #ifndef vpRobotViper650_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 S650 robot named Viper650.
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 650 robot.
Definition: vpViper650.h:95
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition: vpViper650.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