Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpVirtuose.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
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 https://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: Class which enables to project an image in the 3D space
31 * and get the view of a virtual camera.
32 */
33
38
39#include <visp3/core/vpException.h>
40#include <visp3/robot/vpVirtuose.h>
41
42#ifdef VISP_HAVE_VIRTUOSE
50 : m_virtContext(nullptr), m_ip_port("localhost#5000"), m_verbose(false), m_apiMajorVersion(0), m_apiMinorVersion(0),
51 m_ctrlMajorVersion(0), m_ctrlMinorVersion(0), m_typeCommand(COMMAND_TYPE_IMPEDANCE), m_indexType(INDEXING_ALL),
52 m_is_init(false), m_period(0.001f), m_njoints(6)
53{
54 virtAPIVersion(&m_apiMajorVersion, &m_apiMinorVersion);
55 std::cout << "API version: " << m_apiMajorVersion << "." << m_apiMinorVersion << std::endl;
56}
57
62{
63 if (m_virtContext != nullptr) {
64 virtClose(m_virtContext);
65 m_virtContext = nullptr;
66 }
67}
68
73
79void vpVirtuose::setIpAddressAndPort(const std::string &ip, int port)
80{
81 std::stringstream ss;
82 ss << ip << "#" << port;
83
84 m_ip_port = ss.str();
85}
86
95{
96 if (force.size() != 6) {
98 "Cannot apply a force feedback (dim %d) to the haptic "
99 "device that is not 6-dimension",
100 force.size()));
101 }
102
103 init();
104
105 float virtforce[6];
106 for (unsigned int i = 0; i < 6; i++)
107 virtforce[i] = static_cast<float>(force[i]);
108
109 if (virtAddForce(m_virtContext, virtforce)) {
110 int err = virtGetErrorCode(m_virtContext);
111 throw(vpException(vpException::fatalError, "Error calling virtAddForce: error code %d", err));
112 }
113}
114
120{
121 init();
122
123 if (virtEnableForceFeedback(m_virtContext, enable)) {
124 int err = virtGetErrorCode(m_virtContext);
125 throw(vpException(vpException::fatalError, "Error calling virtEnableForceFeedback(): error code %d", err));
126 }
127}
128
133{
134 if (!m_is_init) {
135 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
136 }
137
138 float articular_position_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
139
140 if (virtGetArticularPosition(m_virtContext, articular_position_)) {
141 int err = virtGetErrorCode(m_virtContext);
142 throw(vpException(vpException::fatalError, "Error calling virtGetArticularPosition(): error code %d", err));
143 }
144
145 vpColVector articularPosition(m_njoints, 0);
146 for (unsigned int i = 0; i < m_njoints; i++)
147 articularPosition[i] = articular_position_[i];
148
149 return articularPosition;
150}
151
156{
157 if (!m_is_init) {
158 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
159 }
160
161 float articular_velocity_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
162
163 if (virtGetArticularSpeed(m_virtContext, articular_velocity_)) {
164 int err = virtGetErrorCode(m_virtContext);
165 throw(vpException(vpException::fatalError, "Error calling virtGetArticularSpeed: error code %d", err));
166 }
167
168 vpColVector articularVelocity(m_njoints, 0);
169
170 for (unsigned int i = 0; i < m_njoints; i++)
171 articularVelocity[i] = articular_velocity_[i];
172
173 return articularVelocity;
174}
175
184{
185 if (!m_is_init) {
186 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
187 }
188
189 float position_[7];
190 vpPoseVector position;
191 vpTranslationVector translation;
192 vpQuaternionVector quaternion;
193
194 if (virtGetAvatarPosition(m_virtContext, position_)) {
195 int err = virtGetErrorCode(m_virtContext);
196 throw(vpException(vpException::fatalError, "Error calling virtGetAvatarPosition: error code %d", err));
197 }
198 else {
199 for (int i = 0; i < 3; i++)
200 translation[i] = position_[i];
201 for (int i = 0; i < 4; i++)
202 quaternion[i] = position_[3 + i];
203
204 vpThetaUVector thetau(quaternion);
205
206 position.buildFrom(translation, thetau);
207
208 return position;
209 }
210}
211
219{
220 if (!m_is_init) {
221 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
222 }
223
224 vpPoseVector position;
225 float position_[7];
226 vpTranslationVector translation;
227 vpQuaternionVector quaternion;
228
229 if (virtGetBaseFrame(m_virtContext, position_)) {
230 int err = virtGetErrorCode(m_virtContext);
231 throw(vpException(vpException::fatalError, "Error calling virtGetBaseFrame: error code %d", err));
232 }
233 else {
234 for (int i = 0; i < 3; i++)
235 translation[i] = position_[i];
236 for (int i = 0; i < 4; i++)
237 quaternion[i] = position_[3 + i];
238
239 vpThetaUVector thetau(quaternion);
240
241 position.buildFrom(translation, thetau);
242
243 return position;
244 }
245}
246
250VirtCommandType vpVirtuose::getCommandType() const
251{
252 if (!m_is_init) {
253 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
254 }
255
256 VirtCommandType type;
257
258 if (virtGetCommandType(m_virtContext, &type)) {
259 int err = virtGetErrorCode(m_virtContext);
260 throw(vpException(vpException::fatalError, "Error calling virtGetCommandType: error code %d", err));
261 }
262 return type;
263}
264
270{
271 if (!m_is_init) {
272 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
273 }
274
275 int deadman;
276 if (virtGetDeadMan(m_virtContext, &deadman)) {
277 int err = virtGetErrorCode(m_virtContext);
278 throw(vpException(vpException::fatalError, "Error calling virtGetDeadMan: error code %d", err));
279 }
280 return (deadman ? true : false);
281}
282
289{
290 if (!m_is_init) {
291 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
292 }
293
294 int emergencyStop;
295 if (virtGetEmergencyStop(m_virtContext, &emergencyStop)) {
296 int err = virtGetErrorCode(m_virtContext);
297 throw(vpException(vpException::fatalError, "Error calling virtGetEmergencyStop: error code %d", err));
298 }
299 return (emergencyStop ? true : false);
300}
301
307{
308 if (!m_is_init) {
309 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
310 }
311
312 vpColVector force(6, 0);
313 float force_[6];
314 if (virtGetForce(m_virtContext, force_)) {
315 int err = virtGetErrorCode(m_virtContext);
316 throw(vpException(vpException::fatalError, "Error calling virtGetForce: error code %d", err));
317 }
318
319 for (unsigned int i = 0; i < 6; i++)
320 force[i] = force_[i];
321 return force;
322}
323
360VirtContext vpVirtuose::getHandler() { return m_virtContext; }
361
367unsigned int vpVirtuose::getJointsNumber() const
368{
369 if (!m_is_init) {
370 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
371 }
372
373 return m_njoints;
374}
375
383{
384 if (!m_is_init) {
385 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
386 }
387
388 vpPoseVector position;
389 float position_[7];
390 vpTranslationVector translation;
391 vpQuaternionVector quaternion;
392
393 if (virtGetObservationFrame(m_virtContext, position_)) {
394 int err = virtGetErrorCode(m_virtContext);
395 throw(vpException(vpException::fatalError, "Error calling virtGetObservationFrame: error code %d", err));
396 }
397 else {
398 for (int i = 0; i < 3; i++)
399 translation[i] = position_[i];
400 for (int i = 0; i < 4; i++)
401 quaternion[i] = position_[3 + i];
402
403 vpThetaUVector thetau(quaternion);
404
405 position.buildFrom(translation, thetau);
406 }
407 return position;
408}
409
417{
418 if (!m_is_init) {
419 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
420 }
421
422 vpPoseVector position;
423 float position_[7];
424 vpTranslationVector translation;
425 vpQuaternionVector quaternion;
426
427 if (virtGetPhysicalPosition(m_virtContext, position_)) {
428 int err = virtGetErrorCode(m_virtContext);
429 throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalPosition: error code %d", err));
430 }
431 else {
432 for (int i = 0; i < 3; i++)
433 translation[i] = position_[i];
434 for (int i = 0; i < 4; i++)
435 quaternion[i] = position_[3 + i];
436
437 vpThetaUVector thetau(quaternion);
438
439 position.buildFrom(translation, thetau);
440 }
441 return position;
442}
443
451{
452 if (!m_is_init) {
453 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
454 }
455
456 vpColVector vel(6, 0);
457 float speed[6];
458 if (virtGetPhysicalSpeed(m_virtContext, speed)) {
459 int err = virtGetErrorCode(m_virtContext);
460 throw(vpException(vpException::fatalError, "Error calling virtGetPhysicalSpeed: error code %s",
461 virtGetErrorMessage(err)));
462 }
463 for (unsigned int i = 0; i < 6; i++)
464 vel[i] = speed[i];
465 return vel;
466}
467
474{
475 if (!m_is_init) {
476 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
477 }
478
479 vpPoseVector position;
480 float position_[7];
481 vpTranslationVector translation;
482 vpQuaternionVector quaternion;
483
484 if (virtGetPosition(m_virtContext, position_)) {
485 int err = virtGetErrorCode(m_virtContext);
486 throw(vpException(vpException::fatalError, "Error calling virtGetPosition: error code %d", err));
487 }
488 else {
489 for (int i = 0; i < 3; i++)
490 translation[i] = position_[i];
491 for (int i = 0; i < 4; i++)
492 quaternion[i] = position_[3 + i];
493
494 vpThetaUVector thetau(quaternion);
495
496 position.buildFrom(translation, thetau);
497 }
498 return position;
499}
500
505{
506 if (!m_is_init) {
507 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
508 }
509
510 int power;
511 virtGetPowerOn(m_virtContext, &power);
512 return (power ? true : false);
513}
514
522{
523 if (!m_is_init) {
524 throw(vpException(vpException::fatalError, "Device not initialized. Call init()."));
525 }
526
527 vpColVector vel(6, 0);
528 float speed[6];
529 if (virtGetSpeed(m_virtContext, speed)) {
530 int err = virtGetErrorCode(m_virtContext);
531 throw(vpException(vpException::fatalError, "Cannot get haptic device velocity: %s", virtGetErrorMessage(err)));
532 }
533 for (unsigned int i = 0; i < 6; i++)
534 vel[i] = speed[i];
535 return vel;
536}
537
544{
545 if (!m_is_init) {
546 m_virtContext = virtOpen(m_ip_port.c_str());
547
548 if (m_virtContext == nullptr) {
549 int err = virtGetErrorCode(m_virtContext);
551 "Cannot open communication with haptic device using %s: %s. Check ip and port values",
552 m_ip_port.c_str(), virtGetErrorMessage(err)));
553 }
554
555 if (virtGetControlerVersion(m_virtContext, &m_ctrlMajorVersion, &m_ctrlMinorVersion)) {
556 int err = virtGetErrorCode(m_virtContext);
557 throw(vpException(vpException::fatalError, "Cannot get haptic device controller version: %s",
558 virtGetErrorMessage(err)));
559 }
560
561 if (m_verbose) {
562 std::cout << "Controller version: " << m_ctrlMajorVersion << "." << m_ctrlMinorVersion << std::endl;
563 }
564
565 if (virtSetCommandType(m_virtContext, m_typeCommand)) {
566 int err = virtGetErrorCode(m_virtContext);
567 throw(
568 vpException(vpException::fatalError, "Cannot set haptic device command type: %s", virtGetErrorMessage(err)));
569 }
570
571 if (virtSetTimeStep(m_virtContext, m_period)) {
572 int err = virtGetErrorCode(m_virtContext);
573 throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
574 }
575
576 // Update number of joints
577 float articular_position_[20] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
578
579 if (virtGetArticularPosition(m_virtContext, articular_position_)) {
580 int err = virtGetErrorCode(m_virtContext);
581 throw(vpException(vpException::fatalError, "Error calling virtGetArticularPosition() in int(): error code %d",
582 err));
583 }
584
585 m_njoints = 6; // At least 6 joints
586 for (unsigned int i = m_njoints; i < 20; i++) {
587 m_njoints = i;
588 if (std::fabs(articular_position_[i]) <= std::numeric_limits<float>::epsilon()) {
589 break;
590 }
591 }
592
593 m_is_init = true;
594 }
595}
596
605{
606 init();
607
608 if (articularForce.size() != m_njoints) {
610 "Cannot apply an articular force feedback (dim %d) to "
611 "the haptic device that is not 6-dimension",
612 articularForce.size()));
613 }
614
615 float *articular_force = new float[m_njoints];
616 for (unsigned int i = 0; i < m_njoints; i++)
617 articular_force[i] = static_cast<float>(articularForce[i]);
618
619 if (virtSetArticularForce(m_virtContext, articular_force)) {
620 delete[] articular_force;
621 int err = virtGetErrorCode(m_virtContext);
622 throw(vpException(vpException::fatalError, "Error calling virtSetArticularForce: error code %d", err));
623 }
624
625 delete[] articular_force;
626}
627
635void vpVirtuose::setArticularPosition(const vpColVector &articularPosition)
636{
637 init();
638
639 if (articularPosition.size() != m_njoints) {
641 "Cannot send an articular position command (dim %d) to "
642 "the haptic device that is not %d-dimension",
643 m_njoints, articularPosition.size()));
644 }
645
646 float *articular_position = new float[m_njoints];
647 for (unsigned int i = 0; i < m_njoints; i++)
648 articular_position[i] = static_cast<float>(articularPosition[i]);
649
650 if (virtSetArticularPosition(m_virtContext, articular_position)) {
651 int err = virtGetErrorCode(m_virtContext);
652 delete[] articular_position;
653 throw(vpException(vpException::fatalError, "Error calling virtSetArticularPosition: error code %d", err));
654 }
655 delete[] articular_position;
656}
657
665void vpVirtuose::setArticularVelocity(const vpColVector &articularVelocity)
666{
667 init();
668
669 if (articularVelocity.size() != m_njoints) {
671 "Cannot send an articular velocity command (dim %d) to "
672 "the haptic device that is not %d-dimension",
673 m_njoints, articularVelocity.size()));
674 }
675
676 float *articular_velocity = new float[m_njoints];
677 for (unsigned int i = 0; i < m_njoints; i++)
678 articular_velocity[i] = static_cast<float>(articularVelocity[i]);
679
680 if (virtSetArticularSpeed(m_virtContext, articular_velocity)) {
681 int err = virtGetErrorCode(m_virtContext);
682 delete[] articular_velocity;
683 throw(vpException(vpException::fatalError, "Error calling virtSetArticularVelocity: error code %d", err));
684 }
685 delete[] articular_velocity;
686}
687
696{
697 init();
698
699 float position_[7];
700 vpTranslationVector translation;
701 vpQuaternionVector quaternion;
702
703 position.extract(translation);
704 position.extract(quaternion);
705
706 for (int i = 0; i < 3; i++)
707 position_[i] = static_cast<float>(translation[i]);
708 for (int i = 0; i < 4; i++)
709 position_[3 + i] = static_cast<float>(quaternion[i]);
710
711 if (virtSetBaseFrame(m_virtContext, position_)) {
712 int err = virtGetErrorCode(m_virtContext);
713 throw(vpException(vpException::fatalError, "Error calling virtSetBaseFrame: error code %d", err));
714 }
715}
716
727void vpVirtuose::setCommandType(const VirtCommandType &type)
728{
729 init();
730
731 if (m_typeCommand != type) {
732 m_typeCommand = type;
733
734 if (virtSetCommandType(m_virtContext, m_typeCommand)) {
735 int err = virtGetErrorCode(m_virtContext);
736 throw(vpException(vpException::fatalError, "Error calling virtSetCommandType: error code %d", err));
737 }
738 }
739}
740
748{
749 init();
750
751 if (force.size() != 6) {
753 "Cannot apply a force feedback (dim %d) to the haptic "
754 "device that is not 6-dimension",
755 force.size()));
756 }
757
758 float virtforce[6];
759 for (unsigned int i = 0; i < 6; i++)
760 virtforce[i] = static_cast<float>(force[i]);
761
762 if (virtSetForce(m_virtContext, virtforce)) {
763 int err = virtGetErrorCode(m_virtContext);
764 throw(vpException(vpException::fatalError, "Error calling virtSetForce: error code %d", err));
765 }
766}
767
773void vpVirtuose::setForceFactor(const float &forceFactor)
774{
775 init();
776
777 if (virtSetForceFactor(m_virtContext, forceFactor)) {
778 int err = virtGetErrorCode(m_virtContext);
779 throw(vpException(vpException::fatalError, "Error calling virtSetForceFactor: error code %d", err));
780 }
781}
782
797void vpVirtuose::setIndexingMode(const VirtIndexingType &type)
798{
799 init();
800
801 if (m_indexType != type) {
802 m_indexType = type;
803
804 if (virtSetIndexingMode(m_virtContext, m_indexType)) {
805 int err = virtGetErrorCode(m_virtContext);
806 throw(vpException(vpException::fatalError, "Error calling setIndexingMode: error code %d", err));
807 }
808 }
809}
810
819{
820 init();
821
822 float position_[7];
823 vpTranslationVector translation;
824 vpQuaternionVector quaternion;
825
826 position.extract(translation);
827 position.extract(quaternion);
828
829 for (int i = 0; i < 3; i++)
830 position_[i] = static_cast<float>(translation[i]);
831 for (int i = 0; i < 4; i++)
832 position_[3 + i] = static_cast<float>(quaternion[i]);
833
834 if (virtSetObservationFrame(m_virtContext, position_)) {
835 int err = virtGetErrorCode(m_virtContext);
836 throw(vpException(vpException::fatalError, "Error calling virtSetObservationFrame: error code %d", err));
837 }
838}
839
883void vpVirtuose::setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
884{
885 init();
886
887 if (virtSetPeriodicFunction(m_virtContext, CallBackVirt, &m_period, this)) {
888 int err = virtGetErrorCode(m_virtContext);
889 throw(vpException(vpException::fatalError, "Error calling virtSetPeriodicFunction: error code %d", err));
890 }
891}
892
899{
900 init();
901
902 float position_[7];
903 vpTranslationVector translation;
904 vpQuaternionVector quaternion;
905
906 position.extract(translation);
907 position.extract(quaternion);
908
909 for (int i = 0; i < 3; i++)
910 position_[i] = static_cast<float>(translation[i]);
911 for (int i = 0; i < 4; i++)
912 position_[3 + i] = static_cast<float>(quaternion[i]);
913
914 if (virtSetPosition(m_virtContext, position_)) {
915 int err = virtGetErrorCode(m_virtContext);
916 throw(vpException(vpException::fatalError, "Error calling virtSetPosition: error code %d", err));
917 }
918}
919
924{
925 init();
926
927 if (virtSetPowerOn(m_virtContext, 0)) {
928 int err = virtGetErrorCode(m_virtContext);
929 throw(vpException(vpException::fatalError, "Error calling virtSetPowerOff: error code %d", err));
930 }
931}
932
937{
938 init();
939
940 if (virtSetPowerOn(m_virtContext, 1)) {
941 int err = virtGetErrorCode(m_virtContext);
942 throw(vpException(vpException::fatalError, "Error calling virtSetPowerOn: error code %d", err));
943 }
944}
945
951void vpVirtuose::setSaturation(const float &forceLimit, const float &torqueLimit)
952{
953 init();
954
955 if (virtSaturateTorque(m_virtContext, forceLimit, torqueLimit)) {
956 int err = virtGetErrorCode(m_virtContext);
957 throw(vpException(vpException::fatalError, "Error calling virtSaturateTorque: error code %d", err));
958 }
959}
960
966void vpVirtuose::setTimeStep(const float &timeStep)
967{
968 init();
969
970 if (m_period != timeStep) {
971 m_period = timeStep;
972
973 if (virtSetTimeStep(m_virtContext, m_period)) {
974 int err = virtGetErrorCode(m_virtContext);
975 throw(vpException(vpException::fatalError, "Error calling virtSetTimeStep: error code %d", err));
976 }
977 }
978}
979
986{
987 init();
988
989 if (velocity.size() != 6) {
990 throw(vpException(vpException::dimensionError, "Cannot set a velocity vector (dim %d) that is not 6-dimension",
991 velocity.size()));
992 }
993
994 float speed[6];
995 for (unsigned int i = 0; i < 6; i++)
996 speed[i] = static_cast<float>(velocity[i]);
997
998 if (virtSetSpeed(m_virtContext, speed)) {
999 int err = virtGetErrorCode(m_virtContext);
1000 throw(vpException(vpException::fatalError, "Error calling virtSetSpeed: error code %d", err));
1001 }
1002}
1003
1009void vpVirtuose::setVelocityFactor(const float &velocityFactor)
1010{
1011 init();
1012
1013 if (virtSetSpeedFactor(m_virtContext, velocityFactor)) {
1014 int err = virtGetErrorCode(m_virtContext);
1015 throw(vpException(vpException::fatalError, "Error calling setVelocityFactor: error code %d", err));
1016 }
1017}
1018
1025{
1026 init();
1027
1028 if (virtStartLoop(m_virtContext)) {
1029 int err = virtGetErrorCode(m_virtContext);
1030 throw(vpException(vpException::fatalError, "Error calling startLoop: error code %d", err));
1031 }
1032 else
1033 std::cout << "Haptic loop open." << std::endl;
1034}
1035
1042{
1043 init();
1044
1045 if (virtStopLoop(m_virtContext)) {
1046 int err = virtGetErrorCode(m_virtContext);
1047 throw(vpException(vpException::fatalError, "Error calling stopLoop: error code %d", err));
1048 }
1049 else
1050 std::cout << "Haptic loop closed." << std::endl;
1051}
1052END_VISP_NAMESPACE
1053#else
1054// Work around to avoid warning
1055void dummy_vpVirtuose() { }
1056#endif
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:435
Implementation of column vector and the associated operations.
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.
void extract(vpRotationMatrix &R) const
vpPoseVector & buildFrom(const double &tx, const double &ty, const double &tz, const double &tux, const double &tuy, const double &tuz)
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
vpColVector getVelocity() const
vpColVector getArticularPosition() const
VirtCommandType getCommandType() const
void setIpAddressAndPort(const std::string &ip, int port)
void setPowerOff()
void setTimeStep(const float &timeStep)
void setForceFactor(const float &forceFactor)
void setArticularVelocity(const vpColVector &articularVelocity)
void setObservationFrame(const vpPoseVector &position)
void enableForceFeedback(int enable)
vpPoseVector getPosition() const
bool getPower() const
vpPoseVector getBaseFrame() const
bool m_verbose
Definition vpVirtuose.h:219
VirtContext getHandler()
int m_apiMajorVersion
Definition vpVirtuose.h:220
void setForce(const vpColVector &force)
void setIndexingMode(const VirtIndexingType &type)
unsigned int getJointsNumber() const
void close()
int m_ctrlMinorVersion
Definition vpVirtuose.h:223
vpPoseVector getPhysicalPosition() const
unsigned int m_njoints
Definition vpVirtuose.h:228
float m_period
Definition vpVirtuose.h:227
bool m_is_init
Definition vpVirtuose.h:226
std::string m_ip_port
Definition vpVirtuose.h:218
void setBaseFrame(const vpPoseVector &position)
VirtContext m_virtContext
Definition vpVirtuose.h:217
vpPoseVector getObservationFrame() const
bool getEmergencyStop() const
void setCommandType(const VirtCommandType &type)
void setPeriodicFunction(VirtPeriodicFunction CallBackVirt)
vpColVector getArticularVelocity() const
void stopPeriodicFunction()
int m_ctrlMajorVersion
Definition vpVirtuose.h:222
vpPoseVector getAvatarPosition() const
void setPowerOn()
void addForce(vpColVector &force)
void setArticularForce(const vpColVector &articularForce)
int m_apiMinorVersion
Definition vpVirtuose.h:221
void setPosition(vpPoseVector &position)
void setVelocity(vpColVector &velocity)
VirtCommandType m_typeCommand
Definition vpVirtuose.h:224
void startPeriodicFunction()
void setVelocityFactor(const float &velocityFactor)
void setSaturation(const float &forceLimit, const float &torqueLimit)
virtual ~vpVirtuose()
vpColVector getPhysicalVelocity() const
void setArticularPosition(const vpColVector &articularPosition)
VirtIndexingType m_indexType
Definition vpVirtuose.h:225
vpColVector getForce() const