Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpVirtuose.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: Class which enables to project an image in the 3D space
32  * and get the view of a virtual camera.
33  *
34 *****************************************************************************/
35 
41 #include <visp3/core/vpException.h>
42 #include <visp3/robot/vpVirtuose.h>
43 
44 #ifdef VISP_HAVE_VIRTUOSE
52  : m_virtContext(nullptr), m_ip_port("localhost#5000"), m_verbose(false), m_apiMajorVersion(0), m_apiMinorVersion(0),
53  m_ctrlMajorVersion(0), m_ctrlMinorVersion(0), m_typeCommand(COMMAND_TYPE_IMPEDANCE), m_indexType(INDEXING_ALL),
54  m_is_init(false), m_period(0.001f), m_njoints(6)
55 {
56  virtAPIVersion(&m_apiMajorVersion, &m_apiMinorVersion);
57  std::cout << "API version: " << m_apiMajorVersion << "." << m_apiMinorVersion << std::endl;
58 }
59 
64 {
65  if (m_virtContext != nullptr) {
66  virtClose(m_virtContext);
67  m_virtContext = nullptr;
68  }
69 }
70 
75 
81 void vpVirtuose::setIpAddressAndPort(const std::string &ip, int port)
82 {
83  std::stringstream ss;
84  ss << ip << "#" << port;
85 
86  m_ip_port = ss.str();
87 }
88 
97 {
98  if (force.size() != 6) {
100  "Cannot apply a force feedback (dim %d) to the haptic "
101  "device that is not 6-dimension",
102  force.size()));
103  }
104 
105  init();
106 
107  float virtforce[6];
108  for (unsigned int i = 0; i < 6; i++)
109  virtforce[i] = (float)force[i];
110 
111  if (virtAddForce(m_virtContext, virtforce)) {
112  int err = virtGetErrorCode(m_virtContext);
113  throw(vpException(vpException::fatalError, "Error calling virtAddForce: error code %d", err));
114  }
115 }
116 
122 {
123  init();
124 
125  if (virtEnableForceFeedback(m_virtContext, enable)) {
126  int err = virtGetErrorCode(m_virtContext);
127  throw(vpException(vpException::fatalError, "Error calling virtEnableForceFeedback(): error code %d", err));
128  }
129 }
130 
135 {
136  if (!m_is_init) {
137  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
138  }
139 
140  float articular_position_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
141 
142  if (virtGetArticularPosition(m_virtContext, articular_position_)) {
143  int err = virtGetErrorCode(m_virtContext);
144  throw(vpException(vpException::fatalError, "Error calling virtGetArticularPosition(): error code %d", err));
145  }
146 
147  vpColVector articularPosition(m_njoints, 0);
148  for (unsigned int i = 0; i < m_njoints; i++)
149  articularPosition[i] = articular_position_[i];
150 
151  return articularPosition;
152 }
153 
158 {
159  if (!m_is_init) {
160  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
161  }
162 
163  float articular_velocity_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
164 
165  if (virtGetArticularSpeed(m_virtContext, articular_velocity_)) {
166  int err = virtGetErrorCode(m_virtContext);
167  throw(vpException(vpException::fatalError, "Error calling virtGetArticularSpeed: error code %d", err));
168  }
169 
170  vpColVector articularVelocity(m_njoints, 0);
171 
172  for (unsigned int i = 0; i < m_njoints; i++)
173  articularVelocity[i] = articular_velocity_[i];
174 
175  return articularVelocity;
176 }
177 
186 {
187  if (!m_is_init) {
188  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
189  }
190 
191  float position_[7];
192  vpPoseVector position;
193  vpTranslationVector translation;
194  vpQuaternionVector quaternion;
195 
196  if (virtGetAvatarPosition(m_virtContext, position_)) {
197  int err = virtGetErrorCode(m_virtContext);
198  throw(vpException(vpException::fatalError, "Error calling virtGetAvatarPosition: error code %d", err));
199  }
200  else {
201  for (int i = 0; i < 3; i++)
202  translation[i] = position_[i];
203  for (int i = 0; i < 4; i++)
204  quaternion[i] = position_[3 + i];
205 
206  vpThetaUVector thetau(quaternion);
207 
208  position.build(translation, thetau);
209 
210  return position;
211  }
212 }
213 
221 {
222  if (!m_is_init) {
223  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
224  }
225 
226  vpPoseVector position;
227  float position_[7];
228  vpTranslationVector translation;
229  vpQuaternionVector quaternion;
230 
231  if (virtGetBaseFrame(m_virtContext, position_)) {
232  int err = virtGetErrorCode(m_virtContext);
233  throw(vpException(vpException::fatalError, "Error calling virtGetBaseFrame: error code %d", err));
234  }
235  else {
236  for (int i = 0; i < 3; i++)
237  translation[i] = position_[i];
238  for (int i = 0; i < 4; i++)
239  quaternion[i] = position_[3 + i];
240 
241  vpThetaUVector thetau(quaternion);
242 
243  position.build(translation, thetau);
244 
245  return position;
246  }
247 }
248 
252 VirtCommandType vpVirtuose::getCommandType() const
253 {
254  if (!m_is_init) {
255  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
256  }
257 
258  VirtCommandType type;
259 
260  if (virtGetCommandType(m_virtContext, &type)) {
261  int err = virtGetErrorCode(m_virtContext);
262  throw(vpException(vpException::fatalError, "Error calling virtGetCommandType: error code %d", err));
263  }
264  return type;
265 }
266 
272 {
273  if (!m_is_init) {
274  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
275  }
276 
277  int deadman;
278  if (virtGetDeadMan(m_virtContext, &deadman)) {
279  int err = virtGetErrorCode(m_virtContext);
280  throw(vpException(vpException::fatalError, "Error calling virtGetDeadMan: error code %d", err));
281  }
282  return (deadman ? true : false);
283 }
284 
291 {
292  if (!m_is_init) {
293  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
294  }
295 
296  int emergencyStop;
297  if (virtGetEmergencyStop(m_virtContext, &emergencyStop)) {
298  int err = virtGetErrorCode(m_virtContext);
299  throw(vpException(vpException::fatalError, "Error calling virtGetEmergencyStop: error code %d", err));
300  }
301  return (emergencyStop ? true : false);
302 }
303 
309 {
310  if (!m_is_init) {
311  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
312  }
313 
314  vpColVector force(6, 0);
315  float force_[6];
316  if (virtGetForce(m_virtContext, force_)) {
317  int err = virtGetErrorCode(m_virtContext);
318  throw(vpException(vpException::fatalError, "Error calling virtGetForce: error code %d", err));
319  }
320 
321  for (unsigned int i = 0; i < 6; i++)
322  force[i] = force_[i];
323  return force;
324 }
325 
362 VirtContext vpVirtuose::getHandler() { return m_virtContext; }
363 
369 unsigned int vpVirtuose::getJointsNumber() const
370 {
371  if (!m_is_init) {
372  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
373  }
374 
375  return m_njoints;
376 }
377 
385 {
386  if (!m_is_init) {
387  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
388  }
389 
390  vpPoseVector position;
391  float position_[7];
392  vpTranslationVector translation;
393  vpQuaternionVector quaternion;
394 
395  if (virtGetObservationFrame(m_virtContext, position_)) {
396  int err = virtGetErrorCode(m_virtContext);
397  throw(vpException(vpException::fatalError, "Error calling virtGetObservationFrame: error code %d", err));
398  }
399  else {
400  for (int i = 0; i < 3; i++)
401  translation[i] = position_[i];
402  for (int i = 0; i < 4; i++)
403  quaternion[i] = position_[3 + i];
404 
405  vpThetaUVector thetau(quaternion);
406 
407  position.build(translation, thetau);
408  }
409  return position;
410 }
411 
419 {
420  if (!m_is_init) {
421  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
422  }
423 
424  vpPoseVector position;
425  float position_[7];
426  vpTranslationVector translation;
427  vpQuaternionVector quaternion;
428 
429  if (virtGetPhysicalPosition(m_virtContext, position_)) {
430  int err = virtGetErrorCode(m_virtContext);
431  throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalPosition: error code %d", err));
432  }
433  else {
434  for (int i = 0; i < 3; i++)
435  translation[i] = position_[i];
436  for (int i = 0; i < 4; i++)
437  quaternion[i] = position_[3 + i];
438 
439  vpThetaUVector thetau(quaternion);
440 
441  position.build(translation, thetau);
442  }
443  return position;
444 }
445 
453 {
454  if (!m_is_init) {
455  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
456  }
457 
458  vpColVector vel(6, 0);
459  float speed[6];
460  if (virtGetPhysicalSpeed(m_virtContext, speed)) {
461  int err = virtGetErrorCode(m_virtContext);
462  throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalSpeed: error code %s",
463  virtGetErrorMessage(err)));
464  }
465  for (unsigned int i = 0; i < 6; i++)
466  vel[i] = speed[i];
467  return vel;
468 }
469 
476 {
477  if (!m_is_init) {
478  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
479  }
480 
481  vpPoseVector position;
482  float position_[7];
483  vpTranslationVector translation;
484  vpQuaternionVector quaternion;
485 
486  if (virtGetPosition(m_virtContext, position_)) {
487  int err = virtGetErrorCode(m_virtContext);
488  throw(vpException(vpException::fatalError, "Error calling virtGetPosition: error code %d", err));
489  }
490  else {
491  for (int i = 0; i < 3; i++)
492  translation[i] = position_[i];
493  for (int i = 0; i < 4; i++)
494  quaternion[i] = position_[3 + i];
495 
496  vpThetaUVector thetau(quaternion);
497 
498  position.build(translation, thetau);
499  }
500  return position;
501 }
502 
507 {
508  if (!m_is_init) {
509  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
510  }
511 
512  int power;
513  virtGetPowerOn(m_virtContext, &power);
514  return (power ? true : false);
515 }
516 
524 {
525  if (!m_is_init) {
526  throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
527  }
528 
529  vpColVector vel(6, 0);
530  float speed[6];
531  if (virtGetSpeed(m_virtContext, speed)) {
532  int err = virtGetErrorCode(m_virtContext);
533  throw(vpException(vpException::fatalError, "Cannot get haptic device velocity: %s", virtGetErrorMessage(err)));
534  }
535  for (unsigned int i = 0; i < 6; i++)
536  vel[i] = speed[i];
537  return vel;
538 }
539 
546 {
547  if (!m_is_init) {
548  m_virtContext = virtOpen(m_ip_port.c_str());
549 
550  if (m_virtContext == nullptr) {
551  int err = virtGetErrorCode(m_virtContext);
553  "Cannot open communication with haptic device using %s: %s. Check ip and port values",
554  m_ip_port.c_str(), virtGetErrorMessage(err)));
555  }
556 
557  if (virtGetControlerVersion(m_virtContext, &m_ctrlMajorVersion, &m_ctrlMinorVersion)) {
558  int err = virtGetErrorCode(m_virtContext);
559  throw(vpException(vpException::fatalError, "Cannot get haptic device controller version: %s",
560  virtGetErrorMessage(err)));
561  }
562 
563  if (m_verbose) {
564  std::cout << "Controller version: " << m_ctrlMajorVersion << "." << m_ctrlMinorVersion << std::endl;
565  }
566 
567  if (virtSetCommandType(m_virtContext, m_typeCommand)) {
568  int err = virtGetErrorCode(m_virtContext);
569  throw(
570  vpException(vpException::fatalError, "Cannot set haptic device command type: %s", virtGetErrorMessage(err)));
571  }
572 
573  if (virtSetTimeStep(m_virtContext, m_period)) {
574  int err = virtGetErrorCode(m_virtContext);
575  throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
576  }
577 
578  // Update number of joints
579  float articular_position_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
580 
581  if (virtGetArticularPosition(m_virtContext, articular_position_)) {
582  int err = virtGetErrorCode(m_virtContext);
583  throw(vpException(vpException::fatalError, "Error calling virtGetArticularPosition() in int(): error code %d",
584  err));
585  }
586 
587  m_njoints = 6; // At least 6 joints
588  for (unsigned int i = m_njoints; i < 20; i++) {
589  m_njoints = i;
590  if (std::fabs(articular_position_[i]) <= std::numeric_limits<float>::epsilon()) {
591  break;
592  }
593  }
594 
595  m_is_init = true;
596  }
597 }
598 
606 void vpVirtuose::setArticularForce(const vpColVector &articularForce)
607 {
608  init();
609 
610  if (articularForce.size() != m_njoints) {
612  "Cannot apply an articular force feedback (dim %d) to "
613  "the haptic device that is not 6-dimension",
614  articularForce.size()));
615  }
616 
617  float *articular_force = new float[m_njoints];
618  for (unsigned int i = 0; i < m_njoints; i++)
619  articular_force[i] = (float)articularForce[i];
620 
621  if (virtSetArticularForce(m_virtContext, articular_force)) {
622  delete[] articular_force;
623  int err = virtGetErrorCode(m_virtContext);
624  throw(vpException(vpException::fatalError, "Error calling virtSetArticularForce: error code %d", err));
625  }
626 
627  delete[] articular_force;
628 }
629 
637 void vpVirtuose::setArticularPosition(const vpColVector &articularPosition)
638 {
639  init();
640 
641  if (articularPosition.size() != m_njoints) {
643  "Cannot send an articular position command (dim %d) to "
644  "the haptic device that is not %d-dimension",
645  m_njoints, articularPosition.size()));
646  }
647 
648  float *articular_position = new float[m_njoints];
649  for (unsigned int i = 0; i < m_njoints; i++)
650  articular_position[i] = (float)articularPosition[i];
651 
652  if (virtSetArticularPosition(m_virtContext, articular_position)) {
653  int err = virtGetErrorCode(m_virtContext);
654  delete[] articular_position;
655  throw(vpException(vpException::fatalError, "Error calling virtSetArticularPosition: error code %d", err));
656  }
657  delete[] articular_position;
658 }
659 
667 void vpVirtuose::setArticularVelocity(const vpColVector &articularVelocity)
668 {
669  init();
670 
671  if (articularVelocity.size() != m_njoints) {
673  "Cannot send an articular velocity command (dim %d) to "
674  "the haptic device that is not %d-dimension",
675  m_njoints, articularVelocity.size()));
676  }
677 
678  float *articular_velocity = new float[m_njoints];
679  for (unsigned int i = 0; i < m_njoints; i++)
680  articular_velocity[i] = (float)articularVelocity[i];
681 
682  if (virtSetArticularSpeed(m_virtContext, articular_velocity)) {
683  int err = virtGetErrorCode(m_virtContext);
684  delete[] articular_velocity;
685  throw(vpException(vpException::fatalError, "Error calling virtSetArticularVelocity: error code %d", err));
686  }
687  delete[] articular_velocity;
688 }
689 
698 {
699  init();
700 
701  float position_[7];
702  vpTranslationVector translation;
703  vpQuaternionVector quaternion;
704 
705  position.extract(translation);
706  position.extract(quaternion);
707 
708  for (int i = 0; i < 3; i++)
709  position_[i] = (float)translation[i];
710  for (int i = 0; i < 4; i++)
711  position_[3 + i] = (float)quaternion[i];
712 
713  if (virtSetBaseFrame(m_virtContext, position_)) {
714  int err = virtGetErrorCode(m_virtContext);
715  throw(vpException(vpException::fatalError, "Error calling virtSetBaseFrame: error code %d", err));
716  }
717 }
718 
729 void vpVirtuose::setCommandType(const VirtCommandType &type)
730 {
731  init();
732 
733  if (m_typeCommand != type) {
734  m_typeCommand = type;
735 
736  if (virtSetCommandType(m_virtContext, m_typeCommand)) {
737  int err = virtGetErrorCode(m_virtContext);
738  throw(vpException(vpException::fatalError, "Error calling virtSetCommandType: error code %d", err));
739  }
740  }
741 }
742 
750 {
751  init();
752 
753  if (force.size() != 6) {
755  "Cannot apply a force feedback (dim %d) to the haptic "
756  "device that is not 6-dimension",
757  force.size()));
758  }
759 
760  float virtforce[6];
761  for (unsigned int i = 0; i < 6; i++)
762  virtforce[i] = (float)force[i];
763 
764  if (virtSetForce(m_virtContext, virtforce)) {
765  int err = virtGetErrorCode(m_virtContext);
766  throw(vpException(vpException::fatalError, "Error calling virtSetForce: error code %d", err));
767  }
768 }
769 
775 void vpVirtuose::setForceFactor(const float &forceFactor)
776 {
777  init();
778 
779  if (virtSetForceFactor(m_virtContext, forceFactor)) {
780  int err = virtGetErrorCode(m_virtContext);
781  throw(vpException(vpException::fatalError, "Error calling virtSetForceFactor: error code %d", err));
782  }
783 }
784 
799 void vpVirtuose::setIndexingMode(const VirtIndexingType &type)
800 {
801  init();
802 
803  if (m_indexType != type) {
804  m_indexType = type;
805 
806  if (virtSetIndexingMode(m_virtContext, m_indexType)) {
807  int err = virtGetErrorCode(m_virtContext);
808  throw(vpException(vpException::fatalError, "Error calling setIndexingMode: error code %d", err));
809  }
810  }
811 }
812 
821 {
822  init();
823 
824  float position_[7];
825  vpTranslationVector translation;
826  vpQuaternionVector quaternion;
827 
828  position.extract(translation);
829  position.extract(quaternion);
830 
831  for (int i = 0; i < 3; i++)
832  position_[i] = (float)translation[i];
833  for (int i = 0; i < 4; i++)
834  position_[3 + i] = (float)quaternion[i];
835 
836  if (virtSetObservationFrame(m_virtContext, position_)) {
837  int err = virtGetErrorCode(m_virtContext);
838  throw(vpException(vpException::fatalError, "Error calling virtSetObservationFrame: error code %d", err));
839  }
840 }
841 
885 void vpVirtuose::setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
886 {
887  init();
888 
889  if (virtSetPeriodicFunction(m_virtContext, CallBackVirt, &m_period, this)) {
890  int err = virtGetErrorCode(m_virtContext);
891  throw(vpException(vpException::fatalError, "Error calling virtSetPeriodicFunction: error code %d", err));
892  }
893 }
894 
901 {
902  init();
903 
904  float position_[7];
905  vpTranslationVector translation;
906  vpQuaternionVector quaternion;
907 
908  position.extract(translation);
909  position.extract(quaternion);
910 
911  for (int i = 0; i < 3; i++)
912  position_[i] = (float)translation[i];
913  for (int i = 0; i < 4; i++)
914  position_[3 + i] = (float)quaternion[i];
915 
916  if (virtSetPosition(m_virtContext, position_)) {
917  int err = virtGetErrorCode(m_virtContext);
918  throw(vpException(vpException::fatalError, "Error calling virtSetPosition: error code %d", err));
919  }
920 }
921 
926 {
927  init();
928 
929  if (virtSetPowerOn(m_virtContext, 0)) {
930  int err = virtGetErrorCode(m_virtContext);
931  throw(vpException(vpException::fatalError, "Error calling virtSetPowerOff: error code %d", err));
932  }
933 }
934 
939 {
940  init();
941 
942  if (virtSetPowerOn(m_virtContext, 1)) {
943  int err = virtGetErrorCode(m_virtContext);
944  throw(vpException(vpException::fatalError, "Error calling virtSetPowerOn: error code %d", err));
945  }
946 }
947 
953 void vpVirtuose::setSaturation(const float &forceLimit, const float &torqueLimit)
954 {
955  init();
956 
957  if (virtSaturateTorque(m_virtContext, forceLimit, torqueLimit)) {
958  int err = virtGetErrorCode(m_virtContext);
959  throw(vpException(vpException::fatalError, "Error calling virtSaturateTorque: error code %d", err));
960  }
961 }
962 
968 void vpVirtuose::setTimeStep(const float &timeStep)
969 {
970  init();
971 
972  if (m_period != timeStep) {
973  m_period = timeStep;
974 
975  if (virtSetTimeStep(m_virtContext, m_period)) {
976  int err = virtGetErrorCode(m_virtContext);
977  throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
978  }
979  }
980 }
981 
988 {
989  init();
990 
991  if (velocity.size() != 6) {
992  throw(vpException(vpException::dimensionError, "Cannot set a velocity vector (dim %d) that is not 6-dimension",
993  velocity.size()));
994  }
995 
996  float speed[6];
997  for (unsigned int i = 0; i < 6; i++)
998  speed[i] = (float)velocity[i];
999 
1000  if (virtSetSpeed(m_virtContext, speed)) {
1001  int err = virtGetErrorCode(m_virtContext);
1002  throw(vpException(vpException::fatalError, "Error calling virtSetSpeed: error code %d", err));
1003  }
1004 }
1005 
1011 void vpVirtuose::setVelocityFactor(const float &velocityFactor)
1012 {
1013  init();
1014 
1015  if (virtSetSpeedFactor(m_virtContext, velocityFactor)) {
1016  int err = virtGetErrorCode(m_virtContext);
1017  throw(vpException(vpException::fatalError, "Error calling setVelocityFactor: error code %d", err));
1018  }
1019 }
1020 
1027 {
1028  init();
1029 
1030  if (virtStartLoop(m_virtContext)) {
1031  int err = virtGetErrorCode(m_virtContext);
1032  throw(vpException(vpException::fatalError, "Error calling startLoop: error code %d", err));
1033  }
1034  else
1035  std::cout << "Haptic loop open." << std::endl;
1036 }
1037 
1044 {
1045  init();
1046 
1047  if (virtStopLoop(m_virtContext)) {
1048  int err = virtGetErrorCode(m_virtContext);
1049  throw(vpException(vpException::fatalError, "Error calling stopLoop: error code %d", err));
1050  }
1051  else
1052  std::cout << "Haptic loop closed." << std::endl;
1053 }
1054 END_VISP_NAMESPACE
1055 #else
1056 // Work around to avoid warning
1057 void dummy_vpVirtuose() { };
1058 #endif
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
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ dimensionError
Bad dimension.
Definition: vpException.h:71
@ fatalError
Fatal error.
Definition: vpException.h:72
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:203
vpPoseVector & build(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz)
void extract(vpRotationMatrix &R) const
Implementation of a rotation vector as quaternion angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
bool getDeadMan() const
Definition: vpVirtuose.cpp:271
vpColVector getVelocity() const
Definition: vpVirtuose.cpp:523
vpColVector getArticularPosition() const
Definition: vpVirtuose.cpp:134
VirtCommandType getCommandType() const
Definition: vpVirtuose.cpp:252
void setIpAddressAndPort(const std::string &ip, int port)
Definition: vpVirtuose.cpp:81
void init()
Definition: vpVirtuose.cpp:545
void setPowerOff()
Definition: vpVirtuose.cpp:925
void setTimeStep(const float &timeStep)
Definition: vpVirtuose.cpp:968
void setForceFactor(const float &forceFactor)
Definition: vpVirtuose.cpp:775
void setArticularVelocity(const vpColVector &articularVelocity)
Definition: vpVirtuose.cpp:667
void setObservationFrame(const vpPoseVector &position)
Definition: vpVirtuose.cpp:820
void enableForceFeedback(int enable)
Definition: vpVirtuose.cpp:121
vpPoseVector getPosition() const
Definition: vpVirtuose.cpp:475
bool getPower() const
Definition: vpVirtuose.cpp:506
vpPoseVector getBaseFrame() const
Definition: vpVirtuose.cpp:220
bool m_verbose
Definition: vpVirtuose.h:221
VirtContext getHandler()
Definition: vpVirtuose.cpp:362
int m_apiMajorVersion
Definition: vpVirtuose.h:222
void setForce(const vpColVector &force)
Definition: vpVirtuose.cpp:749
void setIndexingMode(const VirtIndexingType &type)
Definition: vpVirtuose.cpp:799
unsigned int getJointsNumber() const
Definition: vpVirtuose.cpp:369
void close()
Definition: vpVirtuose.cpp:63
int m_ctrlMinorVersion
Definition: vpVirtuose.h:225
vpPoseVector getPhysicalPosition() const
Definition: vpVirtuose.cpp:418
unsigned int m_njoints
Definition: vpVirtuose.h:230
float m_period
Definition: vpVirtuose.h:229
bool m_is_init
Definition: vpVirtuose.h:228
std::string m_ip_port
Definition: vpVirtuose.h:220
void setBaseFrame(const vpPoseVector &position)
Definition: vpVirtuose.cpp:697
VirtContext m_virtContext
Definition: vpVirtuose.h:219
vpPoseVector getObservationFrame() const
Definition: vpVirtuose.cpp:384
bool getEmergencyStop() const
Definition: vpVirtuose.cpp:290
void setCommandType(const VirtCommandType &type)
Definition: vpVirtuose.cpp:729
void setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
Definition: vpVirtuose.cpp:885
vpColVector getArticularVelocity() const
Definition: vpVirtuose.cpp:157
void stopPeriodicFunction()
int m_ctrlMajorVersion
Definition: vpVirtuose.h:224
vpPoseVector getAvatarPosition() const
Definition: vpVirtuose.cpp:185
void setPowerOn()
Definition: vpVirtuose.cpp:938
void addForce(vpColVector &force)
Definition: vpVirtuose.cpp:96
void setArticularForce(const vpColVector &articularForce)
Definition: vpVirtuose.cpp:606
int m_apiMinorVersion
Definition: vpVirtuose.h:223
void setPosition(vpPoseVector &position)
Definition: vpVirtuose.cpp:900
void setVelocity(vpColVector &velocity)
Definition: vpVirtuose.cpp:987
VirtCommandType m_typeCommand
Definition: vpVirtuose.h:226
void startPeriodicFunction()
void setVelocityFactor(const float &velocityFactor)
void setSaturation(const float &forceLimit, const float &torqueLimit)
Definition: vpVirtuose.cpp:953
virtual ~vpVirtuose()
Definition: vpVirtuose.cpp:74
vpColVector getPhysicalVelocity() const
Definition: vpVirtuose.cpp:452
void setArticularPosition(const vpColVector &articularPosition)
Definition: vpVirtuose.cpp:637
VirtIndexingType m_indexType
Definition: vpVirtuose.h:227
vpColVector getForce() const
Definition: vpVirtuose.cpp:308