Visual Servoing Platform  version 3.6.1 under development (2023-10-04)
tutorial-universal-robots-acquire-calib-data.cpp
1 #include <iostream>
3 
4 #include <visp3/core/vpCameraParameters.h>
5 #include <visp3/core/vpXmlParserCamera.h>
6 #include <visp3/gui/vpDisplayGDI.h>
7 #include <visp3/gui/vpDisplayX.h>
8 #include <visp3/io/vpImageIo.h>
9 #include <visp3/robot/vpRobotUniversalRobots.h>
10 #include <visp3/sensor/vpRealSense2.h>
11 
12 #if defined(VISP_HAVE_REALSENSE2) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) && \
13  (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_UR_RTDE)
14 
15 int main(int argc, char **argv)
16 {
17  try {
18  std::string opt_robot_ip = "192.168.0.100";
19 
20  for (int i = 1; i < argc; i++) {
21  if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
22  opt_robot_ip = std::string(argv[i + 1]);
23  } else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
24  std::cout << argv[0] << " [--ip " << opt_robot_ip << "] [--help] [-h]" << std::endl;
25  return EXIT_SUCCESS;
26  }
27  }
28 
30 
32 
33  vpRealSense2 g;
34  rs2::config config;
35  config.disable_stream(RS2_STREAM_DEPTH);
36  config.disable_stream(RS2_STREAM_INFRARED);
37  config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
38  g.open(config);
39  g.acquire(I);
40 
41  unsigned int width = I.getWidth();
42  unsigned int height = I.getHeight();
43 
44  std::cout << "Image size: " << width << " x " << height << std::endl;
45  // Save intrinsics
47  vpXmlParserCamera xml_camera;
49  xml_camera.save(cam, "ur_camera.xml", "Camera", width, height);
50 
51 #if defined(VISP_HAVE_X11)
52  vpDisplayX dc(I, 10, 10, "Color image");
53 #elif defined(VISP_HAVE_GDI)
54  vpDisplayGDI dc(I, 10, 10, "Color image");
55 #endif
56 
57  bool end = false;
58  unsigned cpt = 0;
59  while (!end) {
60  g.acquire(I);
61 
63 
64  vpDisplay::displayText(I, 15, 15, "Left click to acquire data", vpColor::red);
65  vpDisplay::displayText(I, 30, 15, "Right click to quit", vpColor::red);
67  if (vpDisplay::getClick(I, button, false)) {
68  if (button == vpMouseButton::button1) {
69  cpt++;
70 
71  vpPoseVector fPe;
72  std::cout << "Connect to robot to get its position..." << std::endl;
73  robot.connect(opt_robot_ip);
74  robot.getPosition(vpRobot::END_EFFECTOR_FRAME, fPe);
75  robot.disconnect();
76 
77  std::stringstream ss_img, ss_pos;
78 
79  ss_img << "ur_image-" << cpt << ".png";
80  ss_pos << "ur_pose_fPe_" << cpt << ".yaml";
81  std::cout << "Save: " << ss_img.str() << " and " << ss_pos.str() << std::endl;
82  vpImageIo::write(I, ss_img.str());
83  fPe.saveYAML(ss_pos.str(), fPe);
84  } else if (button == vpMouseButton::button3) {
85  end = true;
86  }
87  }
89  }
90  } catch (const vpException &e) {
91  std::cerr << "ViSP exception " << e.what() << std::endl;
92  } catch (const std::exception &e) {
93  std::cerr << e.what() << std::endl;
94  }
95 
96  return EXIT_SUCCESS;
97 }
98 #else
99 int main()
100 {
101 #if !defined(VISP_HAVE_REALSENSE2)
102  std::cout << "Install librealsense-2.x." << std::endl;
103 #endif
104 #if !(VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
105  std::cout << "Build ViSP with c++11 or higher compiler flag (cmake -DUSE_CXX_STANDARD=11)." << std::endl;
106 #endif
107 #if !defined(VISP_HAVE_UR_RTDE)
108  std::cout << "ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
109  << std::endl;
110 #endif
111 
112  std::cout << "After installation of the missing 3rd parties, configure ViSP with cmake"
113  << " and build ViSP again." << std::endl;
114  return EXIT_SUCCESS;
115 }
116 #endif
static bool saveYAML(const std::string &filename, const vpArray2D< Type > &A, const char *header="")
Definition: vpArray2D.h:877
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
static const vpColor red
Definition: vpColor.h:211
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:128
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:132
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition: vpException.h:59
const char * what() const
Definition: vpException.cpp:70
static void write(const vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:287
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:184
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:192
void acquire(vpImage< unsigned char > &grey, double *ts=NULL)
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
bool open(const rs2::config &cfg=rs2::config())
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:79
XML parser to load and save intrinsic camera parameters.
int save(const vpCameraParameters &cam, const std::string &filename, const std::string &camera_name, unsigned int image_width=0, unsigned int image_height=0, const std::string &additionalInfo="", bool verbose=true)