Visual Servoing Platform  version 3.0.0
vpViper.h
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 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 a generic ADEPT Viper (either 650 or 850) robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 #ifndef vpViper_h
39 #define vpViper_h
40 
49 #include <visp3/core/vpHomogeneousMatrix.h>
50 #include <visp3/core/vpImage.h>
51 #include <visp3/core/vpRGBa.h>
52 #include <visp3/core/vpCameraParameters.h>
53 #include <visp3/core/vpVelocityTwistMatrix.h>
54 #include <visp3/robot/vpRobotException.h>
55 
107 class VISP_EXPORT vpViper
108 {
109  public:
110  vpViper();
111  virtual ~vpViper() {};
112 
113  vpHomogeneousMatrix getForwardKinematics(const vpColVector & q) const;
114  unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix & fMw, vpColVector & q, const bool &verbose=false) const;
115  unsigned int getInverseKinematics(const vpHomogeneousMatrix & fMc, vpColVector & q, const bool &verbose=false) const;
116  vpHomogeneousMatrix get_fMc (const vpColVector & q) const;
117  void get_fMw(const vpColVector & q, vpHomogeneousMatrix & fMw) const;
118  void get_wMe(vpHomogeneousMatrix & wMe) const;
119  void get_eMc(vpHomogeneousMatrix & eMc) const;
120  void get_fMe(const vpColVector & q, vpHomogeneousMatrix & fMe) const;
121  void get_fMc(const vpColVector & q, vpHomogeneousMatrix & fMc) const;
122 
123  void get_cMe(vpHomogeneousMatrix &cMe) const;
124  void get_cVe(vpVelocityTwistMatrix &cVe) const;
125  void get_fJw(const vpColVector &q, vpMatrix &fJw) const;
126  void get_fJe(const vpColVector &q, vpMatrix &fJe) const;
127  void get_eJe(const vpColVector &q, vpMatrix &eJe) const;
128 
129  virtual void set_eMc(const vpHomogeneousMatrix &eMc_);
130  virtual void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
131 
132  friend VISP_EXPORT std::ostream & operator << (std::ostream & os, const vpViper & viper);
133 
134  vpColVector getJointMin() const;
135  vpColVector getJointMax() const;
136  double getCoupl56() const;
137 
138  private:
139  bool convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod, const bool &verbose=false) const;
140 
141  public:
142  static const unsigned int njoint;
143 
144  protected:
146  // Minimal representation of eMc
148  vpRxyzVector erc; // radian
149 
150  // Denavit-Hartenberg parameters
151  double a1, d1;
152  double a2;
153  double a3;
154  double d4;
155  double d6;
156  double c56;
157 
158  // Software joint limits in radians
159  vpColVector joint_max; // Maximal value of the joints
160  vpColVector joint_min; // Minimal value of the joints
161 };
162 
163 #endif
164 
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
double a3
for joint 3
Definition: vpViper.h:153
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition: vpViper.h:145
Modelisation of the ADEPT Viper robot.
Definition: vpViper.h:107
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpRxyzVector erc
Definition: vpViper.h:148
double a2
for joint 2
Definition: vpViper.h:152
virtual ~vpViper()
Definition: vpViper.h:111
double d1
for joint 1
Definition: vpViper.h:151
double c56
Mechanical coupling between joint 5 and joint 6.
Definition: vpViper.h:156
vpTranslationVector etc
Definition: vpViper.h:147
vpColVector joint_max
Definition: vpViper.h:159
Implementation of a velocity twist matrix and operations on such kind of matrices.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
double d4
for joint 4
Definition: vpViper.h:154
Class that consider the case of a translation vector.
static const unsigned int njoint
Number of joint.
Definition: vpViper.h:142
double d6
for joint 6
Definition: vpViper.h:155
vpColVector joint_min
Definition: vpViper.h:160