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/vpDisplayGDI.h>
57 #include <visp3/gui/vpDisplayGTK.h>
58 #include <visp3/gui/vpDisplayX.h>
59 #include <visp3/io/vpParseArgv.h>
60 #include <visp3/robot/vpRobotBiclops.h>
61 #include <visp3/sensor/vpRealSense2.h>
62 #include <visp3/visual_features/vpFeatureBuilder.h>
63 #include <visp3/visual_features/vpFeaturePoint.h>
64 #include <visp3/vs/vpServo.h>
65 #include <visp3/vs/vpServoDisplay.h>
68 #define GETOPTARGS "c:d:h"
77 void usage(
const char *name,
const char *badparam, std::string &conf)
80 Example of eye-in-hand control law. We control here a real robot, the biclops\n\
81 robot (pan-tilt head provided by Traclabs) equipped with a Realsense camera\n\
82 mounted on its end-effector. The velocity to apply to the PT head is joint\n\
83 velocity. The visual feature is a point corresponding to the center of\n\
84 gravity of an AprilTag. \n\
87 %s [-c <Biclops configuration file>] [-h]\n",
92 -c <Biclops configuration file> %s\n\
93 Sets the Biclops robot configuration file.\n",
97 fprintf(stderr,
"ERROR: \n");
98 fprintf(stderr,
"\nBad parameter [%s]\n", badparam);
112 bool getOptions(
int argc,
const char **argv, std::string &conf)
123 usage(argv[0],
nullptr, conf);
128 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;
145 int main(
int argc,
const char **argv)
149 std::string opt_conf =
"/usr/share/BiclopsDefault.cfg";
152 if (getOptions(argc, argv, opt_conf) ==
false) {
195 cRe[0][0] = 0; cRe[0][1] = 1; cRe[0][2] = 0;
196 cRe[1][0] = -1; cRe[1][1] = 0; cRe[1][2] = 0;
197 cRe[2][0] = 0; cRe[2][1] = 0; cRe[2][2] = 1;
210 config.disable_stream(RS2_STREAM_DEPTH);
211 config.disable_stream(RS2_STREAM_INFRARED);
212 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
215 std::cout <<
"Read camera parameters from Realsense device" << std::endl;
221 std::cout <<
"Move PT to initial position: " << q.t() << std::endl;
230 #if defined(VISP_HAVE_X11)
232 #elif defined(VISP_HAVE_GTK)
234 #elif defined(VISP_HAVE_GDI)
266 bool send_velocities =
false;
274 std::stringstream ss;
275 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
294 std::cout <<
"q_dot: " << q_dot.
t() << std::endl;
296 std::cout <<
"|| s - s* || = " << (task.
getError()).sumSquare() << std::endl;
301 if (!send_velocities) {
313 send_velocities = !send_velocities;
327 std::cout <<
"Stop the robot " << std::endl;
333 std::cout <<
"Catch an exception: " << e.
getMessage() << std::endl;
341 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
Display for windows using GDI (available on any windows 32 platform).
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
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 * getMessage() const
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...
void buildFrom(double x, double y, 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 ...
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.
void get_eJe(vpMatrix &eJe) vp_override
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
@ 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.
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 getError() const
vpColVector computeControlLaw()
Class that consider the case of a translation vector.
void display(vpImage< unsigned char > &I, const std::string &title)
Display a gray-scale image.