Example of eye-in-hand image-based control law. We control here a real robot, the Franka Emika Panda robot (arm with 7 degrees of freedom). The velocity is computed in the camera frame. The inverse jacobian that converts cartesian velocities in joint velocities is implemented in the robot low level controller. Visual features correspond to the 3D pose of the target (an AprilTag) in the camera frame.
The device used to acquire images is a Realsense D435 device.
Camera intrinsic parameters are retrieved from the Realsense SDK.
#include <iostream>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/core/vpXmlParserCamera.h>
#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/gui/vpDisplayFactory.h>
#include <visp3/gui/vpPlot.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/robot/vpRobotFranka.h>
#include <visp3/sensor/vpRealSense2.h>
#include <visp3/visual_features/vpFeatureThetaU.h>
#include <visp3/visual_features/vpFeatureTranslation.h>
#include <visp3/vs/vpServo.h>
#include <visp3/vs/vpServoDisplay.h>
#if defined(VISP_HAVE_REALSENSE2) && defined(VISP_HAVE_DISPLAY) && defined(VISP_HAVE_FRANKA) && defined(VISP_HAVE_PUGIXML)
#ifdef ENABLE_VISP_NAMESPACE
#endif
std::vector<vpImagePoint> *traj_vip)
{
for (size_t i = 0; i < vip.size(); ++i) {
if (traj_vip[i].size()) {
traj_vip[i].push_back(vip[i]);
}
}
else {
traj_vip[i].push_back(vip[i]);
}
}
for (size_t i = 0; i < vip.size(); ++i) {
for (size_t j = 1; j < traj_vip[i].size(); j++) {
}
}
}
int main(int argc, char **argv)
{
double opt_tag_size = 0.120;
bool opt_tag_z_aligned = false;
std::string opt_robot_ip = "192.168.1.1";
std::string opt_eMc_filename = "";
std::string opt_intrinsic_filename = "";
std::string opt_camera_name = "Camera";
bool display_tag = true;
int opt_quad_decimate = 2;
bool opt_verbose = false;
bool opt_plot = false;
bool opt_adaptive_gain = false;
bool opt_task_sequencing = false;
double convergence_threshold_t = 0.0005;
double convergence_threshold_tu = 0.5;
for (int i = 1; i < argc; ++i) {
if ((std::string(argv[i]) == "--tag-size") && (i + 1 < argc)) {
opt_tag_size = std::stod(argv[++i]);
}
else if ((std::string(argv[i]) == "--tag-quad-decimate") && (i + 1 < argc)) {
opt_quad_decimate = std::stoi(argv[++i]);
}
else if (std::string(argv[i]) == "--tag-z-aligned") {
opt_tag_z_aligned = true;
}
else if ((std::string(argv[i]) == "--ip") && (i + 1 < argc)) {
opt_robot_ip = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) {
opt_intrinsic_filename = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--camera-name" && i + 1 < argc) {
opt_camera_name = std::string(argv[++i]);
}
else if ((std::string(argv[i]) == "--eMc") && (i + 1 < argc)) {
opt_eMc_filename = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--verbose") {
opt_verbose = true;
}
else if (std::string(argv[i]) == "--plot") {
opt_plot = true;
}
else if (std::string(argv[i]) == "--adaptive-gain") {
opt_adaptive_gain = true;
}
else if (std::string(argv[i]) == "--task-sequencing") {
opt_task_sequencing = true;
}
else if (std::string(argv[i]) == "--no-convergence-threshold") {
convergence_threshold_t = 0.;
convergence_threshold_tu = 0.;
}
else if ((std::string(argv[i]) == "--help") || (std::string(argv[i]) == "-h")) {
std::cout << "SYNOPSYS" << std::endl
<< " " << argv[0]
<< " [--ip <controller ip>]"
<< " [--intrinsic <xml file>]"
<< " [--camera-name <name>]"
<< " [--tag-size <size>]"
<< " [--tag-quad-decimate <decimation factor>]"
<< " [--tag-z-aligned]"
<< " [--eMc <extrinsic transformation file>]"
<< " [--adaptive-gain]"
<< " [--plot]"
<< " [--task-sequencing]"
<< " [--no-convergence-threshold]"
<< " [--verbose]"
<< " [--help] [-h]\n"
<< std::endl;
std::cout << "DESCRIPTION" << std::endl
<< " Use a position-based visual-servoing scheme to position the camera in front of an Apriltag." << std::endl
<< std::endl
<< " --ip <controller ip>" << std::endl
<< " Franka controller ip address" << std::endl
<< " Default: " << opt_robot_ip << std::endl
<< std::endl
<< " --intrinsic <xml file>" << std::endl
<< " XML file that contains camera intrinsic parameters. " << std::endl
<< " If no file is specified, use Realsense camera factory intrinsic parameters." << std::endl
<< std::endl
<< " --camera-name <name>" << std::endl
<< " Camera name in the XML file that contains camera intrinsic parameters." << std::endl
<< " Default: \"Camera\"" << std::endl
<< std::endl
<< " --tag-size <size>" << std::endl
<< " Apriltag size in [m]." << std::endl
<< " Default: " << opt_tag_size << " [m]" << std::endl
<< std::endl
<< " --tag-quad-decimate <decimation factor>" << std::endl
<< " Decimation factor used during Apriltag detection." << std::endl
<< " Default: " << opt_quad_decimate << std::endl
<< std::endl
<< " --tag-z-aligned" << std::endl
<< " When enabled, tag z-axis and camera z-axis are aligned." << std::endl
<< " Default: false" << std::endl
<< std::endl
<< " --eMc <extrinsic transformation file>" << std::endl
<< " File containing the homogeneous transformation matrix between" << std::endl
<< " robot end-effector and camera frame." << std::endl
<< std::endl
<< " --adaptive-gain" << std::endl
<< " Flag to enable adaptive gain to speed up visual servo near convergence." << std::endl
<< std::endl
<< " --plot" << std::endl
<< " Flag to enable curve plotter." << std::endl
<< std::endl
<< " --task-sequencing" << std::endl
<< " Flag to enable task sequencing scheme." << std::endl
<< std::endl
<< " --no-convergence-threshold" << std::endl
<< " Flag to disable convergence threshold used to stop the visual servo." << std::endl
<< std::endl
<< " --verbose" << std::endl
<< " Flag to enable extra verbosity." << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Print this helper message." << std::endl
<< std::endl;
return EXIT_SUCCESS;
}
else {
std::cout << "\nERROR" << std::endl
<< std::string(argv[i]) << " command line option is not supported." << std::endl
<< "Use " << std::string(argv[0]) << " --help" << std::endl
<< std::endl;
return EXIT_FAILURE;
}
}
config.enable_stream(RS2_STREAM_COLOR, 640, 480, RS2_FORMAT_RGBA8, 30);
config.enable_stream(RS2_STREAM_DEPTH, 640, 480, RS2_FORMAT_Z16, 30);
config.enable_stream(RS2_STREAM_INFRARED, 640, 480, RS2_FORMAT_Y8, 30);
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
#else
#endif
std::cout << "Parameters:" << std::endl;
std::cout << " Apriltag " << std::endl;
std::cout << " Size [m] : " << opt_tag_size << std::endl;
std::cout << " Z aligned : " << (opt_tag_z_aligned ? "true" : "false") << std::endl;
std::cout << " Camera intrinsics " << std::endl;
std::cout << " Factory parameters : " << (opt_intrinsic_filename.empty() ? "yes" : "no") << std::endl;
if (opt_intrinsic_filename.empty()) {
std::cout << "Use Realsense camera intrinsic factory parameters: " << std::endl;
std::cout <<
"cam:\n" <<
cam << std::endl;
}
std::cout << "Camera parameters file " << opt_intrinsic_filename << " doesn't exist." << std::endl;
return EXIT_FAILURE;
}
else {
if (!opt_camera_name.empty()) {
std::cout << " Param file name [.xml]: " << opt_intrinsic_filename << std::endl;
std::cout << " Camera name : " << opt_camera_name << std::endl;
std::cout << "Unable to parse parameters with distortion for camera \"" << opt_camera_name << "\" from "
<< opt_intrinsic_filename << " file" << std::endl;
std::cout << "Attempt to find parameters without distortion" << std::endl;
if (
parser.parse(cam, opt_intrinsic_filename, opt_camera_name,
std::cout << "Unable to parse parameters without distortion for camera \"" << opt_camera_name << "\" from "
<< opt_intrinsic_filename << " file" << std::endl;
return EXIT_FAILURE;
}
}
}
}
std::cout <<
"Camera parameters used to compute the pose:\n" <<
cam << std::endl;
detector.setAprilTagPoseEstimationMethod(poseEstimationMethod);
detector.setDisplayTag(display_tag);
detector.setAprilTagQuadDecimate(opt_quad_decimate);
detector.setZAlignedWithCameraAxis(opt_tag_z_aligned);
e_P_c[0] = 0.0337731;
e_P_c[1] = -0.00535012;
e_P_c[2] = -0.0523339;
e_P_c[3] = -0.247294;
e_P_c[4] = -0.306729;
e_P_c[5] = 1.53055;
if (!opt_eMc_filename.empty()) {
e_P_c.
loadYAML(opt_eMc_filename, e_P_c);
}
else {
std::cout << "Warning, opt_eMc_filename is empty! Use hard coded values." << std::endl;
}
std::cout << "e_M_c:\n" << e_M_c << std::endl;
try {
robot.connect(opt_robot_ip);
task.addFeature(tu, tud);
if (opt_adaptive_gain) {
}
else {
}
int iter_plot = 0;
if (opt_plot) {
plotter =
new vpPlot(2,
static_cast<int>(250 * 2), 500,
static_cast<int>(I.getWidth()) + 80, 10,
"Real time curves plotter");
plotter->setTitle(0,
"Visual features error");
plotter->setTitle(1,
"Camera velocities");
plotter->setLegend(0, 0,
"error_feat_tx");
plotter->setLegend(0, 1,
"error_feat_ty");
plotter->setLegend(0, 2,
"error_feat_tz");
plotter->setLegend(0, 3,
"error_feat_theta_ux");
plotter->setLegend(0, 4,
"error_feat_theta_uy");
plotter->setLegend(0, 5,
"error_feat_theta_uz");
}
bool final_quit = false;
bool has_converged = false;
bool send_velocities = false;
bool servo_started = false;
std::vector<vpImagePoint> *traj_vip = nullptr;
robot.set_eMc(e_M_c);
while (!has_converged && !final_quit) {
std::vector<vpHomogeneousMatrix> c_M_o_vec;
bool ret = detector.detect(I, opt_tag_size, cam, c_M_o_vec);
std::stringstream ss;
ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
if (ret && (c_M_o_vec.size() == 1)) {
c_M_o = c_M_o_vec[0];
static bool first_time = true;
if (first_time) {
std::vector<vpHomogeneousMatrix> secure_o_M_o(2), secure_cd_M_c(2);
secure_o_M_o[1].buildFrom(0, 0, 0, 0, 0, M_PI);
for (
size_t i = 0;
i < 2; ++
i) {
secure_cd_M_c[
i] = cd_M_o * secure_o_M_o[
i] * c_M_o.
inverse();
}
if (std::fabs(secure_cd_M_c[0].getThetaUVector().getTheta()) < std::fabs(secure_cd_M_c[1].getThetaUVector().getTheta())) {
o_M_o = secure_o_M_o[0];
}
else {
std::cout << "Desired frame modified to avoid PI rotation of the camera" << std::endl;
o_M_o = secure_o_M_o[1];
}
}
cd_M_c = cd_M_o * o_M_o * c_M_o.
inverse();
if (opt_task_sequencing) {
if (!servo_started) {
if (send_velocities) {
servo_started = true;
}
}
}
else {
v_c =
task.computeControlLaw();
}
std::vector<vpImagePoint> vip = detector.getPolygon(0);
vip.push_back(detector.getCog(0));
if (first_time) {
traj_vip = new std::vector<vpImagePoint>[vip.size()];
}
display_point_trajectory(I, vip, traj_vip);
if (opt_plot) {
iter_plot++;
}
if (opt_verbose) {
std::cout << "v_c: " << v_c.t() << std::endl;
}
ss.str("");
ss << "error_t: " << error_tr;
ss.str("");
ss << "error_tu: " << error_tu;
if (opt_verbose)
std::cout << "error translation: " << error_tr << " ; error rotation: " << error_tu << std::endl;
if (error_tr < convergence_threshold_t && error_tu < convergence_threshold_tu) {
has_converged = true;
std::cout << "Servo task has converged" << std::endl;
;
}
if (first_time) {
first_time = false;
}
}
else {
v_c = 0;
}
if (!send_velocities) {
v_c = 0;
}
ss.str("");
switch (button) {
send_velocities = !send_velocities;
break;
final_quit = true;
v_c = 0;
break;
default:
break;
}
}
}
std::cout << "Stop the robot " << std::endl;
if (opt_plot && plotter != nullptr) {
}
if (!final_quit) {
while (!final_quit) {
final_quit = true;
}
}
}
if (traj_vip) {
delete[] traj_vip;
}
}
std::cout <<
"ViSP exception: " <<
e.what() << std::endl;
std::cout << "Stop the robot " << std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_FAILURE;
}
catch (const franka::NetworkException &e) {
std::cout <<
"Franka network exception: " <<
e.what() << std::endl;
std::cout << "Check if you are connected to the Franka robot"
<< " or if you specified the right IP using --ip command line option set by default to 192.168.1.1. "
<< std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_FAILURE;
}
catch (const std::exception &e) {
std::cout <<
"Franka exception: " <<
e.what() << std::endl;
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_FAILURE;
}
#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
if (display != nullptr) {
delete display;
}
#endif
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_REALSENSE2)
std::cout << "Install librealsense-2.x and rebuild ViSP." << std::endl;
#endif
#if !defined(VISP_HAVE_FRANKA)
std::cout << "Install libfranka and rebuild ViSP." << std::endl;
#endif
#if !defined(VISP_HAVE_PUGIXML)
std::cout << "Build ViSP with pugixml support enabled." << std::endl;
#endif
return EXIT_SUCCESS;
}
#endif
Adaptive gain computation.
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithDistortion
Perspective projection with distortion model.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
static const vpColor none
static const vpColor yellow
static const vpColor green
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
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 displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
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.
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotati...
Class that defines the translation visual feature .
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
static double distance(const vpImagePoint &iP1, const vpImagePoint &iP2)
Definition of the vpImage class member functions.
static double deg(double rad)
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Implementation of a pose vector and operations on poses.
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())
@ 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.
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
XML parser to load and save intrinsic camera parameters.
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 double measureTimeMs()