42 #include <visp3/core/vpConfig.h>
44 #if defined(VISP_HAVE_UR_RTDE)
46 #include <visp3/robot/vpRobotUniversalRobots.h>
48 int main(
int argc,
char **argv)
50 #ifdef ENABLE_VISP_NAMESPACE
53 std::string robot_ip =
"192.168.0.100";
55 for (
int i = 1; i < argc; i++) {
56 if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
57 robot_ip = std::string(argv[i + 1]);
59 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
60 std::cout << argv[0] <<
" [--ip " << robot_ip <<
"] [--help] [-h]"
67 std::cout <<
"-- Start test 1/3" << std::endl;
69 robot.connect(robot_ip);
71 std::shared_ptr<ur_rtde::RTDEReceiveInterface> rtde_receive_interface = robot.getRTDEReceiveInterfaceHandler();
72 std::shared_ptr<ur_rtde::DashboardClient> db_client = robot.getDashboardClientHandler();
74 std::cout <<
"Robot connected : " << (rtde_receive_interface->isConnected() ?
"yes" :
"no") << std::endl;
75 std::cout <<
"Robot mode : " << rtde_receive_interface->getRobotMode() << std::endl;
76 std::cout <<
"Robot model : " << db_client->getRobotModel() << std::endl;
77 std::cout <<
"PolyScope version: " << db_client->polyscopeVersion() << std::endl;
81 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
84 catch (
const std::exception &e) {
85 std::cout <<
"ur_rtde exception: " << e.what() << std::endl;
90 std::cout <<
"-- Start test 2/3" << std::endl;
92 robot.connect(robot_ip);
97 if (robot.getRobotMode() >= 4) {
100 for (
unsigned i = 0; i < 10; i++) {
103 std::cout <<
"Joint position [deg]: " << q.
rad2deg().
t() << std::endl;
109 std::cout <<
"fMe pose vector: " << fPe.
t() << std::endl;
111 std::cout <<
"fMe pose matrix: \n" << fMe_1 << std::endl;
114 for (
size_t i = 0; i < fPe.
size(); i++) {
116 std::cout <<
"Wrong end-effector pose returned by getPosition(). Test failed" << std::endl;
121 std::cout <<
"fMe pose matrix: \n" << fMe_2 << std::endl;
122 for (
size_t i = 0; i < fMe_2.
size(); i++) {
124 std::cout <<
"Wrong end-effector pose returned by get_fMe(). Test failed" << std::endl;
132 if (robot.getRobotMode() == 7) {
134 std::cout <<
"fMe pose matrix: \n" << fMe_3 << std::endl;
135 for (
size_t i = 0; i < fMe_3.
size(); i++) {
137 std::cout <<
"Wrong end-effector forward kinematics . Test failed" << std::endl;
145 std::cout <<
"fMc pose vector: " << fPc.
t() << std::endl;
148 for (
size_t i = 0; i < fPc.
size(); i++) {
150 std::cout <<
"Wrong tool pose. Test failed" << std::endl;
156 std::cout <<
"To proceed with this test you need to power on the robot" << std::endl;
160 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
163 catch (
const std::exception &e) {
164 std::cout <<
"ur_rtde exception: " << e.what() << std::endl;
169 std::cout <<
"-- Start test 3/3" << std::endl;
172 robot.connect(robot_ip);
175 for (
unsigned i = 0; i < 10; i++) {
177 std::cout <<
"End-effector force/torque: " << eFe.
t() << std::endl;
182 for (
unsigned i = 0; i < 10; i++) {
184 std::cout <<
"Camera or tool frame force/torque: " << cFc.
t() << std::endl;
189 std::cout <<
"ViSP exception: " << e.
what() << std::endl;
192 catch (
const std::exception &e) {
193 std::cout <<
"ur_rtde exception: " << e.what() << std::endl;
197 std::cout <<
"The end" << std::endl;
204 std::cout <<
"ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
Type * data
Address of the first element of the data array.
unsigned int size() const
Return the number of elements of the 2D array.
Implementation of column vector and the associated operations.
error that can be emitted by ViSP classes.
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)
Implementation of a pose vector and operations on poses.
VISP_EXPORT int wait(double t0, double t)