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/vpDisplayGDI.h>
59 #include <visp3/gui/vpDisplayGTK.h>
60 #include <visp3/gui/vpDisplayX.h>
61 #include <visp3/robot/vpRobotPololuPtu.h>
62 #include <visp3/sensor/vpRealSense2.h>
63 #include <visp3/visual_features/vpFeatureBuilder.h>
64 #include <visp3/visual_features/vpFeaturePoint.h>
65 #include <visp3/vs/vpServo.h>
66 #include <visp3/vs/vpAdaptiveGain.h>
67 #include <visp3/vs/vpServoDisplay.h>
69 void usage(
const char **argv,
int error,
const std::string &device,
int baudrate)
71 std::cout <<
"Name" << std::endl
72 <<
" Example of eye-in-hand control law. We control here a real robot, a pan-tilt unit" << std::endl
73 <<
" controlled using a Pololu Maestro board equipped.The PTU is equipped with a Realsense" << std::endl
74 <<
" camera mounted on its end-effector.The velocity to apply to the PT head is a joint" << std::endl
75 <<
" velocity.The visual feature is a point corresponding to the center of gravity" << std::endl
76 <<
" of an AprilTag." << std::endl
78 std::cout <<
"Synopsis" << std::endl
79 <<
" " << argv[0] <<
" [--device <name>] [--baud <rate>] [--verbose, -v] [--help, -h]" << std::endl
81 std::cout <<
"Description" << std::endl
82 <<
" --device <name> Device name." << std::endl
83 <<
" Default: " << device << std::endl
85 <<
" --baud <rate> Serial link baud rate." << std::endl
86 <<
" Default: " << baudrate << std::endl
88 <<
" --verbose, -v Enable verbosity." << std::endl
90 <<
" --help, -h Print this helper message." << std::endl
93 std::cout <<
"Error" << std::endl
95 <<
"Unsupported parameter " << argv[error] << std::endl;
99 int main(
int argc,
const char **argv)
102 std::string opt_device =
"COM4";
104 std::string opt_device =
"/dev/ttyACM0";
108 int opt_baudrate = 38400;
109 bool opt_verbose =
false;
111 for (
int i = 1; i < argc; i++) {
112 if (std::string(argv[i]) ==
"--device" && i + 1 < argc) {
113 opt_device = std::string(argv[i + 1]);
116 else if (std::string(argv[i]) ==
"--verbose" || std::string(argv[i]) ==
"-v") {
119 else if (std::string(argv[i]) ==
"--help" || std::string(argv[i]) ==
"-h") {
120 usage(argv, 0, opt_device, opt_baudrate);
124 usage(argv, i, opt_device, opt_baudrate);
177 std::cout <<
"Move PT to initial position: " << q.t() << std::endl;
179 robot.setPositioningVelocityPercentage(10.f);
184 std::cout <<
"Min velocity resolution: " <<
vpMath::deg(robot.getAngularVelocityResolution()) <<
" deg/s" << std::endl;
189 config.disable_stream(RS2_STREAM_DEPTH);
190 config.disable_stream(RS2_STREAM_INFRARED);
191 config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
194 std::cout <<
"Read camera parameters from Realsense device" << std::endl;
203 #if defined(VISP_HAVE_X11)
205 #elif defined(VISP_HAVE_GTK)
207 #elif defined(VISP_HAVE_GDI)
258 bool send_velocities =
false;
260 double min_pix_error = 10;
268 std::stringstream ss;
269 ss <<
"Left click to " << (send_velocities ?
"stop the robot" :
"servo the robot") <<
", right click to quit.";
288 double error = (task.
getError()).sumSquare();
290 std::cout <<
"|| s - s* || = " << error << std::endl;
292 if (error < min_error) {
294 std::cout <<
"Stop the robot" << std::endl;
302 if (!send_velocities) {
314 send_velocities = !send_velocities;
328 std::cout <<
"Stop the robot " << std::endl;
334 std::cout <<
"Catch an exception: " << e.
getMessage() << std::endl;
342 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
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 ...
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())
void get_eJe(vpMatrix &eJe) vp_override
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel) vp_override
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.
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.
VISP_EXPORT int wait(double t0, double t)