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