Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotKinova.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:
31 * Interface for Kinova Jaco robot.
32 */
33
38
39#include <visp3/core/vpConfig.h>
40
41#ifdef VISP_HAVE_JACOSDK
42
43#include <visp3/core/vpIoTools.h>
44#include <visp3/robot/vpRobotException.h>
45
46#include <visp3/core/vpHomogeneousMatrix.h>
47#include <visp3/robot/vpRobotKinova.h>
48
55 m_devices_list(nullptr), m_active_device(-1), m_command_layer(CMD_LAYER_UNSET), m_command_layer_handle()
56{
57 init();
58}
59
64{
66
67 if (m_devices_list) {
68 delete[] m_devices_list;
69 }
70}
71
76void vpRobotKinova::setDoF(unsigned int dof)
77{
78 if (dof == 4 || dof == 6 || dof == 7) {
79 nDof = dof;
80 }
81 else {
83 "Unsupported Kinova Jaco degrees of freedom: %d. Possible values are 4, 6 or 7.", dof));
84 }
85}
86
91{
92 // If you want to control the robot in Cartesian in a tool frame, set the corresponding transformation in m_eMc
93 // that is set to identity by default in the constructor.
94
97
98 // Set here the robot degrees of freedom number
99 nDof = 6; // Jaco2 default dof = 6
100
101 m_devices_list = new KinovaDevice[MAX_KINOVA_DEVICE];
102}
103
104/*
105
106 At least one of these function has to be implemented to control the robot with a
107 Cartesian velocity:
108 - get_eJe()
109 - get_fJe()
110
111*/
112
121{
122 if (!m_plugin_loaded) {
123 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
124 }
125 if (!m_devices_count) {
126 throw(vpException(vpException::fatalError, "No Kinova robot found"));
127 }
128
129 (void)eJe;
130 std::cout << "Not implemented ! " << std::endl;
131}
132
141{
142 if (!m_plugin_loaded) {
143 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
144 }
145 if (!m_devices_count) {
146 throw(vpException(vpException::fatalError, "No Kinova robot found"));
147 }
148
149 (void)fJe;
150 std::cout << "Not implemented ! " << std::endl;
151}
152
153/*
154
155 At least one of these function has to be implemented to control the robot:
156 - setCartVelocity()
157 - setJointVelocity()
158
159*/
160
176{
177 if (v.size() != 6) {
179 "Cannot send a velocity twist vector in tool frame that is not 6-dim (%d)", v.size()));
180 }
181
182 vpColVector v_e; // This is the velocity that the robot is able to apply in the end-effector frame
183 vpColVector v_c; // This is the velocity that the robot is able to apply in the camera frame
184 vpColVector v_mix; // This is the velocity that the robot is able to apply in the mix frame
185 switch (frame) {
187 // We have to transform the requested velocity in the end-effector frame.
188 // Knowing that the constant transformation between the tool frame and the end-effector frame obtained
189 // by extrinsic calibration is set in m_eMc we can compute the velocity twist matrix eVc that transform
190 // a velocity twist from tool (or camera) frame into end-effector frame
191 vpVelocityTwistMatrix eVc(m_eMc); // GET IT FROM CAMERA EXTRINSIC CALIBRATION FILE
192
193 // Input velocity is expressed in camera or tool frame
194 v_c = v;
195
196 // Transform velocity in end-effector
197 v_e = eVc * v_c;
198
199 // Convert end-effector translation velocity in base frame, rotation velocity is unchanged
200 vpColVector p_e;
202 vpRxyzVector bre(p_e[3], p_e[4], p_e[5]);
203 vpRotationMatrix bRe(bre);
204 vpMatrix bVe(6, 6, 0);
205 bVe.eye();
206 bVe.insert(bRe, 0, 0);
207 v_mix = bVe * v_e;
208
209 TrajectoryPoint pointToSend;
210 pointToSend.InitStruct();
211 // We specify that this point will be used an angular (joint by joint) velocity vector
212 pointToSend.Position.Type = CARTESIAN_VELOCITY;
213 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
214
215 pointToSend.Position.CartesianPosition.X = static_cast<float>(v_mix[0]);
216 pointToSend.Position.CartesianPosition.Y = static_cast<float>(v_mix[1]);
217 pointToSend.Position.CartesianPosition.Z = static_cast<float>(v_mix[2]);
218 pointToSend.Position.CartesianPosition.ThetaX = static_cast<float>(v_mix[3]);
219 pointToSend.Position.CartesianPosition.ThetaY = static_cast<float>(v_mix[4]);
220 pointToSend.Position.CartesianPosition.ThetaZ = static_cast<float>(v_mix[5]);
221
222 KinovaSetCartesianControl(); // Not sure that this function is useful here
223
224 KinovaSendBasicTrajectory(pointToSend);
225 break;
226 }
227
229 // Input velocity is expressed in end-effector
230 v_e = v;
231
232 // Convert end-effector translation velocity in base frame, rotation velocity is unchanged
233 vpColVector p_e;
235 vpRxyzVector bre(p_e[3], p_e[4], p_e[5]);
236 vpRotationMatrix bRe(bre);
237 vpMatrix bVe(6, 6, 0);
238 bVe.eye();
239 bVe.insert(bRe, 0, 0);
240 v_mix = bVe * v_e;
241
242 TrajectoryPoint pointToSend;
243 pointToSend.InitStruct();
244 // We specify that this point will be used an angular (joint by joint) velocity vector
245 pointToSend.Position.Type = CARTESIAN_VELOCITY;
246 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
247
248 pointToSend.Position.CartesianPosition.X = static_cast<float>(v_mix[0]);
249 pointToSend.Position.CartesianPosition.Y = static_cast<float>(v_mix[1]);
250 pointToSend.Position.CartesianPosition.Z = static_cast<float>(v_mix[2]);
251 pointToSend.Position.CartesianPosition.ThetaX = static_cast<float>(v_mix[3]);
252 pointToSend.Position.CartesianPosition.ThetaY = static_cast<float>(v_mix[4]);
253 pointToSend.Position.CartesianPosition.ThetaZ = static_cast<float>(v_mix[5]);
254
255 KinovaSetCartesianControl(); // Not sure that this function is useful here
256
257 KinovaSendBasicTrajectory(pointToSend);
258 break;
259 }
260
261 case vpRobot::MIXT_FRAME: {
262
263 // Convert end-effector translation velocity in base frame, rotation velocity is unchanged
264 vpColVector p_e;
266 vpRxyzVector bre(p_e[3], p_e[4], p_e[5]);
267 vpRotationMatrix bRe(bre);
268 std::cout << "rotation matrix from base to endeffector is bRe : " << std::endl;
269 std::cout << "bRe:\n" << bRe << std::endl;
270 vpMatrix bVe(6, 6, 0);
271 bVe.eye();
272 bVe.insert(bRe, 0, 0);
273 v_e = v;
274 // vpColVector bVe;
275 vpColVector v_mix = bVe * v_e;
276
277 TrajectoryPoint pointToSend;
278 pointToSend.InitStruct();
279 // We specify that this point will be used an angular (joint by joint) velocity vector
280 pointToSend.Position.Type = CARTESIAN_VELOCITY;
281 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
282
283 pointToSend.Position.CartesianPosition.X = static_cast<float>(v_mix[0]);
284 pointToSend.Position.CartesianPosition.Y = static_cast<float>(v_mix[1]);
285 pointToSend.Position.CartesianPosition.Z = static_cast<float>(v_mix[2]);
286 pointToSend.Position.CartesianPosition.ThetaX = static_cast<float>(v_e[3]);
287 pointToSend.Position.CartesianPosition.ThetaY = static_cast<float>(v_e[4]);
288 pointToSend.Position.CartesianPosition.ThetaZ = static_cast<float>(v_e[5]);
289
290 KinovaSetCartesianControl(); // Not sure that this function is useful here
291 KinovaSendBasicTrajectory(pointToSend);
292 break;
293 }
296 // Out of the scope
297 break;
298 }
299}
300
306{
307 if (qdot.size() != static_cast<unsigned int>(nDof)) {
309 "Cannot apply a %d-dim joint velocity vector to the Jaco robot configured with %d DoF",
310 qdot.size(), nDof));
311 }
312 TrajectoryPoint pointToSend;
313 pointToSend.InitStruct();
314 // We specify that this point will be used an angular (joint by joint) velocity vector
315 pointToSend.Position.Type = ANGULAR_VELOCITY;
316 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
317 switch (nDof) {
318 case 7: {
319 pointToSend.Position.Actuators.Actuator7 = static_cast<float>(vpMath::deg(qdot[6]));
320 pointToSend.Position.Actuators.Actuator6 = static_cast<float>(vpMath::deg(qdot[5]));
321 pointToSend.Position.Actuators.Actuator5 = static_cast<float>(vpMath::deg(qdot[4]));
322 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(qdot[3]));
323 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(qdot[2]));
324 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(qdot[1]));
325 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(qdot[0]));
326 break;
327 }
328 case 6: {
329 pointToSend.Position.Actuators.Actuator6 = static_cast<float>(vpMath::deg(qdot[5]));
330 pointToSend.Position.Actuators.Actuator5 = static_cast<float>(vpMath::deg(qdot[4]));
331 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(qdot[3]));
332 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(qdot[2]));
333 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(qdot[1]));
334 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(qdot[0]));
335 break;
336 }
337 case 4: {
338 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(qdot[3]));
339 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(qdot[2]));
340 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(qdot[1]));
341 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(qdot[0]));
342 break;
343 }
344 default:
345 throw(vpException(vpException::fatalError, "Jaco robot non supported %d DoF", nDof));
346 }
347
348 KinovaSetAngularControl(); // Not sure that this function is useful here
349
350 KinovaSendBasicTrajectory(pointToSend);
351}
352
371{
372 if (!m_plugin_loaded) {
373 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
374 }
375 if (!m_devices_count) {
376 throw(vpException(vpException::fatalError, "No Kinova robot found"));
377 }
380 "Cannot send a velocity to the robot. "
381 "Call setRobotState(vpRobot::STATE_VELOCITY_CONTROL) once before "
382 "entering your control loop.");
383 }
384
385 vpColVector vel_sat(6);
386
387 // Velocity saturation
388 switch (frame) {
389 // Saturation in cartesian space
393 case vpRobot::MIXT_FRAME: {
394 if (vel.size() != 6) {
396 "Cannot apply a Cartesian velocity that is not a 6-dim vector (%d)", vel.size()));
397 }
398 vpColVector vel_max(6);
399
400 for (unsigned int i = 0; i < 3; i++)
401 vel_max[i] = getMaxTranslationVelocity();
402 for (unsigned int i = 3; i < 6; i++)
403 vel_max[i] = getMaxRotationVelocity();
404
405 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
406
407 setCartVelocity(frame, vel_sat);
408 break;
409 }
410
411 // Saturation in joint space
413 if (vel.size() != static_cast<size_t>(nDof)) {
414 throw(vpException(vpException::dimensionError, "Cannot apply a joint velocity that is not a %-dim vector (%d)",
415 nDof, vel.size()));
416 }
417 vpColVector vel_max(vel.size());
418
419 // Since the robot has only rotation axis all the joint max velocities are set to getMaxRotationVelocity()
420 vel_max = getMaxRotationVelocity();
421
422 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
423
424 setJointVelocity(vel_sat);
425 }
426 }
427}
428
429/*
430
431 THESE FUNCTIONS ARE NOT MANDATORY BUT ARE USUALLY USEFUL
432
433*/
434
443{
444 AngularPosition currentCommand;
445
446 // We get the actual angular command of the robot. Values are in deg
447 KinovaGetAngularCommand(currentCommand);
448
449 q.resize(nDof);
450 switch (nDof) {
451 case 7: {
452 q[6] = vpMath::rad(currentCommand.Actuators.Actuator7);
453 q[5] = vpMath::rad(currentCommand.Actuators.Actuator6);
454 q[4] = vpMath::rad(currentCommand.Actuators.Actuator5);
455 q[3] = vpMath::rad(currentCommand.Actuators.Actuator4);
456 q[2] = vpMath::rad(currentCommand.Actuators.Actuator3);
457 q[1] = vpMath::rad(currentCommand.Actuators.Actuator2);
458 q[0] = vpMath::rad(currentCommand.Actuators.Actuator1);
459 break;
460 }
461 case 6: {
462 q[5] = vpMath::rad(currentCommand.Actuators.Actuator6);
463 q[4] = vpMath::rad(currentCommand.Actuators.Actuator5);
464 q[3] = vpMath::rad(currentCommand.Actuators.Actuator4);
465 q[2] = vpMath::rad(currentCommand.Actuators.Actuator3);
466 q[1] = vpMath::rad(currentCommand.Actuators.Actuator2);
467 q[0] = vpMath::rad(currentCommand.Actuators.Actuator1);
468 break;
469 }
470 case 4: {
471 q[3] = vpMath::rad(currentCommand.Actuators.Actuator4);
472 q[2] = vpMath::rad(currentCommand.Actuators.Actuator3);
473 q[1] = vpMath::rad(currentCommand.Actuators.Actuator2);
474 q[0] = vpMath::rad(currentCommand.Actuators.Actuator1);
475 break;
476 }
477 default:
478 throw(vpException(vpException::fatalError, "Jaco robot non supported %d DoF", nDof));
479 }
480}
481
511{
512 if (!m_plugin_loaded) {
513 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
514 }
515 if (!m_devices_count) {
516 throw(vpException(vpException::fatalError, "No Kinova robot found"));
517 }
518
519 if (frame == JOINT_STATE) {
520 getJointPosition(position);
521 }
522 else if (frame == END_EFFECTOR_FRAME) {
523 CartesianPosition currentCommand;
524 // We get the actual cartesian position of the robot
525 KinovaGetCartesianCommand(currentCommand);
526 position.resize(6);
527 position[0] = currentCommand.Coordinates.X;
528 position[1] = currentCommand.Coordinates.Y;
529 position[2] = currentCommand.Coordinates.Z;
530 position[3] = currentCommand.Coordinates.ThetaX;
531 position[4] = currentCommand.Coordinates.ThetaY;
532 position[5] = currentCommand.Coordinates.ThetaZ;
533 }
534 else {
535 std::cout << "Not implemented ! " << std::endl;
536 }
537}
538
559{
560 if (frame == JOINT_STATE) {
561 throw(vpException(vpException::fatalError, "Cannot get Jaco joint position as a pose vector"));
562 }
563
564 vpColVector position;
565 getPosition(frame, position);
566
567 vpRxyzVector rxyz; // reference frame to end-effector frame rotations
568 // Update the transformation between reference frame and end-effector frame
569 for (unsigned int i = 0; i < 3; i++) {
570 pose[i] = position[i]; // tx, ty, tz
571 rxyz[i] = position[i + 3]; // ry, ry, rz
572 }
573 vpThetaUVector tu(rxyz);
574 for (unsigned int i = 0; i < 3; i++) {
575 pose[i + 3] = tu[i]; // tux, tuy, tuz
576 }
577}
578
586{
587 if (!m_plugin_loaded) {
588 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
589 }
590 if (!m_devices_count) {
591 throw(vpException(vpException::fatalError, "No Kinova robot found"));
592 }
593 if (frame == vpRobot::JOINT_STATE) {
594 if (static_cast<int>(q.size()) != nDof) {
596 "Cannot move robot to a joint position of dim %u that is not a %d-dim vector", q.size(), nDof));
597 }
598 TrajectoryPoint pointToSend;
599 pointToSend.InitStruct();
600 // We specify that this point will be an angular(joint by joint) position.
601 pointToSend.Position.Type = ANGULAR_POSITION;
602 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
603 switch (nDof) {
604 case 7: {
605 pointToSend.Position.Actuators.Actuator7 = static_cast<float>(vpMath::deg(q[6]));
606 pointToSend.Position.Actuators.Actuator6 = static_cast<float>(vpMath::deg(q[5]));
607 pointToSend.Position.Actuators.Actuator5 = static_cast<float>(vpMath::deg(q[4]));
608 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(q[3]));
609 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(q[2]));
610 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(q[1]));
611 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(q[0]));
612 break;
613 }
614 case 6: {
615 pointToSend.Position.Actuators.Actuator6 = static_cast<float>(vpMath::deg(q[5]));
616 pointToSend.Position.Actuators.Actuator5 = static_cast<float>(vpMath::deg(q[4]));
617 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(q[3]));
618 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(q[2]));
619 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(q[1]));
620 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(q[0]));
621 break;
622 }
623 case 4: {
624 pointToSend.Position.Actuators.Actuator4 = static_cast<float>(vpMath::deg(q[3]));
625 pointToSend.Position.Actuators.Actuator3 = static_cast<float>(vpMath::deg(q[2]));
626 pointToSend.Position.Actuators.Actuator2 = static_cast<float>(vpMath::deg(q[1]));
627 pointToSend.Position.Actuators.Actuator1 = static_cast<float>(vpMath::deg(q[0]));
628 break;
629 }
630 default:
631 throw(vpException(vpException::fatalError, "Jaco robot non supported %d DoF", nDof));
632 }
633
634 KinovaSetAngularControl(); // Not sure that this function is useful here
635
636 if (m_verbose) {
637 std::cout << "Move robot to joint position [rad rad rad rad rad rad]: " << q.t() << std::endl;
638 }
639 KinovaSendBasicTrajectory(pointToSend);
640 }
641 else if (frame == vpRobot::END_EFFECTOR_FRAME) {
642 if (q.size() != 6) {
644 "Cannot move robot to cartesian position of dim %d that is not a 6-dim vector", q.size()));
645 }
646 TrajectoryPoint pointToSend;
647 pointToSend.InitStruct();
648 // We specify that this point will be an angular(joint by joint) position.
649 pointToSend.Position.Type = CARTESIAN_POSITION;
650 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
651 pointToSend.Position.CartesianPosition.X = static_cast<float>(q[0]);
652 pointToSend.Position.CartesianPosition.Y = static_cast<float>(q[1]);
653 pointToSend.Position.CartesianPosition.Z = static_cast<float>(q[2]);
654 pointToSend.Position.CartesianPosition.ThetaX = static_cast<float>(q[3]);
655 pointToSend.Position.CartesianPosition.ThetaY = static_cast<float>(q[4]);
656 pointToSend.Position.CartesianPosition.ThetaZ = static_cast<float>(q[5]);
657
658 KinovaSetCartesianControl(); // Not sure that this function is useful here
659
660 if (m_verbose) {
661 std::cout << "Move robot to cartesian position [m m m rad rad rad]: " << q.t() << std::endl;
662 }
663 KinovaSendBasicTrajectory(pointToSend);
664
665 }
666 else {
668 "Cannot move robot to a cartesian position. Only joint positioning is implemented"));
669 }
670}
671
679{
680 if (!m_plugin_loaded) {
681 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
682 }
683 if (!m_devices_count) {
684 throw(vpException(vpException::fatalError, "No Kinova robot found"));
685 }
686
687 (void)frame;
688 (void)q;
689 std::cout << "Not implemented ! " << std::endl;
690}
691
704{
706 throw(vpException(vpException::fatalError, "Kinova robot command layer unset"));
707 }
708 if (m_plugin_loaded) {
709 closePlugin();
710 }
711#ifdef __linux__
712 // We load the API
713 std::string plugin_name = (m_command_layer == CMD_LAYER_USB) ? std::string("Kinova.API.USBCommandLayerUbuntu.so")
714 : std::string("Kinova.API.EthCommandLayerUbuntu.so");
715 std::string plugin = vpIoTools::createFilePath(m_plugin_location, plugin_name);
716 if (m_verbose) {
717 std::cout << "Load plugin: \"" << plugin << "\"" << std::endl;
718 }
719 m_command_layer_handle = dlopen(plugin.c_str(), RTLD_NOW | RTLD_GLOBAL);
720
721 std::string prefix = (m_command_layer == CMD_LAYER_USB) ? std::string("") : std::string("Ethernet_");
722 // We load the functions from the library
723 KinovaCloseAPI = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("CloseAPI")).c_str());
724 KinovaGetAngularCommand =
725 (int (*)(AngularPosition &))dlsym(m_command_layer_handle, (prefix + std::string("GetAngularCommand")).c_str());
726 KinovaGetCartesianCommand = (int (*)(CartesianPosition &))dlsym(
727 m_command_layer_handle, (prefix + std::string("GetCartesianCommand")).c_str());
728 KinovaGetDevices = (int (*)(KinovaDevice devices[MAX_KINOVA_DEVICE], int &result))dlsym(
729 m_command_layer_handle, (prefix + std::string("GetDevices")).c_str());
730 KinovaInitAPI = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("InitAPI")).c_str());
731 KinovaInitFingers = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("InitFingers")).c_str());
732 KinovaMoveHome = (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("MoveHome")).c_str());
733 KinovaSendBasicTrajectory =
734 (int (*)(TrajectoryPoint))dlsym(m_command_layer_handle, (prefix + std::string("SendBasicTrajectory")).c_str());
735 KinovaSetActiveDevice =
736 (int (*)(KinovaDevice devices))dlsym(m_command_layer_handle, (prefix + std::string("SetActiveDevice")).c_str());
737 KinovaSetAngularControl =
738 (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetAngularControl")).c_str());
739 KinovaSetCartesianControl =
740 (int (*)())dlsym(m_command_layer_handle, (prefix + std::string("SetCartesianControl")).c_str());
741#elif _WIN32
742 // We load the API.
743 std::string plugin_name = (m_command_layer == CMD_LAYER_USB) ? std::string("CommandLayerWindows.dll")
744 : std::string("CommandLayerEthernet.dll");
745 std::string plugin = vpIoTools::createFilePath(m_plugin_location, plugin_name);
746 if (m_verbose) {
747 std::cout << "Load plugin: \"" << plugin << "\"" << std::endl;
748 }
749 m_command_layer_handle = LoadLibrary(TEXT(plugin.c_str()));
750
751 // We load the functions from the library
752 KinovaCloseAPI = (int (*)())GetProcAddress(m_command_layer_handle, "CloseAPI");
753 KinovaGetAngularCommand = (int (*)(AngularPosition &))GetProcAddress(m_command_layer_handle, "GetAngularCommand");
754 KinovaGetCartesianCommand =
755 (int (*)(CartesianPosition &))GetProcAddress(m_command_layer_handle, "GetCartesianCommand");
756 KinovaGetDevices =
757 (int (*)(KinovaDevice[MAX_KINOVA_DEVICE], int &))GetProcAddress(m_command_layer_handle, "GetDevices");
758 KinovaInitAPI = (int (*)())GetProcAddress(m_command_layer_handle, "InitAPI");
759 KinovaInitFingers = (int (*)())GetProcAddress(m_command_layer_handle, "InitFingers");
760 KinovaMoveHome = (int (*)())GetProcAddress(m_command_layer_handle, "MoveHome");
761 KinovaSendBasicTrajectory = (int (*)(TrajectoryPoint))GetProcAddress(m_command_layer_handle, "SendBasicTrajectory");
762 KinovaSetActiveDevice = (int (*)(KinovaDevice))GetProcAddress(m_command_layer_handle, "SetActiveDevice");
763 KinovaSetAngularControl = (int (*)())GetProcAddress(m_command_layer_handle, "SetAngularControl");
764 KinovaSetCartesianControl = (int (*)())GetProcAddress(m_command_layer_handle, "SetCartesianControl");
765#endif
766
767 // Verify that all functions has been loaded correctly
768 if ((KinovaCloseAPI == nullptr) || (KinovaGetAngularCommand == nullptr) || (KinovaGetAngularCommand == nullptr) ||
769 (KinovaGetCartesianCommand == nullptr) || (KinovaGetDevices == nullptr) || (KinovaInitAPI == nullptr) ||
770 (KinovaInitFingers == nullptr) || (KinovaMoveHome == nullptr) || (KinovaSendBasicTrajectory == nullptr) ||
771 (KinovaSetActiveDevice == nullptr) || (KinovaSetAngularControl == nullptr) || (KinovaSetCartesianControl == nullptr)) {
772 throw(vpException(vpException::fatalError, "Cannot load plugin from \"%s\" folder", m_plugin_location.c_str()));
773 }
774 if (m_verbose) {
775 std::cout << "Plugin successfully loaded" << std::endl;
776 }
777
778 m_plugin_loaded = true;
779}
780
785{
786 if (m_plugin_loaded) {
787 if (m_verbose) {
788 std::cout << "Close plugin" << std::endl;
789 }
790#ifdef __linux__
791 dlclose(m_command_layer_handle);
792#elif _WIN32
793 FreeLibrary(m_command_layer_handle);
794#endif
795 m_plugin_loaded = false;
796 }
797}
798
803{
804 if (!m_plugin_loaded) {
805 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
806 }
807 if (!m_devices_count) {
808 throw(vpException(vpException::fatalError, "No Kinova robot found"));
809 }
810
811 if (m_verbose) {
812 std::cout << "Move the robot to home position" << std::endl;
813 }
814 KinovaMoveHome();
815}
816
822{
823 loadPlugin();
824 if (!m_plugin_loaded) {
825 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
826 }
827
828 int result = (*KinovaInitAPI)();
829
830 if (m_verbose) {
831 std::cout << "Initialization's result: " << result << std::endl;
832 }
833
834 m_devices_count = KinovaGetDevices(m_devices_list, result);
835
836 if (m_verbose) {
837 std::cout << "Found " << m_devices_count << " devices" << std::endl;
838 }
839
840 // By default set the first device as active
842
843 // Initialize fingers
844 KinovaInitFingers();
845
846 return m_devices_count;
847}
848
860{
861 if (!m_plugin_loaded) {
862 throw(vpException(vpException::fatalError, "Jaco SDK plugin not loaded"));
863 }
864 if (!m_devices_count) {
865 throw(vpException(vpException::fatalError, "No Kinova robot found"));
866 }
867 if (device < 0 || device >= m_devices_count) {
868 throw(vpException(vpException::badValue, "Cannot set Kinova active device %d. Value should be in range [0, %d]",
869 device, m_devices_count - 1));
870 }
871 if (device != m_active_device) {
872 m_active_device = device;
873 KinovaSetActiveDevice(m_devices_list[m_active_device]);
874 }
875}
876END_VISP_NAMESPACE
877#elif !defined(VISP_BUILD_SHARED_LIBS)
878// Work around to avoid warning: libvisp_robot.a(vpRobotKinova.cpp.o) has
879// no symbols
880void dummy_vpRobotKinova() { }
881#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.
vpRowVector t() const
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
Definition vpException.h:60
@ badValue
Used to indicate that a value is not in the allowed range.
Definition vpException.h:73
@ dimensionError
Bad dimension.
Definition vpException.h:71
@ fatalError
Fatal error.
Definition vpException.h:72
static std::string createFilePath(const std::string &parent, const std::string &child)
static double rad(double deg)
Definition vpMath.h:129
static double deg(double rad)
Definition vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
void insert(const vpMatrix &A, unsigned int r, unsigned int c)
Implementation of a pose vector and operations on poses.
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
KinovaDevice * m_devices_list
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setDoF(unsigned int dof)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
std::string m_plugin_location
vpHomogeneousMatrix m_eMc
Constant transformation between end-effector and tool (or camera) frame.
CommandLayer m_command_layer
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void setJointVelocity(const vpColVector &qdot)
void getJointPosition(vpColVector &q)
virtual ~vpRobotKinova() VP_OVERRIDE
void setCartVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &v)
void setActiveDevice(int device)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
int nDof
number of degrees of freedom
Definition vpRobot.h:101
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition vpRobot.h:103
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:162
vpControlFrameType
Definition vpRobot.h:74
@ REFERENCE_FRAME
Definition vpRobot.h:75
@ JOINT_STATE
Definition vpRobot.h:79
@ TOOL_FRAME
Definition vpRobot.h:83
@ MIXT_FRAME
Definition vpRobot.h:85
@ CAMERA_FRAME
Definition vpRobot.h:81
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
static const double maxRotationVelocityDefault
Definition vpRobot.h:98
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
static const double maxTranslationVelocityDefault
Definition vpRobot.h:96
double getMaxRotationVelocity(void) const
Definition vpRobot.cpp:272
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition vpRobot.h:107
double maxTranslationVelocity
Definition vpRobot.h:95
double getMaxTranslationVelocity(void) const
Definition vpRobot.cpp:250
double maxRotationVelocity
Definition vpRobot.h:97
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
Implementation of a rotation vector as axis-angle minimal representation.