Example of eye-in-hand pose-based control law. We control here the Afma6 robot at Inria. The velocity is computed in the camera frame. Visual features correspond to the 3D pose of the target (a known of object, for which we have the 3D model) in the camera frame.
The device used to acquire images is a Realsense D435 device. Camera intrinsic parameters are retrieved from the Realsense SDK.
The target is an object for which we have the 3D model (in .obj format). We use MegaPose to estimate the object pose in the camera frame, which we plug into the Pose-Based control law.
This example was used to validate Megapose: as such, we provide the initial and desired poses in world frame and use megapose to match them with the object's pose in the camera at the initial and desired locations. Thus, this example takes as input two pose files, acquired with Afma6_office, where the poses are expressed in the world frame. The robot is then moved to these poses and Megapose is used to estimate the object pose in the camera frames. The object detection in the image is performed by click. This allows to compare the ground truth pose error (computed in world frame) with the one estimated thanks to megapose.
In a more practical example, the desired pose would directly be given in the camera frame (as used by megapose) and the robot would thus not need to move to the desired pose before actually servoing.
where init.pos and desired.pos are files obtained through Afma6_office, and myObjectName is the name of an object known by the megapose server.
#include <iostream>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpConfig.h>
#include <visp3/detection/vpDetectorAprilTag.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayX.h>
#include <visp3/gui/vpPlot.h>
#include <visp3/io/vpImageIo.h>
#include <visp3/robot/vpRobotAfma6.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>
#include <visp3/core/vpImageFilter.h>
#include <visp3/io/vpVideoWriter.h>
#if defined(VISP_HAVE_REALSENSE2) && ((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L))) && \
(defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI)) && defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_MODULE_DNN_TRACKER)
#include <optional>
#include <visp3/io/vpJsonArgumentParser.h>
#include <visp3/dnn_tracker/vpMegaPoseTracker.h>
#ifdef VISP_HAVE_NLOHMANN_JSON
using json = nlohmann::json;
#endif
#ifdef ENABLE_VISP_NAMESPACE
#endif
std::optional<vpRect> detectObjectForInitMegaposeClick(
const vpImage<vpRGBa> &I)
{
if (startLabelling) {
vpRect bb(topLeft, bottomRight);
return bb;
}
else {
return std::nullopt;
}
}
int main(int argc, const char *argv[])
{
bool opt_verbose = true;
bool opt_plot = true;
double convergence_threshold_t = 0.0005;
double convergence_threshold_tu = 0.5;
unsigned width = 640, height = 480;
std::string megaposeAddress = "127.0.0.1";
unsigned megaposePort = 5555;
int refinerIterations = 1, coarseNumSamples = 1024;
std::string objectName = "";
std::string desiredPosFile = "desired.pos";
std::string initialPosFile = "init.pos";
#ifdef VISP_HAVE_NLOHMANN_JSON
vpJsonArgumentParser parser(
"Pose-based visual servoing with Megapose on an Afma6, with a Realsense D435.",
"--config",
"/");
parser
.addArgument("initialPose", initialPosFile, true, "Path to the file that contains that the desired pose. Can be acquired with Afma6_office.")
.addArgument("desiredPose", desiredPosFile, true, "Path to the file that contains that the desired pose. Can be acquired with Afma6_office.")
.addArgument("object", objectName, true, "Name of the object to track with megapose.")
.addArgument("megapose/address", megaposeAddress, true, "IP address of the Megapose server.")
.addArgument("megapose/port", megaposePort, true, "Port on which the Megapose server listens for connections.")
.addArgument("megapose/refinerIterations", refinerIterations, false, "Number of Megapose refiner model iterations."
"A higher count may lead to better accuracy, at the cost of more processing time")
.addArgument("megapose/initialisationNumSamples", coarseNumSamples, false, "Number of Megapose renderings used for the initial pose estimation.");
parser.parse(argc, argv);
#endif
try {
std::cout << "WARNING: This example will move the robot! "
<< "Please make sure to have the user stop button at hand!" << std::endl
<< "Press Enter to continue..." << std::endl;
std::cin.ignore();
std::vector<vpColVector> velocities;
std::vector<vpPoseVector> error;
robot.setPositioningVelocity(10.0);
robot.readPosFile(desiredPosFile, q);
std::cout << "Move to joint position: " << q.t() << std::endl;
rs2::config config;
config.enable_stream(RS2_STREAM_COLOR, width, height, RS2_FORMAT_RGBA8, 30);
std::cout << "cam:\n" << cam << std::endl;
std::shared_ptr<vpMegaPose> megapose;
try {
megapose = std::make_shared<vpMegaPose>(megaposeAddress, megaposePort, cam, height, width);
}
catch (...) {
}
megapose->setCoarseNumSamples(coarseNumSamples);
const std::vector<std::string> allObjects = megapose->getObjectNames();
if (std::find(allObjects.begin(), allObjects.end(), objectName) == allObjects.end()) {
}
std::future<vpMegaPoseEstimate> trackerFuture;
#if defined(VISP_HAVE_X11)
vpDisplayX dc(I, 10, 10, "Color image");
#elif defined(VISP_HAVE_GDI)
#endif
std::optional<vpRect> detection;
while (!detection) {
detection = detectObjectForInitMegaposeClick(I);
}
robot.readPosFile(initialPosFile, q);
std::cout << "Move to joint position: " << q.t() << std::endl;
detection = std::nullopt;
while (!detection) {
detection = detectObjectForInitMegaposeClick(I);
}
auto est = megaposeTracker.init(I, *detection).get();
std::cout << "Estimate score = " << est.score << std::endl;
t.buildFrom(cdTc);
tu.buildFrom(cdTc);
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, 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 callMegapose = true;
while (!has_converged && !final_quit) {
if (!callMegapose && trackerFuture.wait_for(std::chrono::milliseconds(0)) == std::future_status::ready) {
megaposeEstimate = trackerFuture.get();
cTo = megaposeEstimate.
cTo;
callMegapose = true;
if (megaposeEstimate.
score < 0.2) {
final_quit = true;
std::cout << "Low confidence, exiting" << std::endl;
}
}
if (callMegapose) {
std::cout << "Calling megapose" << std::endl;
trackerFuture = megaposeTracker.track(I);
callMegapose = false;
}
std::stringstream ss;
ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
velocities.push_back(v);
cTw = robot.get_fMc(q).inverse();
error.push_back(cdrc);
if (opt_plot) {
plotter->
plot(1, iter_plot, v);
iter_plot++;
}
if (opt_verbose) {
std::cout << "v: " << v.t() << std::endl;
}
double error_tr_true = sqrt(cd_t_c_true.
sumSquare());
ss.str("");
ss << "Predicted error_t: " << error_tr << ", True error_t:" << error_tr_true;
ss.str("");
ss << "Predicted error_tu: " << error_tu << ", True error_tu:" << error_tu_true;
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;
}
ss.str("");
switch (button) {
send_velocities = !send_velocities;
break;
final_quit = true;
v = 0;
break;
default:
break;
}
}
}
std::cout << "Stop the robot " << std::endl;
#ifdef VISP_HAVE_NLOHMANN_JSON
json j = json {
{"velocities", velocities},
{"error", error}
};
std::ofstream jsonFile;
jsonFile.open("results.json");
jsonFile << j.dump(4);
jsonFile.close();
#endif
if (opt_plot && plotter != nullptr) {
delete plotter;
plotter = nullptr;
}
if (!final_quit) {
while (!final_quit) {
final_quit = true;
}
}
}
}
std::cout <<
"ViSP exception: " << e.
what() << std::endl;
std::cout << "Stop the robot " << std::endl;
return EXIT_FAILURE;
}
catch (const std::exception &e) {
std::cout << "ur_rtde exception: " << e.what() << std::endl;
return EXIT_FAILURE;
}
return EXIT_SUCCESS;
}
#else
int main()
{
#if !defined(VISP_HAVE_REALSENSE2)
std::cout << "Install librealsense-2.x" << std::endl;
#endif
#if !((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
std::cout << "Build ViSP with c++17 or higher compiler flag (cmake -DUSE_CXX_STANDARD=17)." << std::endl;
#endif
#if !defined(VISP_HAVE_AFMA6)
std::cout << "ViSP is not built with Afma-6 robot support..." << std::endl;
#endif
return EXIT_SUCCESS;
}
#endif
Generic class defining intrinsic camera parameters.
@ perspectiveProjWithoutDistortion
Perspective projection without distortion model.
Implementation of column vector and the associated operations.
static const vpColor none
static const vpColor yellow
Display for windows using GDI (available on any windows 32 platform).
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
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 getImage(const vpImage< unsigned char > &Is, vpImage< vpRGBa > &Id)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
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.
@ badValue
Used to indicate that a value is not in the allowed range.
const char * what() const
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
Class that defines the translation visual feature .
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpThetaUVector getThetaUVector() const
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
unsigned int getWidth() const
Command line argument parsing with support for JSON files. If a JSON file is supplied,...
static double deg(double rad)
A simplified interface to track a single object with MegaPose. This tracker works asynchronously: A c...
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
void initGraph(unsigned int graphNum, unsigned int curveNbr)
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
void setTitle(unsigned int graphNum, const std::string &title)
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())
Defines a rectangle in the plane.
Control of Irisa's gantry robot named Afma6.
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)
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 setServo(const vpServoType &servo_type)
vpColVector getError() const
vpColVector computeControlLaw()
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
Class that enables to write easily a video file or a sequence of images.
void saveFrame(vpImage< vpRGBa > &I)
void setFileName(const std::string &filename)
void open(vpImage< vpRGBa > &I)
VISP_EXPORT double measureTimeMs()