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