Example of eye-in-hand control law. We control here a real robot, a pan-tilt head controlled using a Pololu Maestro board where pan axis servo a connected to channel 0 and tilt axis to channel 1. The velocity is computed in joint. The visual feature is a 2D point corresponding to the center of gravity of an AprilTag. A Realsense camera is mounted on the pan-tilt unit.
#include <iostream>
#include <visp3/core/vpConfig.h>
#if defined(VISP_HAVE_POLOLU) && defined(VISP_HAVE_APRILTAG) && defined(VISP_HAVE_REALSENSE2)
#include <visp3/core/vpDisplay.h>
#include <visp3/core/vpException.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/core/vpImage.h>
#include <visp3/core/vpTime.h>
#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/gui/vpDisplayFactory.h>
#include <visp3/robot/vpRobotPololuPtu.h>
#include <visp3/sensor/vpRealSense2.h>
#include <visp3/visual_features/vpFeatureBuilder.h>
#include <visp3/visual_features/vpFeaturePoint.h>
#include <visp3/vs/vpServo.h>
#include <visp3/vs/vpAdaptiveGain.h>
#include <visp3/vs/vpServoDisplay.h>
void usage(const char **argv, int error, const std::string &device, int baudrate)
{
std::cout << "Name" << std::endl
<< " Example of eye-in-hand control law. We control here a real robot, a pan-tilt unit" << std::endl
<< " controlled using a Pololu Maestro board equipped.The PTU is equipped with a Realsense" << std::endl
<< " camera mounted on its end-effector.The velocity to apply to the PT head is a joint" << std::endl
<< " velocity.The visual feature is a point corresponding to the center of gravity" << std::endl
<< " of an AprilTag." << std::endl
<< std::endl;
std::cout << "Synopsis" << std::endl
<< " " << argv[0] << " [--device <name>] [--baud <rate>] [--verbose, -v] [--help, -h]" << std::endl
<< std::endl;
std::cout << "Description" << std::endl
<< " --device <name> Device name." << std::endl
<< " Default: " << device << std::endl
<< std::endl
<< " --baud <rate> Serial link baud rate." << std::endl
<< " Default: " << baudrate << std::endl
<< std::endl
<< " --verbose, -v Enable verbosity." << std::endl
<< std::endl
<< " --help, -h Print this helper message." << std::endl
<< std::endl;
if (error) {
std::cout << "Error" << std::endl
<< " "
<< "Unsupported parameter " << argv[error] << std::endl;
}
}
int main(int argc, const char **argv)
{
#ifdef ENABLE_VISP_NAMESPACE
#endif
#ifdef _WIN32
std::string opt_device = "COM4";
#else
std::string opt_device = "/dev/ttyACM0";
#endif
int opt_baudrate = 38400;
bool opt_verbose = false;
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--device" && i + 1 < argc) {
opt_device = std::string(argv[i + 1]);
i++;
}
else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
opt_verbose = true;
}
else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
usage(argv, 0, opt_device, opt_baudrate);
return EXIT_SUCCESS;
}
else {
usage(argv, i, opt_device, opt_baudrate);
return EXIT_FAILURE;
}
}
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
std::shared_ptr<vpDisplay> display;
#else
#endif
try {
q = 0;
std::cout << "Move PT to initial position: " << q.t() << std::endl;
robot.setPositioningVelocityPercentage(10.f);
std::cout <<
"Min velocity resolution: " <<
vpMath::deg(robot.getAngularVelocityResolution()) <<
" deg/s" << std::endl;
rs2::config config;
config.disable_stream(RS2_STREAM_DEPTH);
config.disable_stream(RS2_STREAM_INFRARED);
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
std::cout << "Read camera parameters from Realsense device" << std::endl;
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
#else
#endif
bool quit = false;
bool send_velocities = false;
double min_pix_error = 10;
while (!quit) {
{
std::stringstream ss;
ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
}
double error = (task.
getError()).sumSquare();
if (opt_verbose) {
std::cout << "|| s - s* || = " << error << std::endl;
}
if (error < min_error) {
if (opt_verbose) {
std::cout << "Stop the robot" << std::endl;
}
q_dot = 0;
}
}
else {
q_dot = 0;
}
if (!send_velocities) {
q_dot = 0;
}
switch (button) {
send_velocities = !send_velocities;
break;
quit = true;
q_dot = 0;
break;
default:
break;
}
}
}
std::cout << "Stop the robot " << std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_SUCCESS;
}
std::cout <<
"Catch an exception: " << e.
getMessage() << std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_FAILURE;
}
}
#else
int main()
{
std::cout << "You do not have a Pololu PTU connected to your computer..." << std::endl;
return EXIT_SUCCESS;
}
#endif
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.
const char * getMessage() const
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpImagePoint &t)
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 ...
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.
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)