2#include "ui_mainwindow.h"
3#include "embedexample.h"
7#include <QtConcurrent/QtConcurrent>
12#pragma comment(lib,"user32.lib")
18#define M_PI 3.14159265358979323846
20MainWindow::MainWindow(QWidget *parent) :
27 ui->widgetRoboDK->hide();
35 if (!RDK->Connected()){
36 qDebug() <<
"Failed to start RoboDK API!!";
41MainWindow::~MainWindow() {
42 robodk_window_clear();
50 statusBar()->showMessage(
"RoboDK API is not connected");
53 if (!
RDK->Connected()){
54 statusBar()->showMessage(
"RoboDK is not running");
64 statusBar()->showMessage(
"Select a robot first");
68 statusBar()->showMessage(
"Robot item is not valid");
82 statusBar()->showMessage(
"Robot selected: " +
ROBOT->
Name());
86void MainWindow::on_btnLoadFile_clicked() {
89 QStringList files = QFileDialog::getOpenFileNames(
this, tr(
"Open one or more files with RoboDK"));
90 foreach (QString file, files){
91 qDebug() <<
"Loading: " << file;
100void MainWindow::on_btnSelectRobot_clicked(){
105void MainWindow::on_btnGetPosition_clicked(){
108 QString separator =
" , ";
113 QString joints_str = joints.ToString(separator, decimals);
114 ui->txtJoints->setText(joints_str);
118 QString pose_str = robot_pose.ToString(separator, decimals);
119 ui->txtXYZWPR->setText(pose_str);
122void MainWindow::on_btnMoveJoints_clicked(){
129 bool blocking =
true;
135void MainWindow::on_btnMovePose_clicked(){
142 bool blocking =
true;
148void MainWindow::on_btnProgRun_clicked(){
151 QString program_name = ui->txtProgName->text();
170void MainWindow::on_btnTestButton_clicked(){
173 QtConcurrent::run(
this, &MainWindow::EventsLoop);
282 for (
int i = 0; i <= n_sides; i++) {
284 double angle = ((double) i / n_sides) * 360.0;
287 Mat pose_i(pose_ref);
288 pose_i.rotate(angle,0,0,1.0);
289 pose_i.translate(size, 0, 0);
290 pose_i.rotate(-angle,0,0,1.0);
293 ROBOT->
RunInstruction(
"Moving to point " + QString::number(i), RoboDK::INSTRUCTION_COMMENT);
297 pose_i.ToXYZRPW(xyzwpr);
309 foreach (
Item target, targets){
310 if (target.
Type() == RoboDK::ITEM_TYPE_TARGET){
311 ui->statusBar->showMessage(
"Moving to: " + target.
Name());
312 qApp->processEvents();
325 qDebug() <<
"Absolute Position of the robot:";
326 qDebug() << pose_robot_base_abs;
328 qDebug() <<
"Current robot position (active tool with respect to the active reference):";
329 qDebug() << pose_robot;
331 qDebug() <<
"Position of the active TCP:";
332 qDebug() << pose_tcp;
335 if (tool_list.length() <= 0){
336 statusBar()->showMessage(
"No tools available for the robot " +
ROBOT->
Name());
340 Item tool = tool_list.at(0);
341 qDebug() <<
"Using tool: " << tool.
Name();
345 Mat pose_tcp_abs = pose_robot_flange_abs * pose_tcp;
349 Mat pose_object_abs =
object.PoseAbs();
350 qDebug() << pose_tcp;
352 Mat tcp_wrt_obj = pose_object_abs.inverted() * pose_tcp_abs;
354 qDebug() <<
"Pose of the TCP with respect to the selected reference frame";
355 qDebug() << tcp_wrt_obj;
360 this->statusBar()->showMessage(QString(
"Tool with respect to %1").arg(
object.Name()) + QString(
": [X,Y,Z,W,P,R]=[%1, %2, %3, %4, %5, %6] mm/deg").arg(xyzwpr[0],0,
'f',3).arg(xyzwpr[1],0,
'f',3).arg(xyzwpr[2],0,
'f',3).arg(xyzwpr[3],0,
'f',3).arg(xyzwpr[4],0,
'f',3).arg(xyzwpr[5],0,
'f',3) );
386 localPlaneFrame.
setPose(diagLocalFrame);
397 qDebug() <<
"Testing pose:";
398 qDebug() <<
"Using robot: " <<
ROBOT;
399 Mat pose_test(0.733722985, 0.0145948902, -0.679291904, -814.060547, 0.000000000, -0.999769211, -0.0214804877, -8.96536446, -0.679448724, 0.0157607272, -0.733553648, 340.561951);
401 pose_test.MakeHomogeneous();
402 qDebug() << pose_test;
406 qDebug() <<
"Solution : " << joints;
414 for (
int i=0; i<all_solutions.length(); i++){
415 tJoints joints_nominal_i = all_solutions.at(i);
416 qDebug() <<
"Nominal solution " << i <<
": " << joints_nominal_i;
418 qDebug() <<
"Accurate solution " << i <<
": " << joints_accurate_i;
461 if (id < 0 || id >= 6){
462 qDebug()<<
"Invalid id provided to for an incremental move";
467 double step = sense * ui->spnStep->value();
471 for (
int i=0; i<6; i++){
484 pose_robot_new = pose_robot * pose_increment;
494void MainWindow::on_radSimulation_clicked()
505void MainWindow::on_radOfflineProgramming_clicked()
519void MainWindow::on_radRunOnRobot_clicked()
534 ui->statusBar->showMessage(
"Can't connect to the robot. Check connection and parameters.");
539void MainWindow::on_btnMakeProgram_clicked()
550void MainWindow::robodk_window_clear(){
556 ui->widgetRoboDK->layout()->deleteLater();
559 ui->widgetRoboDK->hide();
566void MainWindow::on_radShowRoboDK_clicked()
571 robodk_window_clear();
577void MainWindow::on_radHideRoboDK_clicked()
582 robodk_window_clear();
589HWND FindTopWindow(DWORD pid)
591 std::pair<HWND, DWORD> params = { 0, pid };
594 BOOL bResult = EnumWindows([](HWND hwnd, LPARAM lParam) -> BOOL
596 auto pParams = (std::pair<HWND, DWORD>*)(lParam);
599 if (GetWindowThreadProcessId(hwnd, &processId) && processId == pParams->second)
603 pParams->first = hwnd;
611 if (!bResult && GetLastError() == -1 && params.first)
620void MainWindow::on_radIntegrateRoboDK_clicked()
624 qint64 procWID =
RDK->ProcessID();
626 ui->statusBar->showMessage(
"Invalid handle. Close RoboDK and open RoboDK with this application");
633 qDebug() <<
"Using parent process=" << procWID;
637 HWND wid_rdk = FindTopWindow(procWID);
638 qDebug() <<
"HWND RoboDK window: " << wid_rdk;
640 if (wid_rdk == NULL){
641 ui->statusBar->showMessage(
"RoboDK top level window was not found...");
648 QVBoxLayout *vl =
new QVBoxLayout();
649 ui->widgetRoboDK->setLayout(vl);
650 vl->addWidget(new_widget);
658 ui->widgetRoboDK->show();
675 qDebug() <<
"**** New event ****";
690 case RoboDK::EVENT_SELECTION_TREE_CHANGED:
691 qDebug() <<
"Event: Selection changed (the tree was selected)";
693 case RoboDK::EVENT_ITEM_MOVED:
694 qDebug() <<
"Event: Item Moved";
696 case RoboDK::EVENT_REFERENCE_PICKED:
697 qDebug() <<
"Event: Reference Picked";
699 case RoboDK::EVENT_REFERENCE_RELEASED:
700 qDebug() <<
"Event: Reference Released";
702 case RoboDK::EVENT_TOOL_MODIFIED:
703 qDebug() <<
"Event: Tool Modified";
705 case RoboDK::EVENT_3DVIEW_MOVED:
706 qDebug() <<
"Event: 3D view moved";
708 case RoboDK::EVENT_ROBOT_MOVED:
709 qDebug() <<
"Event: Robot moved";
713 case RoboDK::EVENT_SELECTION_3D_CHANGED:
715 qDebug() <<
"Event: Selection changed";
721 RDK->Event_Receive_3D_POS(data,&valueCount);
724 double xyz[3] = { data[16], data[17], data[18] };
725 double ijk[3] = { data[19], data[20], data[21] };
726 int feature_type = data[22];
727 int feature_id = data[23];
728 qDebug() <<
"Additional event data - Absolute position (PoseAbs):";
730 qDebug() <<
"Additional event data - Point and Normal (point selected in relative coordinates)";
731 qDebug() << QString::number(xyz[0]) +
"," + QString::number(xyz[1]) +
"," + QString::number(xyz[2]);
732 qDebug() << QString::number(ijk[0]) +
"," + QString::number(ijk[1]) +
"," + QString::number(ijk[2]);
733 qDebug() <<
"Feature Type and ID";
734 qDebug() << QString::number(feature_type) +
"-" + QString::number(feature_id);
737 case RoboDK::EVENT_KEY:
740 RDK->Event_Receive_Mouse_data(mouseData);
741 int key_press = mouseData[0];
742 int key_id = mouseData[1];
743 int modifiers = mouseData[2];
744 qDebug() <<
"Event: Key pressed: " + QString::number(key_id) +
" " + ((key_press > 0) ?
"Pressed" :
"Released") +
". Modifiers: " + QString::number(modifiers);
747 case RoboDK::EVENT_ITEM_MOVED_POSE:
750 bool flag =
RDK->Event_Receive_Event_Moved(&pose_rel);
757 qDebug() <<
"Event: item moved. Relative pose: " + pose_rel.
ToString();
761 qDebug() <<
"Unknown event " + QString::number(evt);
767bool MainWindow::EventsLoop()
771 qDebug() <<
"Events loop started";
772 while (
RDK->Event_Connected())
776 RDK->WaitForEvent(evt,itm);
779 qDebug() <<
"Event loop finished";
786void MainWindow::on_btnEmbed_clicked()
789 on_radShowRoboDK_clicked();
792 QString windowName = newWindow->windowTitle();
793 qDebug() << windowName;
794 RDK->EmbedWindow(windowName);
798void MainWindow::on_btnTestCamera_clicked(){
799 Item reference =
RDK->
ItemUserPick(
"Pick a coordinate system to attach the camera", RoboDK::ITEM_TYPE_FRAME);
800 if (!reference.
Valid()){
801 qDebug() <<
"No item selected or available";
811 QString cam_params =
"NEAR_LENGTH=5 FAR_LENGTH=100000 FOV=30 SNAPSHOT=1920x1080 NO_TASKBAR BG_COLOR=black";
813 QString image_file = QStandardPaths::writableLocation(QStandardPaths::DesktopLocation) +
"/Camera-Snapshot.png";
816 qDebug() <<
"Failed to save image to: " << image_file;
818 qDebug() <<
"Snapshot saved successfully: " << image_file;
Example's main window (robot panel)
void Select_Robot()
Select a robot.
Item * ROBOT
Pointer to the robot item.
void IncrementalMove(int id, double sense)
Apply an incremental movement.
QWindow * robodk_window
Pointer to the RoboDK window.
bool Check_Robot()
Validate if a Robot has been selected (ROBOT variable is valid)
bool SampleRoboDkEvent(int evt, Item itm)
This is a sample function that is executed when a new RoboDK Event occurs.
bool Check_RoboDK()
Validate if RoboDK is running (RDK is valid)
RoboDK * RDK
Pointer to RoboDK.
The Item class represents an item in RoboDK station. An item can be a robot, a frame,...
int RunInstruction(const QString &code, int run_type=RoboDK::INSTRUCTION_CALL_PROGRAM)
Adds a program call, code, message or comment inside a program.
void setSpeed(double speed_linear, double accel_linear=-1, double speed_joints=-1, double accel_joints=-1)
Sets the speed and/or the acceleration of a robot.
bool Connect(const QString &robot_ip="")
Connect to a real robot using the corresponding robot driver.
void setPoseTool(const Mat tool_pose)
Sets the tool of a robot or a tool object (Tool Center Point, or TCP). The tool pose can be either an...
bool Valid(bool check_pointer=false) const
Check if an item is valid (not null and available in the open station)
void setAccuracyActive(int accurate=1)
Sets the accuracy of the robot active or inactive. A robot must have been calibrated to properly use ...
Mat Pose() const
Returns the local position (pose) of an object, target or reference frame. For example,...
int Type() const
Item type (object, robot, tool, reference, robot machining project, ...)
void setPose(const Mat pose)
Sets the local position (pose) of an object, target or reference frame. For example,...
Mat PoseTool()
Returns the tool pose of an item. If a robot is provided it will get the tool pose of the active tool...
void setPoseFrame(const Mat frame_pose)
Sets the reference frame of a robot(user frame). The frame can be either an item or a pose....
void setRounding(double zonedata)
Sets the robot movement smoothing accuracy (also known as zone data value).
tJoints Joints() const
Returns the current joints of a robot or the joints of a target. If the item is a cartesian target,...
Mat PoseFrame()
Returns the reference frame pose of an item. If a robot is provided it will get the tool pose of the ...
Mat PoseAbs()
Returns the global position (pose) of an item. For example, the position of an object/frame/target wi...
QList< tJoints > SolveIK_All(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The function returns all available ...
void MoveJ(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Joint" mode). By default, this function blocks until the ro...
QList< Item > Childs() const
Returns a list of the item childs that are attached to the provided item.
void MoveL(const Item &itemtarget, bool blocking=true)
Moves a robot to a specific target ("Move Linear" mode). By default, this function blocks until the r...
QString Name() const
Returns the name of an item. The name of the item is always displayed in the RoboDK station tree
bool Finish()
Disconnect from the RoboDK API. This flushes any pending program generation.
tJoints SolveIK(const Mat &pose, const Mat *tool=nullptr, const Mat *ref=nullptr)
Computes the inverse kinematics for the specified robot and pose. The joints returned are the closest...
The Mat class represents a 4x4 pose matrix. The main purpose of this object is to represent a pose in...
void FromXYZRPW(tXYZWPR xyzwpr)
Calculates the pose from the position and euler angles ([x,y,z,r,p,w] vector) The result is the same ...
void ToXYZRPW(tXYZWPR xyzwpr) const
Calculates the equivalent position and euler angles ([x,y,z,r,p,w] vector) of the given pose Note: tr...
QString ToString(const QString &separator=", ", int precision=3, bool xyzwpr_only=false) const
Retrieve a string representation of the pose.
bool FromString(const QString &str)
Set the matrix given a XYZRPW string array (6-values)
This class is the iterface to the RoboDK API. With the RoboDK API you can automate certain tasks and ...
Item getItem(QString name, int itemtype=-1)
Returns an item by its name. If there is no exact match it will return the last closest match.
void CloseRoboDK()
Closes RoboDK window and finishes RoboDK execution
void setRunMode(int run_mode=1)
Sets the behavior of the RoboDK API. By default, RoboDK shows the path simulation for movement instru...
Item AddFile(const QString &filename, const Item *parent=nullptr)
Loads a file and attaches it to parent. It can be any file supported by RoboDK.
Item ItemUserPick(const QString &message="Pick one item", int itemtype=-1)
Shows a RoboDK popup to select one object from the open RoboDK station. An item type can be specified...
int Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString ¶ms="")
Take a snapshot of a simulated camera and save it as an image.
int RunProgram(const QString &function_w_params)
Adds a function call in the program output. RoboDK will handle the syntax when the code is generated ...
int ProgramStart(const QString &progname, const QString &defaultfolder="", const QString &postprocessor="", Item *robot=nullptr)
Defines the name of the program when the program is generated. It is also possible to specify the nam...
QList< Item > getItemList(int filter=-1)
Returns a list of items (list of names or pointers) of all available items in the currently open stat...
Mat CalibrateReference(tMatrix2D *poses_joints, int method=CALIBRATE_FRAME_3P_P1_ON_X, bool use_joints=false, Item *robot=nullptr)
Calibrate a Reference Frame given a list of points or joint values. Important: If the robot is calibr...
Item AddFrame(const QString &name, Item *itemparent=nullptr)
Adds a new Frame that can be referenced by a robot.
Item Cam2D_Add(const Item &item_object, const QString &cam_params, const Item *cam_item=nullptr)
Add a simulated 2D or depth camera as an item. Use Delete to delete it.
void setWindowState(int windowstate=WINDOWSTATE_NORMAL)
Set the state of the RoboDK window
The tJoints class represents a joint position of a robot (robot axes).
bool FromString(const QString &str)
Set the joint values given a comma-separated string. Tabs and spaces are also allowed.
double * Matrix2D_Get_col(const tMatrix2D *var, int col)
Returns the pointer of a column of a tMatrix2D. A column has Matrix2D_Get_nrows values that can be ac...
tMatrix2D * Matrix2D_Create()
Creates a new 2D matrix tMatrix2D.. Use Matrix2D_Delete to delete the matrix (to free the memory)....
void Matrix2D_Set_Size(tMatrix2D *mat, int rows, int cols)
Sets the size of a tMatrix2D.
void Matrix2D_Delete(tMatrix2D **mat)
Deletes a tMatrix2D.
double tXYZWPR[6]
Six doubles that represent robot joints (usually in degrees)
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...