41 #include <visp3/core/vpConfig.h>
43 #ifdef VISP_HAVE_JACOSDK
45 #include <visp3/core/vpIoTools.h>
46 #include <visp3/robot/vpRobotException.h>
48 #include <visp3/core/vpHomogeneousMatrix.h>
49 #include <visp3/robot/vpRobotKinova.h>
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()
80 if (dof == 4 || dof == 6 || dof == 7) {
85 "Unsupported Kinova Jaco degrees of freedom: %d. Possible values are 4, 6 or 7.", dof));
132 std::cout <<
"Not implemented ! " << std::endl;
152 std::cout <<
"Not implemented ! " << std::endl;
181 "Cannot send a velocity twist vector in tool frame that is not 6-dim (%d)", v.
size()));
211 TrajectoryPoint pointToSend;
212 pointToSend.InitStruct();
214 pointToSend.Position.Type = CARTESIAN_VELOCITY;
215 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
224 KinovaSetCartesianControl();
226 KinovaSendBasicTrajectory(pointToSend);
244 TrajectoryPoint pointToSend;
245 pointToSend.InitStruct();
247 pointToSend.Position.Type = CARTESIAN_VELOCITY;
248 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
257 KinovaSetCartesianControl();
259 KinovaSendBasicTrajectory(pointToSend);
270 std::cout <<
"rotation matrix from base to endeffector is bRe : " << std::endl;
271 std::cout <<
"bRe:\n" << bRe << std::endl;
279 TrajectoryPoint pointToSend;
280 pointToSend.InitStruct();
282 pointToSend.Position.Type = CARTESIAN_VELOCITY;
283 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
292 KinovaSetCartesianControl();
293 KinovaSendBasicTrajectory(pointToSend);
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",
314 TrajectoryPoint pointToSend;
315 pointToSend.InitStruct();
317 pointToSend.Position.Type = ANGULAR_VELOCITY;
318 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]));
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]));
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]));
350 KinovaSetAngularControl();
352 KinovaSendBasicTrajectory(pointToSend);
382 "Cannot send a velocity to the robot. "
383 "Call setRobotState(vpRobot::STATE_VELOCITY_CONTROL) once before "
384 "entering your control loop.");
396 if (vel.
size() != 6) {
398 "Cannot apply a Cartesian velocity that is not a 6-dim vector (%d)", vel.
size()));
402 for (
unsigned int i = 0; i < 3; i++)
404 for (
unsigned int i = 3; i < 6; i++)
415 if (vel.
size() !=
static_cast<size_t>(
nDof)) {
446 AngularPosition currentCommand;
449 KinovaGetAngularCommand(currentCommand);
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);
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);
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);
525 CartesianPosition currentCommand;
527 KinovaGetCartesianCommand(currentCommand);
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;
537 std::cout <<
"Not implemented ! " << std::endl;
571 for (
unsigned int i = 0; i < 3; i++) {
572 pose[i] = position[i];
573 rxyz[i] = position[i + 3];
576 for (
unsigned int i = 0; i < 3; i++) {
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));
600 TrajectoryPoint pointToSend;
601 pointToSend.InitStruct();
603 pointToSend.Position.Type = ANGULAR_POSITION;
604 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]));
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]));
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]));
636 KinovaSetAngularControl();
639 std::cout <<
"Move robot to joint position [rad rad rad rad rad rad]: " << q.
t() << std::endl;
641 KinovaSendBasicTrajectory(pointToSend);
646 "Cannot move robot to cartesian position of dim %d that is not a 6-dim vector", q.
size()));
648 TrajectoryPoint pointToSend;
649 pointToSend.InitStruct();
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]);
660 KinovaSetCartesianControl();
663 std::cout <<
"Move robot to cartesian position [m m m rad rad rad]: " << q.
t() << std::endl;
665 KinovaSendBasicTrajectory(pointToSend);
670 "Cannot move robot to a cartesian position. Only joint positioning is implemented"));
691 std::cout <<
"Not implemented ! " << std::endl;
716 : std::string(
"Kinova.API.EthCommandLayerUbuntu.so");
719 std::cout <<
"Load plugin: \"" << plugin <<
"\"" << std::endl;
721 m_command_layer_handle = dlopen(plugin.c_str(), RTLD_NOW | RTLD_GLOBAL);
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());
746 : std::string(
"CommandLayerEthernet.dll");
749 std::cout <<
"Load plugin: \"" << plugin <<
"\"" << std::endl;
751 m_command_layer_handle = LoadLibrary(TEXT(plugin.c_str()));
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");
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");
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)) {
777 std::cout <<
"Plugin successfully loaded" << std::endl;
790 std::cout <<
"Close plugin" << std::endl;
793 dlclose(m_command_layer_handle);
795 FreeLibrary(m_command_layer_handle);
814 std::cout <<
"Move the robot to home position" << std::endl;
830 int result = (*KinovaInitAPI)();
833 std::cout <<
"Initialization's result: " << result << std::endl;
879 #elif !defined(VISP_BUILD_SHARED_LIBS)
882 void dummy_vpRobotKinova() { };
unsigned int size() const
Return the number of elements of the 2D array.
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
@ badValue
Used to indicate that a value is not in the allowed range.
@ dimensionError
Bad dimension.
static double rad(double deg)
static double deg(double rad)
Implementation of a matrix and operations on matrices.
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
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
virtual vpRobotStateType getRobotState(void) const
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
static const double maxRotationVelocityDefault
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
static const double maxTranslationVelocityDefault
double getMaxRotationVelocity(void) const
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
double maxTranslationVelocity
double getMaxTranslationVelocity(void) const
double maxRotationVelocity
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.