Visual Servoing Platform  version 3.5.1 under development (2023-09-22)
vpSimulatorPioneer.cpp
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  * Pioneer mobile robot simulator without display.
33  *
34 *****************************************************************************/
35 
43 #include <visp3/core/vpDebug.h>
44 #include <visp3/core/vpExponentialMap.h>
45 #include <visp3/core/vpHomogeneousMatrix.h>
46 #include <visp3/robot/vpRobotException.h>
47 #include <visp3/robot/vpSimulatorPioneer.h>
48 
53 vpSimulatorPioneer::vpSimulatorPioneer() : wMc_(), wMe_(), xm_(0), ym_(0), theta_(0) { init(); }
54 
62 void vpSimulatorPioneer::init()
63 {
64  xm_ = 0;
65  ym_ = 0;
66  theta_ = 0;
67 
68  nDof = 2;
69  eJeAvailable = true;
70  fJeAvailable = false;
72  qmin = NULL;
73  qmax = NULL;
74 
75  wMc_ = wMe_ * cMe_.inverse();
76 }
77 
83 
92 
111 {
112  switch (frame) {
116  }
117  setRobotFrame(frame);
118 
119  // v is a 2 dimension vector that contains v,w
120  if (v.size() != 2) {
121  vpERROR_TRACE("Bad dimension of the control vector");
122  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
123  }
124 
125  vpColVector v_max(2);
126 
127  v_max[0] = getMaxTranslationVelocity();
128  v_max[1] = getMaxRotationVelocity();
129 
130  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
131 
132  xm_ += delta_t_ * v_sat[0] * cos(theta_);
133  ym_ += delta_t_ * v_sat[0] * sin(theta_);
134  theta_ += delta_t_ * v_sat[1];
135 
136  vpRotationMatrix wRe(0, 0, theta_);
137  vpTranslationVector wte(xm_, ym_, 0);
138  wMe_.buildFrom(wte, wRe);
139  wMc_ = wMe_ * cMe_.inverse();
140 
141  break;
142  } break;
144  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
145  "functionality not implemented");
146  break;
148  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the articular frame:"
149  "functionality not implemented");
150  case vpRobot::MIXT_FRAME:
151  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
152  "functionality not implemented");
153 
154  break;
156  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
157  "functionality not implemented");
158 
159  break;
160  }
161 }
162 
168 
169 /*
170  Get the current position of the robot.
171 
172  \param frame : Control frame type in which to get the position, either :
173  - in the camera cartesien frame,
174  - joint (articular) coordinates of each axes (not implemented)
175  - in a reference or fixed cartesien frame attached to the robot base
176  - in a mixt cartesien frame (translation in reference frame, and rotation in
177  camera frame)
178 
179  \param position : Measured position of the robot:
180  - in camera cartesien frame, a 6 dimension vector, set to 0.
181 
182  - in articular, this functionality is not implemented.
183 
184  - in reference frame, a 6 dimension vector, the first 3 values correspond to
185  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
186  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
187 */
189 {
190  q.resize(6);
191 
192  switch (frame) {
194  q = 0;
195  break;
196 
198  std::cout << "ARTICULAR_FRAME is not implemented in "
199  "vpSimulatorPioneer::getPosition()"
200  << std::endl;
201  break;
203  // Convert wMc_ to a position
204  // From fMc extract the pose
205  vpRotationMatrix wRc;
206  this->wMc_.extract(wRc);
207  vpRxyzVector rxyz;
208  rxyz.buildFrom(wRc);
209 
210  for (unsigned int i = 0; i < 3; i++) {
211  q[i] = this->wMc_[i][3]; // translation x,y,z
212  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
213  }
214 
215  break;
216  }
217  case vpRobot::MIXT_FRAME:
218  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
219  break;
221  std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
222  break;
223  }
224 }
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:292
Implementation of column vector and the associated operations.
Definition: vpColVector.h:167
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:351
@ dimensionError
Bad dimension.
Definition: vpException.h:83
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void extract(vpRotationMatrix &R) const
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:152
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
int nDof
number of degrees of freedom
Definition: vpRobot.h:100
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:142
double * qmin
Definition: vpRobot.h:111
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:160
vpControlFrameType
Definition: vpRobot.h:73
@ REFERENCE_FRAME
Definition: vpRobot.h:74
@ ARTICULAR_FRAME
Definition: vpRobot.h:76
@ MIXT_FRAME
Definition: vpRobot.h:84
@ CAMERA_FRAME
Definition: vpRobot.h:80
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:79
double * qmax
Definition: vpRobot.h:112
int areJointLimitsAvailable
Definition: vpRobot.h:110
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:108
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:64
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:270
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:198
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:104
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:248
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:204
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:178
vpRxyzVector buildFrom(const vpRotationMatrix &R)
vpHomogeneousMatrix wMc_
void getPosition(vpHomogeneousMatrix &wMc) const
vpHomogeneousMatrix wMe_
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Class that consider the case of a translation vector.
vpMatrix get_eJe() const
Definition: vpUnicycle.h:104
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:124
#define vpERROR_TRACE
Definition: vpDebug.h:388