Visual Servoing Platform  version 3.6.1 under development (2024-12-07)
vpSimulatorPioneerPan.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 equipped with a pan head simulator without display.
33  *
34 *****************************************************************************/
35 
42 #include <visp3/core/vpDebug.h>
43 #include <visp3/core/vpExponentialMap.h>
44 #include <visp3/core/vpHomogeneousMatrix.h>
45 #include <visp3/robot/vpRobotException.h>
46 #include <visp3/robot/vpSimulatorPioneerPan.h>
47 
48 BEGIN_VISP_NAMESPACE
58 vpSimulatorPioneerPan::vpSimulatorPioneerPan() : wMc_(), wMm_(), xm_(0), ym_(0), theta_(0), q_pan_() { init(); }
59 
70 void vpSimulatorPioneerPan::init()
71 {
72  xm_ = 0;
73  ym_ = 0;
74  theta_ = 0;
75  q_pan_ = 0;
76 
77  nDof = 3;
78  eJeAvailable = true;
79  fJeAvailable = false;
81  qmin = nullptr;
82  qmax = nullptr;
83 
84  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
85 }
86 
95 
115 {
116  switch (frame) {
120  }
121 
122  setRobotFrame(frame);
123 
124  // v is a 3 dimension vector that contains vx, wz, qpan
125  if (v.size() != 3) {
126  vpERROR_TRACE("Bad dimension of the control vector");
127  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
128  }
129 
130  vpColVector v_max(3);
131 
132  v_max[0] = getMaxTranslationVelocity();
133  v_max[1] = getMaxRotationVelocity();
134  v_max[2] = getMaxRotationVelocity();
135 
136  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
137 
138  xm_ += delta_t_ * v_sat[0] * cos(theta_);
139  ym_ += delta_t_ * v_sat[0] * sin(theta_);
140  theta_ += delta_t_ * v_sat[1];
141  q_pan_ += delta_t_ * v_sat[2];
142 
143  vpRotationMatrix wRm(0, 0, theta_);
144  vpTranslationVector wtm(xm_, ym_, 0);
145  wMm_.buildFrom(wtm, wRm);
146 
147  // Update the end effector pose
148  set_pMe(q_pan_);
149 
150  // Update the camera pose
151  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
152 
153  // Update the jacobian
154  set_eJe(q_pan_);
155 
156  break;
157  }
159  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
160  "functionality not implemented");
162  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the reference frame:"
163  "functionality not implemented");
164  case vpRobot::MIXT_FRAME:
165  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
166  "functionality not implemented");
168  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the end-effector frame:"
169  "functionality not implemented");
170  }
171 }
172 
178 
179 /*
180  Get the current position of the robot.
181 
182  \param frame : Control frame type in which to get the position, either :
183  - in the camera cartesian frame,
184  - joint (articular) coordinates of each axes (not implemented)
185  - in a reference or fixed cartesian frame attached to the robot base
186  - in a mixt cartesian frame (translation in reference frame, and rotation in
187  camera frame)
188 
189  \param position : Measured position of the robot:
190  - in camera cartesian frame, a 6 dimension vector, set to 0.
191 
192  - in articular, this functionality is not implemented.
193 
194  - in reference frame, a 6 dimension vector, the first 3 values correspond to
195  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
196  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
197 */
199 {
200  q.resize(6);
201 
202  switch (frame) {
204  q = 0;
205  break;
206 
208  std::cout << "ARTICULAR_FRAME is not implemented in "
209  "vpSimulatorPioneer::getPosition()"
210  << std::endl;
211  break;
213  // Convert wMc_ to a position
214  // From fMc extract the pose
215  vpRotationMatrix wRc;
216  this->wMc_.extract(wRc);
217  vpRxyzVector rxyz;
218  rxyz.buildFrom(wRc);
219 
220  for (unsigned int i = 0; i < 3; i++) {
221  q[i] = this->wMc_[i][3]; // translation x,y,z
222  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
223  }
224 
225  break;
226  }
227  case vpRobot::MIXT_FRAME:
228  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
229  break;
231  std::cout << "END_EFFECTOR_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
232  break;
233  }
234 }
235 END_VISP_NAMESPACE
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
@ dimensionError
Bad dimension.
Definition: vpException.h:71
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
void set_eJe(double q_pan)
Definition: vpPioneerPan.h:135
void set_pMe(const double q)
Definition: vpPioneerPan.h:210
vpHomogeneousMatrix mMp_
Definition: vpPioneerPan.h:224
vpHomogeneousMatrix pMe_
Definition: vpPioneerPan.h:225
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:104
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
double * qmin
Definition: vpRobot.h:115
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:164
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ MIXT_FRAME
Definition: vpRobot.h:88
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
double * qmax
Definition: vpRobot.h:116
int areJointLimitsAvailable
Definition: vpRobot.h:114
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:112
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:274
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:108
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:252
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
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:183
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
void getPosition(vpHomogeneousMatrix &wMc) const
vpHomogeneousMatrix wMm_
vpHomogeneousMatrix wMc_
robot / camera location in the world frame
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
Class that consider the case of a translation vector.
vpMatrix get_eJe() const
Definition: vpUnicycle.h:96
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:116