Visual Servoing Platform version 3.6.0
Loading...
Searching...
No Matches
testUniversalRobotsGetData.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 * Test Universal Robots behavior
33 *
34*****************************************************************************/
35
42#include <iostream>
43
44#include <visp3/core/vpConfig.h>
45
46#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
47
48#include <visp3/robot/vpRobotUniversalRobots.h>
49
50int main(int argc, char **argv)
51{
52 std::string robot_ip = "192.168.0.100";
53
54 for (int i = 1; i < argc; i++) {
55 if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
56 robot_ip = std::string(argv[i + 1]);
57 } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
58 std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]"
59 << "\n";
60 return EXIT_SUCCESS;
61 }
62 }
63
64 try {
65 std::cout << "-- Start test 1/3" << std::endl;
67 robot.connect(robot_ip);
68
69 std::shared_ptr<ur_rtde::RTDEReceiveInterface> rtde_receive_interface = robot.getRTDEReceiveInterfaceHandler();
70 std::shared_ptr<ur_rtde::DashboardClient> db_client = robot.getDashboardClientHandler();
71
72 std::cout << "Robot connected : " << (rtde_receive_interface->isConnected() ? "yes" : "no") << std::endl;
73 std::cout << "Robot mode : " << rtde_receive_interface->getRobotMode() << std::endl;
74 std::cout << "Robot model : " << db_client->getRobotModel() << std::endl;
75 std::cout << "PolyScope version: " << db_client->polyscopeVersion() << std::endl;
76 robot.disconnect();
77 } catch (const vpException &e) {
78 std::cout << "ViSP exception: " << e.what() << std::endl;
79 return EXIT_FAILURE;
80 } catch (const std::exception &e) {
81 std::cout << "ur_rtde exception: " << e.what() << std::endl;
82 return EXIT_FAILURE;
83 }
84
85 try {
86 std::cout << "-- Start test 2/3" << std::endl;
88 robot.connect(robot_ip);
89
90 // Next test is only done when robot powered on
91 // See robot mode doc:
92 // https://sdurobotics.gitlab.io/ur_rtde/api/api.html#_CPPv4N7ur_rtde20RTDEReceiveInterface12getRobotModeEv
93 if (robot.getRobotMode() >= 4) {
94 vpColVector q, q_init;
95
96 for (unsigned i = 0; i < 10; i++) {
97 robot.getPosition(vpRobot::JOINT_STATE, q_init);
98 q = q_init;
99 std::cout << "Joint position [deg]: " << q.rad2deg().t() << std::endl;
100 vpTime::wait(10);
101 }
102
103 vpPoseVector fPe;
104 robot.getPosition(vpRobot::END_EFFECTOR_FRAME, fPe);
105 std::cout << "fMe pose vector: " << fPe.t() << std::endl;
106 vpHomogeneousMatrix fMe_1(fPe);
107 std::cout << "fMe pose matrix: \n" << fMe_1 << std::endl;
108 vpColVector position;
109 robot.getPosition(vpRobot::END_EFFECTOR_FRAME, position);
110 for (size_t i = 0; i < fPe.size(); i++) {
111 if (!vpMath::equal(fPe[i], position[i])) {
112 std::cout << "Wrong end-effector pose returned by getPosition(). Test failed" << std::endl;
113 return EXIT_FAILURE;
114 }
115 }
116 vpHomogeneousMatrix fMe_2 = robot.get_fMe();
117 std::cout << "fMe pose matrix: \n" << fMe_2 << std::endl;
118 for (size_t i = 0; i < fMe_2.size(); i++) {
119 if (!vpMath::equal(fMe_1.data[i], fMe_2.data[i])) {
120 std::cout << "Wrong end-effector pose returned by get_fMe(). Test failed" << std::endl;
121 return EXIT_FAILURE;
122 }
123 }
124
125 // Next test is only done when brakes are released
126 // See robot mode doc:
127 // https://sdurobotics.gitlab.io/ur_rtde/api/api.html#_CPPv4N7ur_rtde20RTDEReceiveInterface12getRobotModeEv
128 if (robot.getRobotMode() == 7) {
129 vpHomogeneousMatrix fMe_3 = robot.get_fMe(q_init);
130 std::cout << "fMe pose matrix: \n" << fMe_3 << std::endl;
131 for (size_t i = 0; i < fMe_3.size(); i++) {
132 if (!vpMath::equal(fMe_2.data[i], fMe_3.data[i])) {
133 std::cout << "Wrong end-effector forward kinematics . Test failed" << std::endl;
134 return EXIT_FAILURE;
135 }
136 }
137 }
138
139 vpPoseVector fPc;
140 robot.getPosition(vpRobot::TOOL_FRAME, fPc);
141 std::cout << "fMc pose vector: " << fPc.t() << std::endl;
142 std::cout << "fMc pose matrix: \n" << vpHomogeneousMatrix(fPc) << std::endl;
143 robot.getPosition(vpRobot::TOOL_FRAME, position);
144 for (size_t i = 0; i < fPc.size(); i++) {
145 if (!vpMath::equal(fPc[i], position[i])) {
146 std::cout << "Wrong tool pose. Test failed" << std::endl;
147 return EXIT_FAILURE;
148 }
149 }
150 } else {
151 std::cout << "To proceed with this test you need to power on the robot" << std::endl;
152 }
153 } catch (const vpException &e) {
154 std::cout << "ViSP exception: " << e.what() << std::endl;
155 return EXIT_FAILURE;
156 } catch (const std::exception &e) {
157 std::cout << "ur_rtde exception: " << e.what() << std::endl;
158 return EXIT_FAILURE;
159 }
160
161 try {
162 std::cout << "-- Start test 3/3" << std::endl;
163 vpRobotUniversalRobots robot(robot_ip);
164 robot.disconnect();
165 robot.connect(robot_ip);
166
167 vpColVector eFe;
168 for (unsigned i = 0; i < 10; i++) {
169 robot.getForceTorque(vpRobot::END_EFFECTOR_FRAME, eFe);
170 std::cout << "End-effector force/torque: " << eFe.t() << std::endl;
171 vpTime::wait(10);
172 }
173
174 vpColVector cFc;
175 for (unsigned i = 0; i < 10; i++) {
176 robot.getForceTorque(vpRobot::TOOL_FRAME, cFc);
177 std::cout << "Camera or tool frame force/torque: " << cFc.t() << std::endl;
178 vpTime::wait(10);
179 }
180 } catch (const vpException &e) {
181 std::cout << "ViSP exception: " << e.what() << std::endl;
182 return EXIT_FAILURE;
183 } catch (const std::exception &e) {
184 std::cout << "ur_rtde exception: " << e.what() << std::endl;
185 return EXIT_FAILURE;
186 }
187
188 std::cout << "The end" << std::endl;
189 return EXIT_SUCCESS;
190}
191
192#else
193int main()
194{
195#if !defined(VISP_HAVE_UR_RTDE)
196 std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
197 << std::endl;
198#endif
199#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
200 std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
201#endif
202}
203#endif
Type * data
Address of the first element of the data array.
Definition vpArray2D.h:144
unsigned int size() const
Return the number of elements of the 2D array.
Definition vpArray2D.h:292
Implementation of column vector and the associated operations.
vpColVector & rad2deg()
vpRowVector t() const
error that can be emitted by ViSP classes.
Definition vpException.h:59
const char * what() const
Implementation of an homogeneous matrix and operations on such kind of matrices.
static bool equal(double x, double y, double threshold=0.001)
Definition vpMath.h:369
Implementation of a pose vector and operations on poses.
vpRowVector t() const
@ JOINT_STATE
Definition vpRobot.h:78
@ TOOL_FRAME
Definition vpRobot.h:82
@ END_EFFECTOR_FRAME
Definition vpRobot.h:79
VISP_EXPORT int wait(double t0, double t)