#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_UR_RTDE) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
#include <visp3/robot/vpRobotUniversalRobots.h>
int main(int argc, char **argv)
{
std::string robot_ip = "192.168.0.100";
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
robot_ip = std::string(argv[i + 1]);
} else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
std::cout << argv[0] << " [--ip " << robot_ip << "] [--help] [-h]"
<< "\n";
return EXIT_SUCCESS;
}
}
try {
std::cout << "-- Start test 1/3" << std::endl;
std::cout << "Robot connected : " << (rtde_receive_interface->isConnected() ? "yes" : "no") << std::endl;
std::cout << "Robot mode : " << rtde_receive_interface->getRobotMode() << std::endl;
std::cout << "Robot model : " << db_client->getRobotModel() << std::endl;
std::cout << "PolyScope version: " << db_client->polyscopeVersion() << std::endl;
std::cout <<
"ViSP exception: " << e.
what() << std::endl;
return EXIT_FAILURE;
} catch (const std::exception &e) {
std::cout << "ur_rtde exception: " << e.what() << std::endl;
return EXIT_FAILURE;
}
try {
std::cout << "-- Start test 2/3" << std::endl;
for (unsigned i = 0; i < 10; i++) {
q = q_init;
std::cout <<
"Joint position [deg]: " << q.
rad2deg().
t() << std::endl;
}
std::cout <<
"fMe pose vector: " << fPe.
t() << std::endl;
std::cout << "fMe pose matrix: \n" << fMe_1 << std::endl;
for (
size_t i = 0; i < fPe.
size(); i++) {
std::cout << "Wrong end-effector pose returned by getPosition(). Test failed" << std::endl;
return EXIT_FAILURE;
}
}
std::cout << "fMe pose matrix: \n" << fMe_2 << std::endl;
for (
size_t i = 0; i < fMe_2.
size(); i++) {
std::cout << "Wrong end-effector pose returned by get_fMe(). Test failed" << std::endl;
return EXIT_FAILURE;
}
}
std::cout << "fMe pose matrix: \n" << fMe_3 << std::endl;
for (
size_t i = 0; i < fMe_3.
size(); i++) {
std::cout << "Wrong end-effector forward kinematics . Test failed" << std::endl;
return EXIT_FAILURE;
}
}
}
std::cout <<
"fMc pose vector: " << fPc.
t() << std::endl;
for (
size_t i = 0; i < fPc.
size(); i++) {
std::cout << "Wrong tool pose. Test failed" << std::endl;
return EXIT_FAILURE;
}
}
} else {
std::cout << "To proceed with this test you need to power on the robot" << std::endl;
}
std::cout <<
"ViSP exception: " << e.
what() << std::endl;
return EXIT_FAILURE;
} catch (const std::exception &e) {
std::cout << "ur_rtde exception: " << e.what() << std::endl;
return EXIT_FAILURE;
}
try {
std::cout << "-- Start test 3/3" << std::endl;
for (unsigned i = 0; i < 10; i++) {
std::cout <<
"End-effector force/torque: " << eFe.
t() << std::endl;
}
for (unsigned i = 0; i < 10; i++) {
std::cout <<
"Camera or tool frame force/torque: " << cFc.
t() << std::endl;
}
std::cout <<
"ViSP exception: " << e.
what() << std::endl;
return EXIT_FAILURE;
} catch (const std::exception &e) {
std::cout << "ur_rtde exception: " << e.what() << std::endl;
return EXIT_FAILURE;
}
std::cout << "The end" << std::endl;
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_UR_RTDE)
std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
<< std::endl;
#endif
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
#endif
}
#endif