Visual Servoing Platform  version 3.1.0
vpSimulatorPioneerPan.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 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 http://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  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
45 #include <visp3/core/vpDebug.h>
46 #include <visp3/core/vpExponentialMap.h>
47 #include <visp3/core/vpHomogeneousMatrix.h>
48 #include <visp3/robot/vpRobotException.h>
49 #include <visp3/robot/vpSimulatorPioneerPan.h>
50 
60 vpSimulatorPioneerPan::vpSimulatorPioneerPan() : wMc_(), wMm_(), xm_(0), ym_(0), theta_(0), q_pan_() { init(); }
61 
72 void vpSimulatorPioneerPan::init()
73 {
74  xm_ = 0;
75  ym_ = 0;
76  theta_ = 0;
77  q_pan_ = 0;
78 
79  nDof = 3;
80  eJeAvailable = true;
81  fJeAvailable = false;
83  qmin = NULL;
84  qmax = NULL;
85 
86  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
87 }
88 
94 
103 
123 {
124  switch (frame) {
128  }
129 
130  setRobotFrame(frame);
131 
132  // v is a 3 dimension vector that contains vx, wz, qpan
133  if (v.size() != 3) {
134  vpERROR_TRACE("Bad dimension of the control vector");
135  throw vpRobotException(vpRobotException::dimensionError, "Bad dimension of the control vector");
136  }
137 
138  vpColVector v_max(3);
139 
140  v_max[0] = getMaxTranslationVelocity();
141  v_max[1] = getMaxRotationVelocity();
142  v_max[2] = getMaxRotationVelocity();
143 
144  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
145 
146  xm_ += delta_t_ * v_sat[0] * cos(theta_);
147  ym_ += delta_t_ * v_sat[0] * sin(theta_);
148  theta_ += delta_t_ * v_sat[1];
149  q_pan_ += delta_t_ * v_sat[2];
150 
151  vpRotationMatrix wRm(0, 0, theta_);
152  vpTranslationVector wtm(xm_, ym_, 0);
153  wMm_.buildFrom(wtm, wRm);
154 
155  // Update the end effector pose
156  set_pMe(q_pan_);
157 
158  // Update the camera pose
159  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
160 
161  // Update the jacobian
162  set_eJe(q_pan_);
163 
164  break;
165  }
167  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the camera frame:"
168  "functionality not implemented");
170  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the reference frame:"
171  "functionality not implemented");
172  case vpRobot::MIXT_FRAME:
173  throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in the mixt frame:"
174  "functionality not implemented");
175  }
176 }
177 
183 
184 /*
185  Get the current position of the robot.
186 
187  \param frame : Control frame type in which to get the position, either :
188  - in the camera cartesien frame,
189  - joint (articular) coordinates of each axes (not implemented)
190  - in a reference or fixed cartesien frame attached to the robot base
191  - in a mixt cartesien frame (translation in reference frame, and rotation in
192  camera frame)
193 
194  \param position : Measured position of the robot:
195  - in camera cartesien frame, a 6 dimension vector, set to 0.
196 
197  - in articular, this functionality is not implemented.
198 
199  - in reference frame, a 6 dimension vector, the first 3 values correspond to
200  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
201  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
202 */
204 {
205  q.resize(6);
206 
207  switch (frame) {
209  q = 0;
210  break;
211 
213  std::cout << "ARTICULAR_FRAME is not implemented in "
214  "vpSimulatorPioneer::getPosition()"
215  << std::endl;
216  break;
218  // Convert wMc_ to a position
219  // From fMc extract the pose
220  vpRotationMatrix wRc;
221  this->wMc_.extract(wRc);
222  vpRxyzVector rxyz;
223  rxyz.buildFrom(wRc);
224 
225  for (unsigned int i = 0; i < 3; i++) {
226  q[i] = this->wMc_[i][3]; // translation x,y,z
227  q[i + 3] = rxyz[i]; // Euler rotation x,y,z
228  }
229 
230  break;
231  }
232  case vpRobot::MIXT_FRAME:
233  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
234  }
235 }
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:104
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void set_pMe(const double q)
Definition: vpPioneerPan.h:222
Error that can be emited by the vpRobot class and its derivates.
vpHomogeneousMatrix wMc_
robot / camera location in the world frame
Implementation of an homogeneous matrix and operations on such kind of matrices.
double * qmax
Definition: vpRobot.h:109
#define vpERROR_TRACE
Definition: vpDebug.h:393
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:251
vpHomogeneousMatrix inverse() const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
vpControlFrameType
Definition: vpRobot.h:75
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:158
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:273
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix wMm_
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
Implementation of a rotation matrix and operations on such kind of matrices.
int eJeAvailable
is the robot Jacobian expressed in the end-effector frame available
Definition: vpRobot.h:101
Initialize the velocity controller.
Definition: vpRobot.h:67
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:139
vpHomogeneousMatrix mMp_
Definition: vpPioneerPan.h:236
vpMatrix get_eJe() const
Definition: vpUnicycle.h:107
int areJointLimitsAvailable
Definition: vpRobot.h:107
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:127
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
int nDof
number of degrees of freedom
Definition: vpRobot.h:97
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
vpHomogeneousMatrix pMe_
Definition: vpPioneerPan.h:237
void getPosition(vpHomogeneousMatrix &wMc) const
double * qmin
Definition: vpRobot.h:108
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:156
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:207
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:105
void set_eJe(double q_pan)
Definition: vpPioneerPan.h:146
Class that consider the case of a translation vector.
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:241