48#include <visp3/core/vpConfig.h>
50#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
52#include <visp3/core/vpDisplay.h>
53#include <visp3/core/vpException.h>
54#include <visp3/core/vpHomogeneousMatrix.h>
55#include <visp3/core/vpImage.h>
56#include <visp3/core/vpTime.h>
57#include <visp3/detection/vpDetectorAprilTag.h>
58#include <visp3/gui/vpDisplayFactory.h>
59#include <visp3/robot/vpRobotPololuPtu.h>
60#include <visp3/sensor/vpRealSense2.h>
61#include <visp3/visual_features/vpFeatureBuilder.h>
62#include <visp3/visual_features/vpFeaturePoint.h>
63#include <visp3/vs/vpServo.h>
64#include <visp3/vs/vpAdaptiveGain.h>
65#include <visp3/vs/vpServoDisplay.h>
67void usage(
const char **argv,
int error,
const std::string &device,
int baudrate)
69 std::cout <<
"Name" << std::endl
70 <<
" Example of eye-in-hand control law. We control here a real robot, a pan-tilt unit" << std::endl
71 <<
" controlled using a Pololu Maestro board equipped.The PTU is equipped with a Realsense" << std::endl
72 <<
" camera mounted on its end-effector.The velocity to apply to the PT head is a joint" << std::endl
73 <<
" velocity.The visual feature is a point corresponding to the center of gravity" << std::endl
74 <<
" of an AprilTag." << std::endl
76 std::cout <<
"Synopsis" << std::endl
77 <<
" " << argv[0] <<
" [--device <name>] [--baud <rate>] [--verbose, -v] [--help, -h]" << std::endl
79 std::cout <<
"Description" << std::endl
80 <<
" --device <name> Device name." << std::endl
81 <<
" Default: " << device << std::endl
83 <<
" --baud <rate> Serial link baud rate." << std::endl
84 <<
" Default: " << baudrate << std::endl
86 <<
" --verbose, -v Enable verbosity." << std::endl
88 <<
" --help, -h Print this helper message." << std::endl
91 std::cout <<
"Error" << std::endl
93 <<
"Unsupported parameter " << argv[
error] << std::endl;
97int main(
int argc,
const char **argv)
99#ifdef ENABLE_VISP_NAMESPACE
104 std::string opt_device =
"COM4";
106 std::string opt_device =
"/dev/ttyACM0";
110 int opt_baudrate = 38400;
111 bool opt_verbose =
false;
113 for (
int i = 1;
i < argc;
i++) {
114 if (std::string(argv[i]) ==
"--device" && i + 1 < argc) {
115 opt_device = std::string(argv[i + 1]);
118 else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
121 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
122 usage(argv, 0, opt_device, opt_baudrate);
126 usage(argv, i, opt_device, opt_baudrate);
131#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
132 std::shared_ptr<vpDisplay> display;
184 std::cout <<
"Move PT to initial position: " << q.t() << std::endl;
186 robot.setPositioningVelocityPercentage(10.f);
191 std::cout <<
"Min velocity resolution: " <<
vpMath::deg(robot.getAngularVelocityResolution()) <<
" deg/s" << std::endl;
196 config.disable_stream(RS2_STREAM_DEPTH);
197 config.disable_stream(RS2_STREAM_INFRARED);
198 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
201 std::cout <<
"Read camera parameters from Realsense device" << std::endl;
210#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
237 task.addFeature(p, pd);
242 task.setLambda(lambda);
263 bool send_velocities =
false;
265 double min_pix_error = 10;
273 std::stringstream ss;
274 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
288 q_dot =
task.computeControlLaw();
293 double error = (
task.getError()).sumSquare();
295 std::cout <<
"|| s - s* || = " <<
error << std::endl;
297 if (error < min_error) {
299 std::cout <<
"Stop the robot" << std::endl;
307 if (!send_velocities) {
319 send_velocities = !send_velocities;
333 std::cout <<
"Stop the robot " << std::endl;
336#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
337 if (display !=
nullptr) {
344 std::cout <<
"Catch an exception: " <<
e.getMessage() << std::endl;
345#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
346 if (display !=
nullptr) {
357 std::cout <<
"You do not have a Pololu PTU connected to your computer..." << std::endl;
Adaptive gain computation.
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.
static double sqr(double x)
static double deg(double rad)
Implementation of a matrix and operations on matrices.
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 Pololu Maestro pan-tilt unit using two servo motors.
@ 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.
VISP_EXPORT int wait(double t0, double t)