Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotTemplate.cpp
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 * Defines a robot just to show which function you must implement.
32 */
33
34#include <visp3/core/vpConfig.h>
35
36#include <visp3/robot/vpRobotException.h>
37
42
43#include <visp3/core/vpHomogeneousMatrix.h>
44#include <visp3/robot/vpRobotTemplate.h>
45
51{
52 // If you want to control the robot in Cartesian in a tool frame, set the corresponding transformation in m_eMc
53 // that is set to identity by default in the constructor.
54
57
58 // Set here the robot degrees of freedom number
59 nDof = 6; // If your arm has 6 dof
60}
61
66
70vpRobotTemplate::~vpRobotTemplate() { std::cout << "Not implemented ! " << std::endl; }
71
72/*
73
74 At least one of these function has to be implemented to control the robot with a
75 Cartesian velocity:
76 - get_eJe()
77 - get_fJe()
78
79*/
80
87{
88 (void)eJe_;
89 std::cout << "Not implemented ! " << std::endl;
90}
91
98{
99 (void)fJe_;
100 std::cout << "Not implemented ! " << std::endl;
101}
102
103/*
104
105 At least one of these function has to be implemented to control the robot:
106 - setCartVelocity()
107 - setJointVelocity()
108
109*/
110
121{
122 if (v.size() != 6) {
124 "Cannot send a velocity twist vector in tool frame that is not 6-dim (%d)", v.size()));
125 }
126
127 vpColVector v_e; // This is the velocity that the robot is able to apply in the end-effector frame
128 switch (frame) {
129 case vpRobot::TOOL_FRAME: {
130 // We have to transform the requested velocity in the end-effector frame.
131 // Knowing that the constant transformation between the tool frame and the end-effector frame obtained
132 // by extrinsic calibration is set in m_eMc we can compute the velocity twist matrix eVc that transform
133 // a velocity twist from tool (or camera) frame into end-effector frame
135 v_e = eVc * v;
136 break;
137 }
138
141 v_e = v;
142 break;
143 }
146 // Out of the scope
147 break;
148 }
149
150 // Implement your stuff here to send the end-effector velocity twist v_e
151 // - If the SDK allows to send cartesian velocities in the end-effector, it's done. Just wrap data in v_e
152 // - If the SDK allows to send cartesian velocities in the reference (or base) frame you have to implement
153 // the robot Jacobian in set_fJe() and call:
154 // vpColVector v = get_fJe().inverse() * v_e;
155 // At this point you have to wrap data in v that is the 6-dim velocity to apply to the robot
156 // - If the SDK allows to send only joint velocities you have to implement the robot Jacobian in set_eJe()
157 // and call:
158 // vpColVector qdot = get_eJe().inverse() * v_e;
159 // setJointVelocity(qdot);
160 // - If the SDK allows to send only a cartesian position trajectory of the end-effector position in the base frame
161 // called fMe (for fix frame to end-effector homogeneous transformation) you can transform the cartesian
162 // velocity in the end-effector into a displacement eMe using the exponetial map:
163 // double delta_t = 0.010; // in sec
164 // vpHomogenesousMatrix eMe = vpExponentialMap::direct(v_e, delta_t);
165 // vpHomogenesousMatrix fMe = getPosition(vpRobot::REFERENCE_FRAME);
166 // the new position to reach is than given by fMe * eMe
167 // vpColVector fpe(vpPoseVector(fMe * eMe));
168 // setPosition(vpRobot::REFERENCE_FRAME, fpe);
169
170 std::cout << "Not implemented ! " << std::endl;
171 std::cout << "To implement me you need : " << std::endl;
172 std::cout << "\t to known the robot jacobian expressed in ";
173 std::cout << "the end-effector frame (eJe) " << std::endl;
174 std::cout << "\t the frame transformation between tool or camera frame ";
175 std::cout << "and end-effector frame (cMe)" << std::endl;
176}
177
183{
184 (void)qdot;
185
186 // Implement your stuff here to send the joint velocities qdot
187
188 std::cout << "Not implemented ! " << std::endl;
189}
190
201{
204 "Cannot send a velocity to the robot. "
205 "Call setRobotState(vpRobot::STATE_VELOCITY_CONTROL) once before "
206 "entering your control loop.");
207 }
208
209 vpColVector vel_sat(6);
210
211 // Velocity saturation
212 switch (frame) {
213 // Saturation in cartesian space
217 case vpRobot::MIXT_FRAME: {
218 if (vel.size() != 6) {
220 "Cannot apply a Cartesian velocity that is not a 6-dim vector (%d)", vel.size()));
221 }
222 vpColVector vel_max(6);
223
224 for (unsigned int i = 0; i < 3; i++)
225 vel_max[i] = getMaxTranslationVelocity();
226 for (unsigned int i = 3; i < 6; i++)
227 vel_max[i] = getMaxRotationVelocity();
228
229 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
230
231 setCartVelocity(frame, vel_sat);
232 break;
233 }
234 // Saturation in joint space
236 if (vel.size() != static_cast<size_t>(nDof)) {
237 throw(vpException(vpException::dimensionError, "Cannot apply a joint velocity that is not a %-dim vector (%d)",
238 nDof, vel.size()));
239 }
240 vpColVector vel_max(vel.size());
241
242 // Since the robot has only rotation axis all the joint max velocities are set to getMaxRotationVelocity()
243 vel_max = getMaxRotationVelocity();
244
245 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
246
247 setJointVelocity(vel_sat);
248 }
249 }
250}
251
252/*
253
254 THESE FUNCTIONS ARE NOT MANDATORY BUT ARE USUALLY USEFUL
255
256*/
257
264{
265 (void)q;
266 std::cout << "Not implemented ! " << std::endl;
267}
268
276{
277 if (frame == JOINT_STATE) {
279 }
280 else {
281 std::cout << "Not implemented ! " << std::endl;
282 }
283}
284
292{
293 (void)frame;
294 (void)q;
295 std::cout << "Not implemented ! " << std::endl;
296}
297
305{
306 (void)frame;
307 (void)q;
308 std::cout << "Not implemented ! " << std::endl;
309}
310END_VISP_NAMESPACE
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:435
Implementation of column vector and the associated operations.
error that can be emitted by ViSP classes.
Definition vpException.h:60
@ dimensionError
Bad dimension.
Definition vpException.h:71
@ fatalError
Fatal error.
Definition vpException.h:72
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
void getJointPosition(vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void get_fJe(vpMatrix &fJe_) VP_OVERRIDE
void setCartVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &v)
vpHomogeneousMatrix m_eMc
Constant transformation between end-effector and tool (or camera) frame.
virtual ~vpRobotTemplate() VP_OVERRIDE
void init() VP_OVERRIDE
void get_eJe(vpMatrix &eJe_) VP_OVERRIDE
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
void setJointVelocity(const vpColVector &qdot)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
int nDof
number of degrees of freedom
Definition vpRobot.h:101
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:162
vpControlFrameType
Definition vpRobot.h:74
@ REFERENCE_FRAME
Definition vpRobot.h:75
@ JOINT_STATE
Definition vpRobot.h:79
@ TOOL_FRAME
Definition vpRobot.h:83
@ MIXT_FRAME
Definition vpRobot.h:85
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
static const double maxRotationVelocityDefault
Definition vpRobot.h:98
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
static const double maxTranslationVelocityDefault
Definition vpRobot.h:96
double getMaxRotationVelocity(void) const
Definition vpRobot.cpp:272
double maxTranslationVelocity
Definition vpRobot.h:95
double getMaxTranslationVelocity(void) const
Definition vpRobot.cpp:250
double maxRotationVelocity
Definition vpRobot.h:97