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>
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)
15 int main(
int argc,
char **argv)
18 std::string opt_robot_ip =
"192.168.0.100";
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;
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);
44 std::cout <<
"Image size: " << width <<
" x " << height << std::endl;
49 xml_camera.
save(cam,
"ur_camera.xml",
"Camera", width, height);
51 #if defined(VISP_HAVE_X11)
53 #elif defined(VISP_HAVE_GDI)
72 std::cout <<
"Connect to robot to get its position..." << std::endl;
73 robot.connect(opt_robot_ip);
77 std::stringstream ss_img, ss_pos;
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;
91 std::cerr <<
"ViSP exception " << e.
what() << std::endl;
92 }
catch (
const std::exception &e) {
93 std::cerr << e.what() << std::endl;
101 #if !defined(VISP_HAVE_REALSENSE2)
102 std::cout <<
"Install librealsense-2.x." << std::endl;
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;
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..."
112 std::cout <<
"After installation of the missing 3rd parties, configure ViSP with cmake"
113 <<
" and build ViSP again." << std::endl;
static bool saveYAML(const std::string &filename, const vpArray2D< Type > &A, const char *header="")
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
Display for windows using GDI (available on any windows 32 platform).
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
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.
const char * what() const
static void write(const vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
unsigned int getWidth() const
unsigned int getHeight() const
Implementation of a pose vector and operations on poses.
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())
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)