Visual Servoing Platform  version 3.1.0
vpVirtuose.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: Class which enables to project an image in the 3D space
32  * and get the view of a virtual camera.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
44 #include <visp3/core/vpException.h>
45 #include <visp3/robot/vpVirtuose.h>
46 
47 #ifdef VISP_HAVE_VIRTUOSE
48 
55  : m_virtContext(NULL), m_ip("localhost#5000"), m_verbose(false), m_apiMajorVersion(0), m_apiMinorVersion(0),
56  m_ctrlMajorVersion(0), m_ctrlMinorVersion(0), m_typeCommand(COMMAND_TYPE_IMPEDANCE), m_indexType(INDEXING_ALL),
57  m_is_init(false), m_period(0.001f)
58 {
59  virtAPIVersion(&m_apiMajorVersion, &m_apiMinorVersion);
60  std::cout << "API version: " << m_apiMajorVersion << "." << m_apiMinorVersion << std::endl;
61 }
62 
67 {
68  if (m_virtContext != NULL) {
69  virtClose(m_virtContext);
70  m_virtContext = NULL;
71  }
72 }
73 
82 {
83  if (force.size() != 6) {
85  "Cannot apply a force feedback (dim %d) to the haptic "
86  "device that is not 6-dimension",
87  force.size()));
88  }
89 
90  init();
91 
92  float virtforce[6];
93  for (unsigned int i = 0; i < 6; i++)
94  virtforce[i] = (float)force[i];
95 
96  if (virtAddForce(m_virtContext, virtforce)) {
97  int err = virtGetErrorCode(m_virtContext);
98  throw(vpException(vpException::fatalError, "Error calling virtAddForce: error code %d", err));
99  }
100 }
101 
107 {
108  init();
109 
110  if (virtEnableForceFeedback(m_virtContext, enable)) {
111  int err = virtGetErrorCode(m_virtContext);
112  throw(vpException(vpException::fatalError, "Error calling virtEnableForceFeedback(): error code %d", err));
113  }
114 }
115 
120 {
121  if (!m_is_init) {
122  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
123  }
124 
125  vpColVector articularPosition(6, 0);
126 
127  float articular_position_[6];
128  if (virtGetArticularPosition(m_virtContext, articular_position_)) {
129  int err = virtGetErrorCode(m_virtContext);
130  throw(vpException(vpException::fatalError, "Error calling virtGetArticularPosition(): error code %d", err));
131  }
132 
133  for (unsigned int i = 0; i < 6; i++)
134  articularPosition[i] = articular_position_[i];
135 
136  return articularPosition;
137 }
138 
143 {
144  if (!m_is_init) {
145  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
146  }
147 
148  vpColVector articularVelocity(6, 0);
149  float articular_velocity_[6];
150  if (virtGetArticularSpeed(m_virtContext, articular_velocity_)) {
151  int err = virtGetErrorCode(m_virtContext);
152  throw(vpException(vpException::fatalError, "Error calling virtGetArticularSpeed: error code %d", err));
153  }
154 
155  for (unsigned int i = 0; i < 6; i++)
156  articularVelocity[i] = articular_velocity_[i];
157 
158  return articularVelocity;
159 }
160 
169 {
170  if (!m_is_init) {
171  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
172  }
173 
174  float position_[7];
175  vpPoseVector position;
176  vpTranslationVector translation;
177  vpQuaternionVector quaternion;
178 
179  if (virtGetAvatarPosition(m_virtContext, position_)) {
180  int err = virtGetErrorCode(m_virtContext);
181  throw(vpException(vpException::fatalError, "Error calling virtGetAvatarPosition: error code %d", err));
182  } else {
183  for (int i = 0; i < 3; i++)
184  translation[i] = position_[i];
185  for (int i = 0; i < 4; i++)
186  quaternion[i] = position_[3 + i];
187 
188  vpThetaUVector thetau(quaternion);
189 
190  position.buildFrom(translation, thetau);
191 
192  return position;
193  }
194 }
195 
203 {
204  if (!m_is_init) {
205  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
206  }
207 
208  vpPoseVector position;
209  float position_[7];
210  vpTranslationVector translation;
211  vpQuaternionVector quaternion;
212 
213  if (virtGetBaseFrame(m_virtContext, position_)) {
214  int err = virtGetErrorCode(m_virtContext);
215  throw(vpException(vpException::fatalError, "Error calling virtGetBaseFrame: error code %d", err));
216  } else {
217  for (int i = 0; i < 3; i++)
218  translation[i] = position_[i];
219  for (int i = 0; i < 4; i++)
220  quaternion[i] = position_[3 + i];
221 
222  vpThetaUVector thetau(quaternion);
223 
224  position.buildFrom(translation, thetau);
225 
226  return position;
227  }
228 }
229 
233 VirtCommandType vpVirtuose::getCommandType() const
234 {
235  if (!m_is_init) {
236  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
237  }
238 
239  VirtCommandType type;
240 
241  if (virtGetCommandType(m_virtContext, &type)) {
242  int err = virtGetErrorCode(m_virtContext);
243  throw(vpException(vpException::fatalError, "Error calling virtGetCommandType: error code %d", err));
244  }
245  return type;
246 }
247 
253 {
254  if (!m_is_init) {
255  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
256  }
257 
258  int deadman;
259  if (virtGetDeadMan(m_virtContext, &deadman)) {
260  int err = virtGetErrorCode(m_virtContext);
261  throw(vpException(vpException::fatalError, "Error calling virtGetDeadMan: error code %d", err));
262  }
263  return (deadman ? true : false);
264 }
265 
272 {
273  if (!m_is_init) {
274  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
275  }
276 
277  int emergencyStop;
278  if (virtGetEmergencyStop(m_virtContext, &emergencyStop)) {
279  int err = virtGetErrorCode(m_virtContext);
280  throw(vpException(vpException::fatalError, "Error calling virtGetEmergencyStop: error code %d", err));
281  }
282  return (emergencyStop ? true : false);
283 }
284 
290 {
291  if (!m_is_init) {
292  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
293  }
294 
295  vpColVector force(6, 0);
296  float force_[6];
297  if (virtGetForce(m_virtContext, force_)) {
298  int err = virtGetErrorCode(m_virtContext);
299  throw(vpException(vpException::fatalError, "Error calling virtGetForce: error code %d", err));
300  }
301 
302  for (unsigned int i = 0; i < 6; i++)
303  force[i] = force_[i];
304  return force;
305 }
306 
339 VirtContext vpVirtuose::getHandler() { return m_virtContext; }
340 
348 {
349  if (!m_is_init) {
350  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
351  }
352 
353  vpPoseVector position;
354  float position_[7];
355  vpTranslationVector translation;
356  vpQuaternionVector quaternion;
357 
358  if (virtGetObservationFrame(m_virtContext, position_)) {
359  int err = virtGetErrorCode(m_virtContext);
360  throw(vpException(vpException::fatalError, "Error calling virtGetObservationFrame: error code %d", err));
361  } else {
362  for (int i = 0; i < 3; i++)
363  translation[i] = position_[i];
364  for (int i = 0; i < 4; i++)
365  quaternion[i] = position_[3 + i];
366 
367  vpThetaUVector thetau(quaternion);
368 
369  position.buildFrom(translation, thetau);
370  }
371  return position;
372 }
373 
380 {
381  if (!m_is_init) {
382  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
383  }
384 
385  vpPoseVector position;
386  float position_[7];
387  vpTranslationVector translation;
388  vpQuaternionVector quaternion;
389 
390  if (virtGetPhysicalPosition(m_virtContext, position_)) {
391  int err = virtGetErrorCode(m_virtContext);
392  throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalPosition: error code %d", err));
393  } else {
394  for (int i = 0; i < 3; i++)
395  translation[i] = position_[i];
396  for (int i = 0; i < 4; i++)
397  quaternion[i] = position_[3 + i];
398 
399  vpThetaUVector thetau(quaternion);
400 
401  position.buildFrom(translation, thetau);
402  }
403  return position;
404 }
405 
413 {
414  if (!m_is_init) {
415  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
416  }
417 
418  vpColVector vel(6, 0);
419  float speed[6];
420  if (virtGetPhysicalSpeed(m_virtContext, speed)) {
421  int err = virtGetErrorCode(m_virtContext);
422  throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalSpeed: error code %s",
423  virtGetErrorMessage(err)));
424  }
425  for (unsigned int i = 0; i < 6; i++)
426  vel[i] = speed[i];
427  return vel;
428 }
429 
436 {
437  if (!m_is_init) {
438  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
439  }
440 
441  vpPoseVector position;
442  float position_[7];
443  vpTranslationVector translation;
444  vpQuaternionVector quaternion;
445 
446  if (virtGetPosition(m_virtContext, position_)) {
447  int err = virtGetErrorCode(m_virtContext);
448  throw(vpException(vpException::fatalError, "Error calling virtGetPosition: error code %d", err));
449  } else {
450  for (int i = 0; i < 3; i++)
451  translation[i] = position_[i];
452  for (int i = 0; i < 4; i++)
453  quaternion[i] = position_[3 + i];
454 
455  vpThetaUVector thetau(quaternion);
456 
457  position.buildFrom(translation, thetau);
458  }
459  return position;
460 }
461 
466 {
467  if (!m_is_init) {
468  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
469  }
470 
471  int power;
472  virtGetPowerOn(m_virtContext, &power);
473  return (power ? true : false);
474 }
475 
483 {
484  if (!m_is_init) {
485  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
486  }
487 
488  vpColVector vel(6, 0);
489  float speed[6];
490  if (virtGetSpeed(m_virtContext, speed)) {
491  int err = virtGetErrorCode(m_virtContext);
492  throw(vpException(vpException::fatalError, "Cannot get haptic device velocity: %s", virtGetErrorMessage(err)));
493  }
494  for (unsigned int i = 0; i < 6; i++)
495  vel[i] = speed[i];
496  return vel;
497 }
498 
505 {
506  if (!m_is_init) {
507  m_virtContext = virtOpen(m_ip.c_str());
508 
509  if (m_virtContext == NULL) {
510  int err = virtGetErrorCode(m_virtContext);
511  throw(vpException(vpException::fatalError, "Cannot open haptic device: %s", virtGetErrorMessage(err)));
512  }
513 
514  if (virtGetControlerVersion(m_virtContext, &m_ctrlMajorVersion, &m_ctrlMinorVersion)) {
515  int err = virtGetErrorCode(m_virtContext);
516  throw(vpException(vpException::fatalError, "Cannot get haptic device controller version: %s",
517  virtGetErrorMessage(err)));
518  }
519 
520  if (m_verbose) {
521  std::cout << "Controller version: " << m_ctrlMajorVersion << "." << m_ctrlMinorVersion << std::endl;
522  }
523 
524  if (virtSetCommandType(m_virtContext, m_typeCommand)) {
525  int err = virtGetErrorCode(m_virtContext);
526  throw(
527  vpException(vpException::fatalError, "Cannot set haptic device command type: %s", virtGetErrorMessage(err)));
528  }
529 
530  if (virtSetTimeStep(m_virtContext, m_period)) {
531  int err = virtGetErrorCode(m_virtContext);
532  throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
533  }
534 
535  m_is_init = true;
536  }
537 }
538 
545 void vpVirtuose::setArticularForce(const vpColVector &articularForce)
546 {
547  init();
548 
549  if (articularForce.size() != 6) {
551  "Cannot apply an articular force feedback (dim %d) to "
552  "the haptic device that is not 6-dimension",
553  articularForce.size()));
554  }
555 
556  float articular_force[6];
557  for (unsigned int i = 0; i < 6; i++)
558  articular_force[i] = (float)articularForce[i];
559 
560  if (virtSetArticularForce(m_virtContext, articular_force)) {
561  int err = virtGetErrorCode(m_virtContext);
562  throw(vpException(vpException::fatalError, "Error calling virtSetArticularForce: error code %d", err));
563  }
564 }
565 
572 void vpVirtuose::setArticularPosition(const vpColVector &articularPosition)
573 {
574  init();
575 
576  if (articularPosition.size() != 6) {
578  "Cannot send an articular position command (dim %d) to "
579  "the haptic device that is not 6-dimension",
580  articularPosition.size()));
581  }
582 
583  float articular_position[6];
584  for (unsigned int i = 0; i < 6; i++)
585  articular_position[i] = (float)articularPosition[i];
586 
587  if (virtSetArticularPosition(m_virtContext, articular_position)) {
588  int err = virtGetErrorCode(m_virtContext);
589  throw(vpException(vpException::fatalError, "Error calling virtSetArticularPosition: error code %d", err));
590  }
591 }
592 
599 void vpVirtuose::setArticularVelocity(const vpColVector &articularVelocity)
600 {
601  init();
602 
603  if (articularVelocity.size() != 6) {
605  "Cannot send an articular velocity command (dim %d) to "
606  "the haptic device that is not 6-dimension",
607  articularVelocity.size()));
608  }
609 
610  float articular_velocity[6];
611  for (unsigned int i = 0; i < 6; i++)
612  articular_velocity[i] = (float)articularVelocity[i];
613 
614  if (virtSetArticularSpeed(m_virtContext, articular_velocity)) {
615  int err = virtGetErrorCode(m_virtContext);
616  throw(vpException(vpException::fatalError, "Error calling virtSetArticularVelocity: error code %d", err));
617  }
618 }
619 
628 {
629  init();
630 
631  float position_[7];
632  vpTranslationVector translation;
633  vpQuaternionVector quaternion;
634 
635  position.extract(translation);
636  position.extract(quaternion);
637 
638  for (int i = 0; i < 3; i++)
639  position_[i] = (float)translation[i];
640  for (int i = 0; i < 4; i++)
641  position_[3 + i] = (float)quaternion[i];
642 
643  if (virtSetBaseFrame(m_virtContext, position_)) {
644  int err = virtGetErrorCode(m_virtContext);
645  throw(vpException(vpException::fatalError, "Error calling virtSetBaseFrame: error code %d", err));
646  }
647 }
648 
659 void vpVirtuose::setCommandType(const VirtCommandType &type)
660 {
661  init();
662 
663  if (m_typeCommand != type) {
664  m_typeCommand = type;
665 
666  if (virtSetCommandType(m_virtContext, m_typeCommand)) {
667  int err = virtGetErrorCode(m_virtContext);
668  throw(vpException(vpException::fatalError, "Error calling virtSetCommandType: error code %d", err));
669  }
670  }
671 }
672 
680 {
681  init();
682 
683  if (force.size() != 6) {
685  "Cannot apply a force feedback (dim %d) to the haptic "
686  "device that is not 6-dimension",
687  force.size()));
688  }
689 
690  float virtforce[6];
691  for (unsigned int i = 0; i < 6; i++)
692  virtforce[i] = (float)force[i];
693 
694  if (virtSetForce(m_virtContext, virtforce)) {
695  int err = virtGetErrorCode(m_virtContext);
696  throw(vpException(vpException::fatalError, "Error calling virtSetForce: error code %d", err));
697  }
698 }
699 
705 void vpVirtuose::setForceFactor(const float &forceFactor)
706 {
707  init();
708 
709  if (virtSetForceFactor(m_virtContext, forceFactor)) {
710  int err = virtGetErrorCode(m_virtContext);
711  throw(vpException(vpException::fatalError, "Error calling virtSetForceFactor: error code %d", err));
712  }
713 }
714 
729 void vpVirtuose::setIndexingMode(const VirtIndexingType &type)
730 {
731  init();
732 
733  if (m_indexType != type) {
734  m_indexType = type;
735 
736  if (virtSetIndexingMode(m_virtContext, m_indexType)) {
737  int err = virtGetErrorCode(m_virtContext);
738  throw(vpException(vpException::fatalError, "Error calling setIndexingMode: error code %d", err));
739  }
740  }
741 }
742 
751 {
752  init();
753 
754  float position_[7];
755  vpTranslationVector translation;
756  vpQuaternionVector quaternion;
757 
758  position.extract(translation);
759  position.extract(quaternion);
760 
761  for (int i = 0; i < 3; i++)
762  position_[i] = (float)translation[i];
763  for (int i = 0; i < 4; i++)
764  position_[3 + i] = (float)quaternion[i];
765 
766  if (virtSetObservationFrame(m_virtContext, position_)) {
767  int err = virtGetErrorCode(m_virtContext);
768  throw(vpException(vpException::fatalError, "Error calling virtSetObservationFrame: error code %d", err));
769  }
770 }
771 
811 void vpVirtuose::setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
812 {
813  init();
814 
815  if (virtSetPeriodicFunction(m_virtContext, CallBackVirt, &m_period, this)) {
816  int err = virtGetErrorCode(m_virtContext);
817  throw(vpException(vpException::fatalError, "Error calling virtSetPeriodicFunction: error code %d", err));
818  }
819 }
820 
827 {
828  init();
829 
830  float position_[7];
831  vpTranslationVector translation;
832  vpQuaternionVector quaternion;
833 
834  position.extract(translation);
835  position.extract(quaternion);
836 
837  for (int i = 0; i < 3; i++)
838  position_[i] = (float)translation[i];
839  for (int i = 0; i < 4; i++)
840  position_[3 + i] = (float)quaternion[i];
841 
842  if (virtSetPosition(m_virtContext, position_)) {
843  int err = virtGetErrorCode(m_virtContext);
844  throw(vpException(vpException::fatalError, "Error calling virtSetPosition: error code %d", err));
845  }
846 }
847 
852 {
853  init();
854 
855  if (virtSetPowerOn(m_virtContext, 0)) {
856  int err = virtGetErrorCode(m_virtContext);
857  throw(vpException(vpException::fatalError, "Error calling virtSetPowerOff: error code %d", err));
858  }
859 }
860 
865 {
866  init();
867 
868  if (virtSetPowerOn(m_virtContext, 1)) {
869  int err = virtGetErrorCode(m_virtContext);
870  throw(vpException(vpException::fatalError, "Error calling virtSetPowerOn: error code %d", err));
871  }
872 }
873 
879 void vpVirtuose::setSaturation(const float &forceLimit, const float &torqueLimit)
880 {
881  init();
882 
883  if (virtSaturateTorque(m_virtContext, forceLimit, torqueLimit)) {
884  int err = virtGetErrorCode(m_virtContext);
885  throw(vpException(vpException::fatalError, "Error calling virtSaturateTorque: error code %d", err));
886  }
887 }
888 
894 void vpVirtuose::setTimeStep(const float &timeStep)
895 {
896  init();
897 
898  if (m_period != timeStep) {
899  m_period = timeStep;
900 
901  if (virtSetTimeStep(m_virtContext, m_period)) {
902  int err = virtGetErrorCode(m_virtContext);
903  throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
904  }
905  }
906 }
907 
914 {
915  init();
916 
917  if (velocity.size() != 6) {
918  throw(vpException(vpException::dimensionError, "Cannot set a velocity vector (dim %d) that is not 6-dimension",
919  velocity.size()));
920  }
921 
922  float speed[6];
923  for (unsigned int i = 0; i < 6; i++)
924  speed[i] = (float)velocity[i];
925 
926  if (virtSetSpeed(m_virtContext, speed)) {
927  int err = virtGetErrorCode(m_virtContext);
928  throw(vpException(vpException::fatalError, "Error calling virtSetSpeed: error code %d", err));
929  }
930 }
931 
937 void vpVirtuose::setVelocityFactor(const float &velocityFactor)
938 {
939  init();
940 
941  if (virtSetSpeedFactor(m_virtContext, velocityFactor)) {
942  int err = virtGetErrorCode(m_virtContext);
943  throw(vpException(vpException::fatalError, "Error calling setVelocityFactor: error code %d", err));
944  }
945 }
946 
953 {
954  init();
955 
956  if (virtStartLoop(m_virtContext)) {
957  int err = virtGetErrorCode(m_virtContext);
958  throw(vpException(vpException::fatalError, "Error calling startLoop: error code %d", err));
959  } else
960  std::cout << "Haptic loop open." << std::endl;
961 }
962 
969 {
970  init();
971 
972  if (virtStopLoop(m_virtContext)) {
973  int err = virtGetErrorCode(m_virtContext);
974  throw(vpException(vpException::fatalError, "Error calling stopLoop: error code %d", err));
975  } else
976  std::cout << "Haptic loop closed." << std::endl;
977 }
978 
979 #else
980 // Work around to avoid warning
981 void dummy_vpVirtuose(){};
982 #endif
void setSaturation(const float &forceLimit, const float &torqueLimit)
Definition: vpVirtuose.cpp:879
void startPeriodicFunction()
Definition: vpVirtuose.cpp:952
int m_apiMinorVersion
Definition: vpVirtuose.h:204
vpColVector getForce() const
Definition: vpVirtuose.cpp:289
VirtCommandType m_typeCommand
Definition: vpVirtuose.h:207
VirtCommandType getCommandType() const
Definition: vpVirtuose.cpp:233
void setVelocityFactor(const float &velocityFactor)
Definition: vpVirtuose.cpp:937
void extract(vpRotationMatrix &R) const
vpPoseVector getPhysicalPosition() const
Definition: vpVirtuose.cpp:379
vpColVector getArticularPosition() const
Definition: vpVirtuose.cpp:119
vpColVector getArticularVelocity() const
Definition: vpVirtuose.cpp:142
error that can be emited by ViSP classes.
Definition: vpException.h:71
void setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
Definition: vpVirtuose.cpp:811
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:158
void setForce(const vpColVector &force)
Definition: vpVirtuose.cpp:679
void setForceFactor(const float &forceFactor)
Definition: vpVirtuose.cpp:705
VirtContext m_virtContext
Definition: vpVirtuose.h:200
VirtIndexingType m_indexType
Definition: vpVirtuose.h:208
bool m_verbose
Definition: vpVirtuose.h:202
void setArticularVelocity(const vpColVector &articularVelocity)
Definition: vpVirtuose.cpp:599
void setVelocity(vpColVector &velocity)
Definition: vpVirtuose.cpp:913
vpPoseVector getBaseFrame() const
Definition: vpVirtuose.cpp:202
bool m_is_init
Definition: vpVirtuose.h:209
void enableForceFeedback(int enable)
Definition: vpVirtuose.cpp:106
VirtContext getHandler()
Definition: vpVirtuose.cpp:339
int m_ctrlMinorVersion
Definition: vpVirtuose.h:206
void setPowerOn()
Definition: vpVirtuose.cpp:864
void setPowerOff()
Definition: vpVirtuose.cpp:851
void setCommandType(const VirtCommandType &type)
Definition: vpVirtuose.cpp:659
void setBaseFrame(const vpPoseVector &position)
Definition: vpVirtuose.cpp:627
vpPoseVector getAvatarPosition() const
Definition: vpVirtuose.cpp:168
std::string m_ip
Definition: vpVirtuose.h:201
Implementation of a rotation vector as quaternion angle minimal representation.
vpPoseVector getPosition() const
Definition: vpVirtuose.cpp:435
void setPosition(vpPoseVector &position)
Definition: vpVirtuose.cpp:826
void setArticularForce(const vpColVector &articularForce)
Definition: vpVirtuose.cpp:545
bool getPower() const
Definition: vpVirtuose.cpp:465
void setArticularPosition(const vpColVector &articularPosition)
Definition: vpVirtuose.cpp:572
void stopPeriodicFunction()
Definition: vpVirtuose.cpp:968
void setIndexingMode(const VirtIndexingType &type)
Definition: vpVirtuose.cpp:729
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
float m_period
Definition: vpVirtuose.h:210
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:92
int m_apiMajorVersion
Definition: vpVirtuose.h:203
vpColVector getPhysicalVelocity() const
Definition: vpVirtuose.cpp:412
int m_ctrlMajorVersion
Definition: vpVirtuose.h:205
void init()
Definition: vpVirtuose.cpp:504
void setObservationFrame(const vpPoseVector &position)
Definition: vpVirtuose.cpp:750
vpColVector getVelocity() const
Definition: vpVirtuose.cpp:482
bool getEmergencyStop() const
Definition: vpVirtuose.cpp:271
vpPoseVector buildFrom(const double tx, const double ty, const double tz, const double tux, const double tuy, const double tuz)
void addForce(vpColVector &force)
Definition: vpVirtuose.cpp:81
void setTimeStep(const float &timeStep)
Definition: vpVirtuose.cpp:894
Class that consider the case of a translation vector.
Implementation of a rotation vector as axis-angle minimal representation.
bool getDeadMan() const
Definition: vpVirtuose.cpp:252
vpPoseVector getObservationFrame() const
Definition: vpVirtuose.cpp:347