179 "Cannot send a velocity twist vector in tool frame that is not 6-dim (%d)", v.size()));
209 TrajectoryPoint pointToSend;
210 pointToSend.InitStruct();
212 pointToSend.Position.Type = CARTESIAN_VELOCITY;
213 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
222 KinovaSetCartesianControl();
224 KinovaSendBasicTrajectory(pointToSend);
242 TrajectoryPoint pointToSend;
243 pointToSend.InitStruct();
245 pointToSend.Position.Type = CARTESIAN_VELOCITY;
246 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
255 KinovaSetCartesianControl();
257 KinovaSendBasicTrajectory(pointToSend);
268 std::cout <<
"rotation matrix from base to endeffector is bRe : " << std::endl;
269 std::cout <<
"bRe:\n" << bRe << std::endl;
277 TrajectoryPoint pointToSend;
278 pointToSend.InitStruct();
280 pointToSend.Position.Type = CARTESIAN_VELOCITY;
281 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]);
290 KinovaSetCartesianControl();
291 KinovaSendBasicTrajectory(pointToSend);
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",
312 TrajectoryPoint pointToSend;
313 pointToSend.InitStruct();
315 pointToSend.Position.Type = ANGULAR_VELOCITY;
316 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]));
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]));
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]));
348 KinovaSetAngularControl();
350 KinovaSendBasicTrajectory(pointToSend);
444 AngularPosition currentCommand;
447 KinovaGetAngularCommand(currentCommand);
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);
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);
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);
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));
598 TrajectoryPoint pointToSend;
599 pointToSend.InitStruct();
601 pointToSend.Position.Type = ANGULAR_POSITION;
602 pointToSend.Position.HandMode = HAND_NOMOVEMENT;
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]));
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]));
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]));
634 KinovaSetAngularControl();
637 std::cout <<
"Move robot to joint position [rad rad rad rad rad rad]: " << q.
t() << std::endl;
639 KinovaSendBasicTrajectory(pointToSend);
644 "Cannot move robot to cartesian position of dim %d that is not a 6-dim vector", q.
size()));
646 TrajectoryPoint pointToSend;
647 pointToSend.InitStruct();
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]);
658 KinovaSetCartesianControl();
661 std::cout <<
"Move robot to cartesian position [m m m rad rad rad]: " << q.
t() << std::endl;
663 KinovaSendBasicTrajectory(pointToSend);
668 "Cannot move robot to a cartesian position. Only joint positioning is implemented"));
714 : std::string(
"Kinova.API.EthCommandLayerUbuntu.so");
717 std::cout <<
"Load plugin: \"" << plugin <<
"\"" << std::endl;
719 m_command_layer_handle = dlopen(plugin.c_str(), RTLD_NOW | RTLD_GLOBAL);
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());
744 : std::string(
"CommandLayerEthernet.dll");
747 std::cout <<
"Load plugin: \"" << plugin <<
"\"" << std::endl;
749 m_command_layer_handle = LoadLibrary(TEXT(plugin.c_str()));
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");
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");
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)) {
775 std::cout <<
"Plugin successfully loaded" << std::endl;