#include <iostream>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/core/vpXmlParserCamera.h>
#include <visp3/gui/vpDisplayFactory.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/robot/vpRobotUniversalRobots.h>
#include <visp3/sensor/vpRealSense2.h>
#if defined(VISP_HAVE_REALSENSE2) && \
defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_UR_RTDE) && defined(VISP_HAVE_PUGIXML) && \
defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_MODULE_ROBOT) && defined(VISP_HAVE_MODULE_SENSOR)
void usage(const char **argv, int error, const std::string &robot_ip)
{
std::cout << "Synopsis" << std::endl
<< " " << argv[0]
<< " [--ip <address>] [--output-folder <name>] [--help, -h]" << std::endl
<< std::endl;
std::cout << "Description" << std::endl
<< " --ip <address>" << std::endl
<< " Ethernet address to dial with the Panda robot." << std::endl
<< " Default: " << robot_ip << std::endl
<< std::endl
<< " --output-folder <name>" << std::endl
<< " Acquired data output folder." << std::endl
<< " Default: ./" << std::endl
<< std::endl
<< " --help, -h Print this helper message." << std::endl
<< std::endl;
if (error) {
std::cout << "Error" << std::endl
<< " "
<< "Unsupported parameter " << argv[error] << std::endl;
}
}
int main(int argc, const char **argv)
{
#if defined(ENABLE_VISP_NAMESPACE)
#endif
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
#endif
try {
std::string opt_robot_ip = "192.168.0.100";
std::string opt_output_folder = "./";
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--ip" && i + 1 < argc) {
opt_robot_ip = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--output-folder" && i + 1 < argc) {
opt_output_folder = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
usage(argv, 0, opt_robot_ip);
return EXIT_SUCCESS;
}
else {
usage(argv, i, opt_robot_ip);
return EXIT_FAILURE;
}
}
std::cout << "Create output directory: " << opt_output_folder << std::endl;
}
rs2::config config;
config.disable_stream(RS2_STREAM_DEPTH);
config.disable_stream(RS2_STREAM_INFRARED);
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
std::cout << "Image size: " << width << " x " << height << std::endl;
xml_camera.
save(cam, opt_output_folder +
"/ur_camera.xml",
"Camera", width, height);
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
#else
#endif
bool end = false;
unsigned cpt = 0;
while (!end) {
cpt++;
std::cout << "Connect to robot to get its position..." << std::endl;
robot.connect(opt_robot_ip);
robot.disconnect();
std::stringstream ss_img, ss_pos;
ss_img << opt_output_folder + "/ur_image-" << cpt << ".png";
ss_pos << opt_output_folder + "/ur_pose_rPe_" << cpt << ".yaml";
std::cout << "Save: " << ss_img.str() << " and " << ss_pos.str() << std::endl;
}
end = true;
}
}
}
}
std::cerr <<
"ViSP exception " << e.
what() << std::endl;
}
catch (const std::exception &e) {
std::cerr << e.what() << std::endl;
}
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (pdisp != nullptr) {
delete pdisp;
}
#endif
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_MODULE_GUI)
std::cout << "visp_gui module is not available?" << std::endl;
#endif
#if !defined(VISP_HAVE_MODULE_ROBOT)
std::cout << "visp_robot module is not available?" << std::endl;
#endif
#if !defined(VISP_HAVE_MODULE_SENSOR)
std::cout << "visp_sensor module is not available?" << std::endl;
#endif
#if !defined(VISP_HAVE_REALSENSE2)
std::cout << "Install librealsense-2.x." << std::endl;
#endif
#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 !defined(VISP_HAVE_PUGIXML)
std::cout << "Enable pugyxml built-in usage." << std::endl;
#endif
std::cout << "After installation of the missing 3rd parties, configure ViSP with cmake"
<< " and build ViSP again." << std::endl;
return EXIT_SUCCESS;
}
#endif
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.
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.
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.