58 #include <visp3/core/vpCameraParameters.h>
59 #include <visp3/core/vpConfig.h>
60 #include <visp3/detection/vpDetectorAprilTag.h>
61 #include <visp3/gui/vpDisplayFactory.h>
62 #include <visp3/gui/vpPlot.h>
63 #include <visp3/io/vpImageIo.h>
64 #include <visp3/robot/vpRobotFlirPtu.h>
65 #include <visp3/sensor/vpFlyCaptureGrabber.h>
66 #include <visp3/visual_features/vpFeatureBuilder.h>
67 #include <visp3/visual_features/vpFeaturePoint.h>
68 #include <visp3/vs/vpServo.h>
69 #include <visp3/vs/vpServoDisplay.h>
71 #if defined(VISP_HAVE_FLIR_PTU_SDK) && defined(VISP_HAVE_FLYCAPTURE) && defined(VISP_HAVE_DISPLAY)
73 int main(
int argc,
char **argv)
75 #ifdef ENABLE_VISP_NAMESPACE
79 std::string opt_portname;
80 int opt_baudrate = 9600;
81 bool opt_network =
false;
82 std::string opt_extrinsic;
83 double opt_tag_size = 0.120;
84 double opt_constant_gain = 0.5;
87 std::cout <<
"To see how to use this example, run: " << argv[0] <<
" --help" << std::endl;
91 for (
int i = 1; i < argc; i++) {
92 if ((std::string(argv[i]) ==
"--portname" || std::string(argv[i]) ==
"-p") && (i + 1 < argc)) {
93 opt_portname = std::string(argv[i + 1]);
95 else if ((std::string(argv[i]) ==
"--baudrate" || std::string(argv[i]) ==
"-b") && (i + 1 < argc)) {
96 opt_baudrate = std::atoi(argv[i + 1]);
98 else if ((std::string(argv[i]) ==
"--network" || std::string(argv[i]) ==
"-n")) {
101 else if (std::string(argv[i]) ==
"--extrinsic" && i + 1 < argc) {
102 opt_extrinsic = std::string(argv[i + 1]);
104 else if (std::string(argv[i]) ==
"--constant-gain" || std::string(argv[i]) ==
"-g") {
105 opt_constant_gain = std::stod(argv[i + 1]);
108 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
109 std::cout <<
"SYNOPSIS" << std::endl
110 <<
" " << argv[0] <<
" [--portname <portname>] [--baudrate <rate>] [--network] "
111 <<
"[--extrinsic <extrinsic.yaml>] [--constant-gain] [--help] [-h]" << std::endl
113 std::cout <<
"DESCRIPTION" << std::endl
114 <<
" --portname, -p <portname>" << std::endl
115 <<
" Set serial or tcp port name." << std::endl
117 <<
" --baudrate, -b <rate>" << std::endl
118 <<
" Set serial communication baud rate. Default: " << opt_baudrate <<
"." << std::endl
120 <<
" --network, -n" << std::endl
121 <<
" Get PTU network information (Hostname, IP, Gateway) and exit. " << std::endl
123 <<
" --extrinsic <extrinsic.yaml>" << std::endl
124 <<
" YAML file containing extrinsic camera parameters as a vpHomogeneousMatrix." << std::endl
125 <<
" It corresponds to the homogeneous transformation eMc, between end-effector" << std::endl
126 <<
" and camera frame." << std::endl
128 <<
" --constant-gain, -g" << std::endl
129 <<
" Constant gain value. Default value: " << opt_constant_gain << std::endl
131 <<
" --help, -h" << std::endl
132 <<
" Print this helper message. " << std::endl
134 std::cout <<
"EXAMPLE" << std::endl
135 <<
" - How to get network IP" << std::endl
137 <<
" $ " << argv[0] <<
" --portname COM1 --network" << std::endl
138 <<
" Try to connect FLIR PTU to port: COM1 with baudrate: 9600" << std::endl
140 <<
" $ " << argv[0] <<
" --portname /dev/ttyUSB0 --network" << std::endl
141 <<
" Try to connect FLIR PTU to port: /dev/ttyUSB0 with baudrate: 9600" << std::endl
143 <<
" PTU HostName: PTU-5" << std::endl
144 <<
" PTU IP : 169.254.110.254" << std::endl
145 <<
" PTU Gateway : 0.0.0.0" << std::endl
146 <<
" - How to run this binary using network communication" << std::endl
147 <<
" $ " << argv[0] <<
" --portname tcp:169.254.110.254 --tag-size 0.1 --gain 0.1" << std::endl;
155 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
156 std::shared_ptr<vpDisplay> display;
162 std::cout <<
"Try to connect FLIR PTU to port: " << opt_portname <<
" with baudrate: " << opt_baudrate << std::endl;
163 robot.connect(opt_portname, opt_baudrate);
166 std::cout <<
"PTU HostName: " << robot.getNetworkHostName() << std::endl;
167 std::cout <<
"PTU IP : " << robot.getNetworkIP() << std::endl;
168 std::cout <<
"PTU Gateway : " << robot.getNetworkGateway() << std::endl;
180 eRc << 0, 0, 1, -1, 0, 0, 0, -1, 0;
181 etc << -0.1, -0.123, 0.035;
184 if (!opt_extrinsic.empty()) {
190 std::cout <<
"Considered extrinsic transformation eMc:\n" << eMc << std::endl;
194 std::cout <<
"Considered intrinsic camera parameters:\n" << cam <<
"\n";
196 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
204 detector.setDisplayTag(
true);
205 detector.setAprilTagQuadDecimate(2);
221 bool final_quit =
false;
222 bool send_velocities =
false;
232 std::vector<vpHomogeneousMatrix> cMo_vec;
235 while (!final_quit) {
240 detector.detect(I, opt_tag_size, cam, cMo_vec);
242 std::stringstream ss;
243 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
247 if (detector.getNbObjects() == 1) {
250 double Z = cMo_vec[0][2][3];
271 if (!send_velocities) {
284 send_velocities = !send_velocities;
297 std::cout <<
"Stop the robot " << std::endl;
301 std::cout <<
"Catch Flir Ptu exception: " << e.
getMessage() << std::endl;
305 #if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
306 if (display !=
nullptr) {
315 #if !defined(VISP_HAVE_FLYCAPTURE)
316 std::cout <<
"Install FLIR Flycapture" << std::endl;
318 #if !defined(VISP_HAVE_FLIR_PTU_SDK)
319 std::cout <<
"Install FLIR PTU SDK." << std::endl;
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
@ TAG_36h11
AprilTag 36h11 pattern (recommended)
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)
const char * getMessage() const
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
void set_xyZ(double x, double y, double Z)
void open(vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &I)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
unsigned int getWidth() const
unsigned int getHeight() const
Implementation of a matrix and operations on matrices.
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Implementation of a pose vector and operations on poses.
Error that can be emitted by the vpRobot class and its derivatives.
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) VP_OVERRIDE
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Implementation of a rotation matrix and operations on such kind of matrices.
static void display(const vpServo &s, const vpCameraParameters &cam, const vpImage< unsigned char > &I, vpColor currentColor=vpColor::green, vpColor desiredColor=vpColor::red, unsigned int thickness=1)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
void addFeature(vpBasicFeature &s_cur, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
void set_cVe(const vpVelocityTwistMatrix &cVe_)
void set_eJe(const vpMatrix &eJe_)
void setServo(const vpServoType &servo_type)
vpColVector computeControlLaw()
Class that consider the case of a translation vector.
vpVelocityTwistMatrix get_cVe() const
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.