47#include <visp3/core/vpConfig.h>
49#if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
51#include <visp3/core/vpDisplay.h>
52#include <visp3/core/vpException.h>
53#include <visp3/core/vpHomogeneousMatrix.h>
54#include <visp3/core/vpImage.h>
55#include <visp3/detection/vpDetectorAprilTag.h>
56#include <visp3/gui/vpDisplayFactory.h>
57#include <visp3/io/vpParseArgv.h>
58#include <visp3/robot/vpRobotBiclops.h>
59#include <visp3/sensor/vpRealSense2.h>
60#include <visp3/visual_features/vpFeatureBuilder.h>
61#include <visp3/visual_features/vpFeaturePoint.h>
62#include <visp3/vs/vpServo.h>
63#include <visp3/vs/vpServoDisplay.h>
66#define GETOPTARGS "c:d:h"
68#ifdef ENABLE_VISP_NAMESPACE
79void usage(
const char *name,
const char *badparam, std::string &conf)
82 Example of eye-in-hand control law. We control here a real robot, the biclops\n\
83 robot (pan-tilt head provided by Traclabs) equipped with a Realsense camera\n\
84 mounted on its end-effector. The velocity to apply to the PT head is joint\n\
85 velocity. The visual feature is a point corresponding to the center of\n\
86 gravity of an AprilTag. \n\
89 %s [-c <Biclops configuration file>] [-h]\n",
94 -c <Biclops configuration file> %s\n\
95 Sets the Biclops robot configuration file.\n",
99 fprintf(stderr,
"ERROR: \n");
100 fprintf(stderr,
"\nBad parameter [%s]\n", badparam);
114bool getOptions(
int argc,
const char **argv, std::string &conf)
125 usage(argv[0],
nullptr, conf);
129 usage(argv[0], optarg_, conf);
134 if ((c == 1) || (c == -1)) {
136 usage(argv[0],
nullptr, conf);
137 std::cerr <<
"ERROR: " << std::endl;
138 std::cerr <<
" Bad argument " << optarg_ << std::endl << std::endl;
145int main(
int argc,
const char **argv)
147#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
148 std::shared_ptr<vpDisplay> display;
154 std::string opt_conf =
"/usr/share/BiclopsDefault.cfg";
157 if (getOptions(argc, argv, opt_conf) ==
false) {
200 cRe[0][0] = 0; cRe[0][1] = 1; cRe[0][2] = 0;
201 cRe[1][0] = -1; cRe[1][1] = 0; cRe[1][2] = 0;
202 cRe[2][0] = 0; cRe[2][1] = 0; cRe[2][2] = 1;
215 config.disable_stream(RS2_STREAM_DEPTH);
216 config.disable_stream(RS2_STREAM_INFRARED);
217 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
220 std::cout <<
"Read camera parameters from Realsense device" << std::endl;
226 std::cout <<
"Move PT to initial position: " << q.t() << std::endl;
235#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
262 task.addFeature(p, pd);
269 bool send_velocities =
false;
277 std::stringstream ss;
278 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
292 q_dot =
task.computeControlLaw();
297 std::cout <<
"q_dot: " << q_dot.
t() << std::endl;
299 std::cout <<
"|| s - s* || = " << (
task.getError()).
sumSquare() << std::endl;
304 if (!send_velocities) {
316 send_velocities = !send_velocities;
330 std::cout <<
"Stop the robot " << std::endl;
333#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
334 if (display !=
nullptr) {
341 std::cout <<
"Catch an exception: " <<
e.getMessage() << std::endl;
342#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
343 if (display !=
nullptr) {
354 std::cout <<
"You do not have an Biclops PT robot connected to your computer..." << std::endl;
@ DH2
Second Denavit-Hartenberg representation.
static const unsigned int ndof
Number of dof.
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
bool detect(const vpImage< unsigned char > &I) VP_OVERRIDE
vpImagePoint getCog(size_t i) const
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 create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
vpFeaturePoint & buildFrom(const double &x, const double &y, const double &Z)
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 ...
Definition of the vpImage class member functions.
Implementation of a matrix and operations on matrices.
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
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())
Interface for the Biclops, pan, tilt head control.
@ STATE_POSITION_CONTROL
Initialize the position controller.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
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)
Class that consider the case of a translation vector.
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.