37#include <visp3/core/vpConfig.h>
38#include <visp3/core/vpCameraParameters.h>
39#include <visp3/core/vpIoTools.h>
40#include <visp3/core/vpXmlParserCamera.h>
41#include <visp3/gui/vpDisplayFactory.h>
42#include <visp3/io/vpImageIo.h>
43#include <visp3/robot/vpRobotUniversalRobots.h>
44#include <visp3/sensor/vpRealSense2.h>
46#if defined(VISP_HAVE_REALSENSE2) && \
47 defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_UR_RTDE) && defined(VISP_HAVE_PUGIXML) && \
48 defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_MODULE_ROBOT) && defined(VISP_HAVE_MODULE_SENSOR)
50void usage(
const char **argv,
int error,
const std::string &robot_ip)
52 std::cout <<
"Synopsis" << std::endl
54 <<
" [--ip <address>] [--output-folder <name>] [--help, -h]" << std::endl
56 std::cout <<
"Description" << std::endl
57 <<
" --ip <address>" << std::endl
58 <<
" Ethernet address to dial with the Panda robot." << std::endl
59 <<
" Default: " << robot_ip << std::endl
61 <<
" --output-folder <name>" << std::endl
62 <<
" Acquired data output folder." << std::endl
63 <<
" Default: ./" << std::endl
65 <<
" --help, -h Print this helper message." << std::endl
68 std::cout <<
"Error" << std::endl
70 <<
"Unsupported parameter " << argv[
error] << std::endl;
74int main(
int argc,
const char **argv)
76#if defined(ENABLE_VISP_NAMESPACE)
79#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
83 std::string opt_robot_ip =
"192.168.0.100";
84 std::string opt_output_folder =
"./";
86 for (
int i = 1;
i < argc;
i++) {
87 if (std::string(argv[i]) ==
"--ip" && i + 1 < argc) {
88 opt_robot_ip = std::string(argv[++i]);
90 else if (std::string(argv[i]) ==
"--output-folder" && i + 1 < argc) {
91 opt_output_folder = std::string(argv[++i]);
93 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
94 usage(argv, 0, opt_robot_ip);
98 usage(argv, i, opt_robot_ip);
105 std::cout <<
"Create output directory: " << opt_output_folder << std::endl;
115 config.disable_stream(RS2_STREAM_DEPTH);
116 config.disable_stream(RS2_STREAM_INFRARED);
117 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
121 unsigned int width = I.getWidth();
122 unsigned int height = I.getHeight();
124 std::cout <<
"Image size: " <<
width <<
" x " <<
height << std::endl;
129 xml_camera.
save(cam, opt_output_folder +
"/ur_camera.xml",
"Camera", width, height);
131#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
152 std::cout <<
"Connect to robot to get its position..." << std::endl;
153 robot.connect(opt_robot_ip);
157 std::stringstream ss_img, ss_pos;
159 ss_img << opt_output_folder +
"/ur_image-" << cpt <<
".png";
160 ss_pos << opt_output_folder +
"/ur_pose_rPe_" << cpt <<
".yaml";
161 std::cout <<
"Save: " << ss_img.str() <<
" and " << ss_pos.str() << std::endl;
173 std::cerr <<
"ViSP exception " <<
e.what() << std::endl;
175 catch (
const std::exception &e) {
176 std::cerr <<
e.what() << std::endl;
178#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
179 if (pdisp !=
nullptr) {
188#if !defined(VISP_HAVE_MODULE_GUI)
189 std::cout <<
"visp_gui module is not available?" << std::endl;
191#if !defined(VISP_HAVE_MODULE_ROBOT)
192 std::cout <<
"visp_robot module is not available?" << std::endl;
194#if !defined(VISP_HAVE_MODULE_SENSOR)
195 std::cout <<
"visp_sensor module is not available?" << std::endl;
197#if !defined(VISP_HAVE_REALSENSE2)
198 std::cout <<
"Install librealsense-2.x." << std::endl;
200#if !defined(VISP_HAVE_UR_RTDE)
201 std::cout <<
"ViSP is not build with libur_rtde 3rd party used to control a robot from Universal Robots..."
204#if !defined(VISP_HAVE_PUGIXML)
205 std::cout <<
"Enable pugyxml built-in usage." << std::endl;
208 std::cout <<
"After installation of the missing 3rd parties, configure ViSP with cmake"
209 <<
" 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.
Class that defines generic functionalities for display.
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.
static void write(const vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition of the vpImage class member functions.
Implementation of a pose vector and operations on poses.
vpCameraParameters getCameraParameters(const rs2_stream &stream, vpCameraParameters::vpCameraParametersProjType type=vpCameraParameters::perspectiveProjWithDistortion, int index=-1) const
void acquire(vpImage< unsigned char > &grey, double *ts=nullptr)
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)
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.