Visual Servoing Platform  version 3.0.0
vpSimulatorPioneerPan.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Pioneer mobile robot equipped with a pan head simulator without display.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
38 
45 #include <visp3/core/vpHomogeneousMatrix.h>
46 #include <visp3/robot/vpSimulatorPioneerPan.h>
47 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpDebug.h>
49 #include <visp3/core/vpExponentialMap.h>
50 
51 
61 vpSimulatorPioneerPan::vpSimulatorPioneerPan() : wMc_(), wMm_(), xm_(0), ym_(0), theta_(0), q_pan_()
62 {
63  init() ;
64 }
65 
76 void vpSimulatorPioneerPan::init()
77 {
78  xm_ = 0;
79  ym_ = 0;
80  theta_ = 0;
81  q_pan_ = 0;
82 
83  nDof = 3;
84  eJeAvailable = true;
85  fJeAvailable = false;
87  qmin = NULL;
88  qmax = NULL;
89 
90  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
91 }
92 
93 
99 {
100 }
101 
109 void
111 {
112  _eJe = vpUnicycle::get_eJe();
113 }
114 
128 void
130  const vpColVector &v)
131 {
132  switch (frame)
133  {
137  }
138 
139  setRobotFrame(frame);
140 
141  // v is a 3 dimension vector that contains vx, wz, qpan
142  if (v.size() != 3) {
143  vpERROR_TRACE ("Bad dimension of the control vector");
145  "Bad dimension of the control vector");
146  }
147 
148  vpColVector v_max(3);
149 
150  v_max[0] = getMaxTranslationVelocity();
151  v_max[1] = getMaxRotationVelocity();
152  v_max[2] = getMaxRotationVelocity();
153 
154  vpColVector v_sat = vpRobot::saturateVelocities(v, v_max, true);
155 
156  xm_ += delta_t_ * v_sat[0] * cos(theta_);
157  ym_ += delta_t_ * v_sat[0] * sin(theta_);
158  theta_ += delta_t_ * v_sat[1];
159  q_pan_ += delta_t_ * v_sat[2];
160 
161  vpRotationMatrix wRm(0, 0, theta_);
162  vpTranslationVector wtm(xm_, ym_, 0);
163  wMm_.buildFrom(wtm, wRm);
164 
165  // Update the end effector pose
166  set_pMe(q_pan_);
167 
168  // Update the camera pose
169  wMc_ = wMm_ * mMp_ * pMe_ * cMe_.inverse();
170 
171  // Update the jacobian
172  set_eJe(q_pan_);
173 
174  break ;
175  }
176  case vpRobot::CAMERA_FRAME: {
177  vpERROR_TRACE ("Cannot set a velocity in the camera frame: "
178  "functionality not implemented");
180  "Cannot set a velocity in the camera frame:"
181  "functionality not implemented");
182  break ;
183  }
185  vpERROR_TRACE ("Cannot set a velocity in the reference frame: "
186  "functionality not implemented");
188  "Cannot set a velocity in the reference frame:"
189  "functionality not implemented");
190  break ;
191 
192  case vpRobot::MIXT_FRAME:
193  vpERROR_TRACE ("Cannot set a velocity in the mixt frame: "
194  "functionality not implemented");
196  "Cannot set a velocity in the mixt frame:"
197  "functionality not implemented");
198 
199  break ;
200  }
201 }
202 
207 void
209 {
210  wMc = this->wMc_ ;
211 }
212 
213 /*
214  Get the current position of the robot.
215 
216  \param frame : Control frame type in which to get the position, either :
217  - in the camera cartesien frame,
218  - joint (articular) coordinates of each axes (not implemented)
219  - in a reference or fixed cartesien frame attached to the robot base
220  - in a mixt cartesien frame (translation in reference frame, and rotation in camera frame)
221 
222  \param position : Measured position of the robot:
223  - in camera cartesien frame, a 6 dimension vector, set to 0.
224 
225  - in articular, this functionality is not implemented.
226 
227  - in reference frame, a 6 dimension vector, the first 3 values correspond to
228  the translation tx, ty, tz in meters (like a vpTranslationVector), and the
229  last 3 values to the rx, ry, rz rotation (like a vpRxyzVector).
230 */
232 {
233  q.resize (6);
234 
235  switch (frame) {
236  case vpRobot::CAMERA_FRAME :
237  q = 0;
238  break;
239 
241  std::cout << "ARTICULAR_FRAME is not implemented in vpSimulatorPioneer::getPosition()" << std::endl;
242  break;
243  case vpRobot::REFERENCE_FRAME : {
244  // Convert wMc_ to a position
245  // From fMc extract the pose
246  vpRotationMatrix wRc;
247  this->wMc_.extract(wRc);
248  vpRxyzVector rxyz;
249  rxyz.buildFrom(wRc);
250 
251  for (unsigned int i=0; i < 3; i++) {
252  q[i] = this->wMc_[i][3]; // translation x,y,z
253  q[i+3] = rxyz[i]; // Euler rotation x,y,z
254  }
255 
256  break;
257  }
258  case vpRobot::MIXT_FRAME :
259  std::cout << "MIXT_FRAME is not implemented in vpSimulatorCamera::getPosition()" << std::endl;
260  }
261 }
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void set_pMe(const double q)
Definition: vpPioneerPan.h:210
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:111
#define vpERROR_TRACE
Definition: vpDebug.h:391
double getMaxTranslationVelocity(void) const
Definition: vpRobot.cpp:250
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition: vpRobot.cpp:163
vpControlFrameType
Definition: vpRobot.h:76
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:156
vpHomogeneousMatrix wMm_
double getMaxRotationVelocity(void) const
Definition: vpRobot.cpp:275
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:103
Initialize the velocity controller.
Definition: vpRobot.h:68
vpHomogeneousMatrix mMp_
Definition: vpPioneerPan.h:223
vpMatrix get_eJe() const
Definition: vpUnicycle.h:111
void extract(vpRotationMatrix &R) const
int areJointLimitsAvailable
Definition: vpRobot.h:109
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix cMe_
Definition: vpUnicycle.h:136
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
int nDof
number of degrees of freedom
Definition: vpRobot.h:99
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
vpHomogeneousMatrix pMe_
Definition: vpPioneerPan.h:224
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:138
void getPosition(vpHomogeneousMatrix &wMc) const
double * qmin
Definition: vpRobot.h:110
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition: vpRobot.cpp:208
int fJeAvailable
is the robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:107
void set_eJe(double q_pan)
Definition: vpPioneerPan.h:140
Class that consider the case of a translation vector.
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:217