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