Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpViper.h
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
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 https://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
41
42#ifndef VP_VIPER_H
43#define VP_VIPER_H
44
45#include <visp3/core/vpCameraParameters.h>
46#include <visp3/core/vpConfig.h>
47#include <visp3/core/vpHomogeneousMatrix.h>
48#include <visp3/core/vpImage.h>
49#include <visp3/core/vpRGBa.h>
50#include <visp3/core/vpVelocityTwistMatrix.h>
51#include <visp3/robot/vpRobotException.h>
52
110class VISP_EXPORT vpViper
111{
112public:
113 vpViper();
114 vpViper(const vpViper &viper);
115 virtual ~vpViper() { }
116 vpViper &operator=(const vpViper &viper);
117
120 vpHomogeneousMatrix getForwardKinematics(const vpColVector &q) const;
121 unsigned int getInverseKinematicsWrist(const vpHomogeneousMatrix &fMw, vpColVector &q,
122 const bool &verbose = false) const;
123 unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose = false) const;
124 vpHomogeneousMatrix get_fMc(const vpColVector &q) const;
125 void get_fMw(const vpColVector &q, vpHomogeneousMatrix &fMw) const;
126 void get_wMe(vpHomogeneousMatrix &wMe) const;
127 void get_eMc(vpHomogeneousMatrix &eMc) const;
128 void get_eMs(vpHomogeneousMatrix &eMs) const;
129 void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const;
130 void get_fMc(const vpColVector &q, vpHomogeneousMatrix &fMc) const;
131
132 void get_cMe(vpHomogeneousMatrix &cMe) const;
133 void get_cVe(vpVelocityTwistMatrix &cVe) const;
134 void get_fJw(const vpColVector &q, vpMatrix &fJw) const;
135 void get_fJe(const vpColVector &q, vpMatrix &fJe) const;
136 void get_eJe(const vpColVector &q, vpMatrix &eJe) const;
137
138 virtual void set_eMc(const vpHomogeneousMatrix &eMc_);
139 virtual void set_eMc(const vpTranslationVector &etc_, const vpRxyzVector &erc_);
140
141 vpColVector getJointMin() const;
142 vpColVector getJointMax() const;
143 double getCoupl56() const;
145
146 friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpViper &viper);
147
148private:
149 bool convertJointPositionInLimits(unsigned int joint, const double &q, double &q_mod,
150 const bool &verbose = false) const;
151
152public:
153 static const unsigned int njoint;
154
155protected:
157 // Minimal representation of eMc
159 vpRxyzVector erc; // radian
160
161 // Denavit-Hartenberg parameters
162 double a1, d1;
163 double a2;
164 double a3;
165 double d4;
166 double d6;
167 double d7;
168 double c56;
169
170 // Software joint limits in radians
171 vpColVector joint_max; // Maximal value of the joints
172 vpColVector joint_min; // Minimal value of the joints
173};
174END_VISP_NAMESPACE
175#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:175
Implementation of a rotation vector as Euler angle minimal representation.
Class that consider the case of a translation vector.
Modelization of the ADEPT Viper robot.
Definition vpViper.h:111
vpTranslationVector etc
Definition vpViper.h:158
double d6
for joint 6
Definition vpViper.h:166
double a3
for joint 3
Definition vpViper.h:164
static const unsigned int njoint
Number of joint.
Definition vpViper.h:153
double d4
for joint 4
Definition vpViper.h:165
vpColVector joint_max
Definition vpViper.h:171
double c56
Mechanical coupling between joint 5 and joint 6.
Definition vpViper.h:168
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition vpViper.h:156
virtual ~vpViper()
Definition vpViper.h:115
double a1
Definition vpViper.h:162
vpRxyzVector erc
Definition vpViper.h:159
vpColVector joint_min
Definition vpViper.h:172
double a2
for joint 2
Definition vpViper.h:163
vpViper()
Definition vpViper.cpp:57
double d1
for joint 1
Definition vpViper.h:162
double d7
for force/torque location
Definition vpViper.h:167