63 #include <visp3/core/vpCameraParameters.h> 64 #include <visp3/core/vpXmlParserCamera.h> 65 #include <visp3/gui/vpDisplayGDI.h> 66 #include <visp3/gui/vpDisplayX.h> 67 #include <visp3/io/vpImageIo.h> 68 #include <visp3/sensor/vpFlyCaptureGrabber.h> 69 #include <visp3/robot/vpRobotFlirPtu.h> 70 #include <visp3/detection/vpDetectorAprilTag.h> 71 #include <visp3/visual_features/vpFeatureBuilder.h> 72 #include <visp3/visual_features/vpFeaturePoint.h> 73 #include <visp3/vs/vpServo.h> 74 #include <visp3/vs/vpServoDisplay.h> 75 #include <visp3/gui/vpPlot.h> 77 #if defined(VISP_HAVE_FLIR_PTU_SDK) && defined(VISP_HAVE_FLYCAPTURE) && \ 78 (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) 81 int main(
int argc,
char **argv)
83 std::string opt_portname;
84 int opt_baudrate = 9600;
85 bool opt_network =
false;
86 std::string opt_extrinsic;
87 double opt_tag_size = 0.120;
88 double opt_constant_gain = 0.5;
91 std::cout <<
"To see how to use this example, run: " << argv[0] <<
" --help" << std::endl;
95 for (
int i = 1; i < argc; i++) {
96 if ((std::string(argv[i]) ==
"--portname" || std::string(argv[i]) ==
"-p") && (i + 1 < argc)) {
97 opt_portname = std::string(argv[i + 1]);
99 else if ((std::string(argv[i]) ==
"--baudrate" || std::string(argv[i]) ==
"-b") && (i + 1 < argc)) {
100 opt_baudrate = std::atoi(argv[i + 1]);
102 else if ((std::string(argv[i]) ==
"--network" || std::string(argv[i]) ==
"-n")) {
105 else if (std::string(argv[i]) ==
"--extrinsic" && i + 1 < argc) {
106 opt_extrinsic = std::string(argv[i + 1]);
108 else if (std::string(argv[i]) ==
"--constant-gain" || std::string(argv[i]) ==
"-g") {
109 opt_constant_gain = std::stod(argv[i + 1]);;
111 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
112 std::cout <<
"SYNOPSIS" << std::endl
113 <<
" " << argv[0] <<
" [--portname <portname>] [--baudrate <rate>] [--network] " 114 <<
"[--extrinsic <extrinsic.yaml>] [--constant-gain] [--help] [-h]" << std::endl << std::endl;
115 std::cout <<
"DESCRIPTION" << std::endl
116 <<
" --portname, -p <portname>" << std::endl
117 <<
" Set serial or tcp port name." << std::endl << std::endl
118 <<
" --baudrate, -b <rate>" << std::endl
119 <<
" Set serial communication baud rate. Default: " << opt_baudrate <<
"." << std::endl << std::endl
120 <<
" --network, -n" << std::endl
121 <<
" Get PTU network information (Hostname, IP, Gateway) and exit. " << std::endl << std::endl
122 <<
" --extrinsic <extrinsic.yaml>" << std::endl
123 <<
" YAML file containing extrinsic camera parameters as a vpHomogeneousMatrix." << std::endl
124 <<
" It corresponds to the homogeneous transformation eMc, between end-effector" << std::endl
125 <<
" and camera frame." << std::endl << std::endl
126 <<
" --constant-gain, -g" << std::endl
127 <<
" Constant gain value. Default value: " << opt_constant_gain << std::endl << std::endl
128 <<
" --help, -h" << std::endl
129 <<
" Print this helper message. " << std::endl << std::endl;
130 std::cout <<
"EXAMPLE" << std::endl
131 <<
" - How to get network IP" << std::endl
133 <<
" $ " << argv[0] <<
" --portname COM1 --network" << std::endl
134 <<
" Try to connect FLIR PTU to port: COM1 with baudrate: 9600" << std::endl
136 <<
" $ " << argv[0] <<
" --portname /dev/ttyUSB0 --network" << std::endl
137 <<
" Try to connect FLIR PTU to port: /dev/ttyUSB0 with baudrate: 9600" << std::endl
139 <<
" PTU HostName: PTU-5" << std::endl
140 <<
" PTU IP : 169.254.110.254" << std::endl
141 <<
" PTU Gateway : 0.0.0.0" << std::endl
142 <<
" - How to run this binary using network communication" << std::endl
143 <<
" $ " << argv[0] <<
" --portname tcp:169.254.110.254 --tag-size 0.1 --gain 0.1" << std::endl;
152 std::cout <<
"Try to connect FLIR PTU to port: " << opt_portname <<
" with baudrate: " << opt_baudrate << std::endl;
153 robot.
connect(opt_portname, opt_baudrate);
157 std::cout <<
"PTU IP : " << robot.
getNetworkIP() <<std::endl;
173 etc << -0.1, -0.123, 0.035;
176 if (!opt_extrinsic.empty()) {
182 std::cout <<
"Considered extrinsic transformation eMc:\n" << eMc << std::endl;
186 std::cout <<
"Considered intrinsic camera parameters:\n" << cam <<
"\n";
188 #if defined(VISP_HAVE_X11) 190 #elif defined(VISP_HAVE_GDI) 213 bool final_quit =
false;
214 bool send_velocities =
false;
224 std::vector<vpHomogeneousMatrix> cMo_vec;
227 while (!final_quit) {
232 detector.
detect(I, opt_tag_size, cam, cMo_vec);
234 std::stringstream ss;
235 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
242 double Z = cMo_vec[0][2][3];
263 if (!send_velocities) {
276 send_velocities = !send_velocities;
289 std::cout <<
"Stop the robot " << std::endl;
293 std::cout <<
"Catch Flir Ptu exception: " << e.
getMessage() << std::endl;
302 #if !defined(VISP_HAVE_FLYCAPTURE) 303 std::cout <<
"Install FLIR Flycapture" << std::endl;
305 #if !defined(VISP_HAVE_FLIR_PTU_SDK) 306 std::cout <<
"Install FLIR PTU SDK." << std::endl;
Implementation of a matrix and operations on matrices.
Error that can be emited by the vpRobot class and its derivates.
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void setAprilTagPoseEstimationMethod(const vpPoseEstimationMethod &poseEstimationMethod)
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
Implementation of an homogeneous matrix and operations on such kind of matrices.
AprilTag 36h11 pattern (recommended)
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Display for windows using GDI (available on any windows 32 platform).
void set_eJe(const vpMatrix &eJe_)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
void acquire(vpImage< unsigned char > &I)
std::string getNetworkHostName()
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
size_t getNbObjects() const
const char * getMessage() const
static void flush(const vpImage< unsigned char > &I)
void open(vpImage< unsigned char > &I)
Implementation of a rotation matrix and operations on such kind of matrices.
void setAprilTagQuadDecimate(float quadDecimate)
std::string getNetworkGateway()
Initialize the velocity controller.
vpColVector computeControlLaw()
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void set_eMc(vpHomogeneousMatrix &eMc)
static void display(const vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
void set_xyZ(double x, double y, double Z)
void get_eJe(vpMatrix &eJe)
vpImagePoint getCog(size_t i) const
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Stops robot motion especially in velocity and acceleration control.
void connect(const std::string &portname, int baudrate=9600)
unsigned int getHeight() const
std::string getNetworkIP()
Implementation of column vector and the associated operations.
void setDisplayTag(bool display, const vpColor &color=vpColor::none, unsigned int thickness=2)
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Implementation of a pose vector and operations on poses.
vpVelocityTwistMatrix get_cVe() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
unsigned int getWidth() const
void setServo(const vpServoType &servo_type)
Class that consider the case of a translation vector.
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)
bool detect(const vpImage< unsigned char > &I)