RoboDK API for C++ - Documentation
Loading...
Searching...
No Matches
mainwindow.cpp
1#include "mainwindow.h"
2#include "ui_mainwindow.h"
3#include "embedexample.h"
4
5#include <QFileDialog>
6#include <QWindow>
7#include <QStandardPaths>
8
9//#include <QtConcurrent/QtConcurrent>
10
11#ifdef WIN32
12// this is used to integrate RoboDK window as a child window
13#include <windows.h>
14#pragma comment(lib,"user32.lib")
15#endif
16
17//#include <thread>
18
19
20#define M_PI 3.14159265358979323846
21
22MainWindow::MainWindow(QWidget *parent) :
23 QMainWindow(parent),
24 ui(new Ui::MainWindow)
25{
26
27 robodk_window = NULL;
28 ui->setupUi(this);
29 ui->widgetRoboDK->hide();
30 adjustSize();
31
32
33
34 // Start RoboDK API here (RoboDK will start if it is not running)
35 ROBOT = NULL;
36 RDK = new RoboDK();
37 if (!RDK->Connected()){
38 qDebug() << "Failed to start RoboDK API!!";
39 }
40
41}
42
43MainWindow::~MainWindow() {
44 robodk_window_clear();
46 delete ui;
47 delete RDK;
48}
49
51 if (RDK == NULL){
52 statusBar()->showMessage("RoboDK API is not connected");
53 return false;
54 }
55 if (!RDK->Connected()){
56 statusBar()->showMessage("RoboDK is not running");
57 return false;
58 }
59 return true;
60}
61
63 if (!Check_RoboDK()){ return false; }
64
65 if (ROBOT == NULL){
66 statusBar()->showMessage("Select a robot first");
67 return false;
68 }
69 if (!ROBOT->Valid()){
70 statusBar()->showMessage("Robot item is not valid");
71 return false;
72 }
73 return true;
74}
75
77 if (ROBOT != NULL){
78 delete ROBOT;
79 ROBOT = NULL;
80 }
81 ROBOT = new Item(RDK->ItemUserPick("Select a robot", RoboDK::ITEM_TYPE_ROBOT));
82 //ROBOT = new Item(RDK->getItem("UR10", RoboDK::ITEM_TYPE_ROBOT));
83 if (Check_Robot()){
84 statusBar()->showMessage("Robot selected: " + ROBOT->Name());
85 }
86}
87
88void MainWindow::on_btnLoadFile_clicked() {
89 if (!Check_RoboDK()){ return; }
90
91 QStringList files = QFileDialog::getOpenFileNames(this, tr("Open one or more files with RoboDK"));
92 foreach (QString file, files){
93 qDebug() << "Loading: " << file;
94 RDK->AddFile(file);
95 }
96
97 if (!Check_Robot()){
99 }
100}
101
102void MainWindow::on_btnSelectRobot_clicked(){
103 Select_Robot();
104}
105
106
107void MainWindow::on_btnGetPosition_clicked(){
108 if (!Check_Robot()){ return; }
109
110 QString separator = " , ";
111 int decimals = 1;
112
113 // Get robot joints
114 tJoints joints(ROBOT->Joints());
115 QString joints_str = joints.ToString(separator, decimals);
116 ui->txtJoints->setText(joints_str);
117
118 // Get robot pose
119 Mat robot_pose(ROBOT->Pose());
120 QString pose_str = robot_pose.ToString(separator, decimals, true);
121 ui->txtXYZWPR->setText(pose_str);
122}
123
124void MainWindow::on_btnMoveJoints_clicked(){
125 if (!Check_Robot()){ return; }
126
127 tJoints joints;
128
129 joints.FromString(ui->txtJoints->text());
130
131 bool blocking = true;
132
133 ROBOT->MoveJ(joints, blocking);
134
135}
136
137void MainWindow::on_btnMovePose_clicked(){
138 if (!Check_Robot()){ return; }
139
140 Mat pose;
141
142 pose.FromString(ui->txtXYZWPR->text());
143
144 bool blocking = true;
145
146 ROBOT->MoveJ(pose, blocking);
147
148}
149
150void MainWindow::on_btnProgRun_clicked(){
151 if (!Check_Robot()){ return; }
152
153 QString program_name = ui->txtProgName->text();
154
155 RDK->RunProgram(program_name);
156}
157
158// Example to run a second instance of the RoboDK api in parallel:
159// make sure to include #include <thread>
160//std::thread *t1 = new std::thread(blocking_task);
161/*
162void blocking_task(){
163 RoboDK rdk; // important! It will not block the main thread (blocking or non blocking won'T make a difference)
164
165 // show the blocking popup:
166 rdk.Popup_ISO9283_CubeProgram();
167
168}
169*/
170
171// then, start the thread and let it finish once the user finishes with the popup
172void MainWindow::on_btnTestButton_clicked(){
173
174 // example to listen to events
175 // QtConcurrent::run(this, &MainWindow::EventsLoop);
176 //RDK->EventsLoop();
177
178
179 if (!Check_Robot()){ return; }
180
181 /*
182 if (false) {
183 //ROBOT->setPose
184 Item robot_base = ROBOT->Parent();
185
186 // Create or select a reference frame
187 Item ref = RDK->getItem("Ref 1");
188 if (!ref.Valid()){
189 ref = RDK->AddFrame("Ref 1", &robot_base);
190 ref.setPose(Mat::transl(100,200,300));
191 }
192
193 // create or load a tool
194 Item tcp = RDK->getItem("Tool 1");
195 if (!tcp.Valid()){
196 tcp = ROBOT->AddTool(Mat::transl(0,0,150)*Mat::rotx(0.5*M_PI), "Tool 1");
197 }
198
199 // Set the robot base and tool
200 ROBOT->setPoseFrame(ref);
201 ROBOT->setPoseTool(tcp);
202
203 Mat TargetPose = ROBOT->Pose();
204
205 RDK->Render();
206
207 Item prog = RDK->AddProgram("AutomaticProg", ROBOT);
208 prog.setPoseFrame(ref);
209 prog.setPoseTool(tcp);
210
211 //Create a target (or select it)
212 for (int i=0; i<=100; i++){
213 QString target_name(QString("Target %1").arg(i+1));
214 Item target = RDK->getItem(target_name, RoboDK::ITEM_TYPE_TARGET);
215 if (!target.Valid()){
216 target = RDK->AddTarget(target_name, &ref);
217 target.setAsCartesianTarget();
218 target.setPose(TargetPose * transl(0,0, 2*i) * rotz((i/100.0)*30.0*M_PI/180.0));
219 if (i == 0){
220 prog.MoveJ(target);
221 } else {
222 prog.MoveL(target);
223 }
224 }
225 }
226 }
227
228 // manage a gripper
229 if (false){
230 //RDK->getItem("");
231 Item gripper = ROBOT->Childs()[0];
232
233 tJoints joints_original = gripper.Joints();
234
235 double pjoints[] = {0};
236 tJoints joints_new(pjoints, 1);
237 gripper.setJoints(joints_new);
238
239 gripper.MoveJ(joints_original);
240 }
241
242 //target.Delete();
243
244 // example to display text in the 3D window
245 if (true){
246 Item station = RDK->getActiveStation();
247 Item text_object = RDK->AddFile("", &station);
248 text_object.setPose(transl(200,300,100));
249 //text_object.setPoseAbs(transl(200,300,100));
250 text_object.setName("Display 3D text");
251 }
252
253 // Other useful functions to draw primitives
254 //RDK->AddShape()
255 //RDK->AddCurve()
256 //RDK->AddPoints()
257
258
259 return;
260*/
261
262
263
264 //int runmode = RDK->RunMode(); // retrieve the run mode
265
266 //RoboDK *RDK = new RoboDK();
267 //Item *ROBOT = new Item(RDK->getItem("Motoman SV3"));
268
269 // Draw a hexagon inside a circle of radius 100.0 mm
270 int n_sides = 6;
271 float size = 100.0;
272 // retrieve the reference frame and the tool frame (TCP)
273 Mat pose_frame = ROBOT->PoseFrame();
274 Mat pose_tool = ROBOT->PoseTool();
275 Mat pose_ref = ROBOT->Pose();
276
277 // Program start
278 ROBOT->MoveJ(pose_ref);
279 ROBOT->setPoseFrame(pose_frame); // set the reference frame
280 ROBOT->setPoseTool(pose_tool); // set the tool frame: important for Online Programming
281 ROBOT->setSpeed(100); // Set Speed to 100 mm/s
282 ROBOT->setRounding(5); // set the rounding instruction (C_DIS & APO_DIS / CNT / ZoneData / Blend Radius / ...)
283 ROBOT->RunInstruction("CallOnStart"); // run a program
284 for (int i = 0; i <= n_sides; i++) {
285 // calculate angle in degrees:
286 double angle = ((double) i / n_sides) * 360.0;
287
288 // create a pose relative to the pose_ref
289 Mat pose_i(pose_ref);
290 pose_i.rotate(angle,0,0,1.0);
291 pose_i.translate(size, 0, 0);
292 pose_i.rotate(-angle,0,0,1.0);
293
294 // add a comment (when generating code)
295 ROBOT->RunInstruction("Moving to point " + QString::number(i), RoboDK::INSTRUCTION_COMMENT);
296
297 // example to retrieve the pose as Euler angles (X,Y,Z,W,P,R)
298 double xyzwpr[6];
299 pose_i.ToXYZRPW(xyzwpr);
300
301 ROBOT->MoveL(pose_i); // move the robot
302 }
303 ROBOT->RunInstruction("CallOnFinish");
304 ROBOT->MoveL(pose_ref); // move back to the reference point
305
306 return;
307
308
309 // Example to iterate through all the existing targets in the station (blocking):
310 QList<Item> targets = RDK->getItemList(RoboDK::ITEM_TYPE_TARGET);
311 foreach (Item target, targets){
312 if (target.Type() == RoboDK::ITEM_TYPE_TARGET){
313 ui->statusBar->showMessage("Moving to: " + target.Name());
314 qApp->processEvents();
315 ROBOT->MoveJ(target);
316 }
317 }
318 return;
319
320 QList<Item> list = RDK->getItemList();
321
322
323 Mat pose_robot_base_abs = ROBOT->PoseAbs();
324 Mat pose_robot = ROBOT->Pose();
325 Mat pose_tcp = ROBOT->PoseTool();
326
327 qDebug() << "Absolute Position of the robot:";
328 qDebug() << pose_robot_base_abs;
329
330 qDebug() << "Current robot position (active tool with respect to the active reference):";
331 qDebug() << pose_robot;
332
333 qDebug() << "Position of the active TCP:";
334 qDebug() << pose_tcp;
335
336 QList<Item> tool_list = ROBOT->Childs();
337 if (tool_list.length() <= 0){
338 statusBar()->showMessage("No tools available for the robot " + ROBOT->Name());
339 return;
340 }
341
342 Item tool = tool_list.at(0);
343 qDebug() << "Using tool: " << tool.Name();
344
345 Mat pose_robot_flange_abs = tool.PoseAbs();
346 pose_tcp = tool.PoseTool();
347 Mat pose_tcp_abs = pose_robot_flange_abs * pose_tcp;
348
349
351 Mat pose_object_abs = object.PoseAbs();
352 qDebug() << pose_tcp;
353
354 Mat tcp_wrt_obj = pose_object_abs.inverted() * pose_tcp_abs;
355
356 qDebug() << "Pose of the TCP with respect to the selected reference frame";
357 qDebug() << tcp_wrt_obj;
358
359 tXYZWPR xyzwpr;
360 tcp_wrt_obj.ToXYZRPW(xyzwpr);
361
362 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) );
363
364
365 // Example to define a reference frame given 3 points:
366 tMatrix2D* framePts = Matrix2D_Create();
367 Matrix2D_Set_Size(framePts, 3, 3);
368 double *p1 = Matrix2D_Get_col(framePts, 0);
369 double *p2 = Matrix2D_Get_col(framePts, 1);
370 double *p3 = Matrix2D_Get_col(framePts, 2);
371
372 // Define point 1:
373 p1[0] = 100;
374 p1[1] = 200;
375 p1[2] = 300;
376
377 // Define point 2:
378 p2[0] = 500;
379 p2[1] = 200;
380 p2[2] = 300;
381
382 // Define point 3:
383 p3[0] = 100;
384 p3[1] = 500;
385 p3[2] = 300;
387 Item localPlaneFrame = RDK->AddFrame("Plane Coord");
388 localPlaneFrame.setPose(diagLocalFrame);
389 Matrix2D_Delete(&framePts);
390 return;
391
392
393
394
395 // Inverse kinematics test:
396 //Mat tool_pose = transl(10,20,30);
397 //Mat ref_pose = transl(100, 100,500);
398
399 qDebug() << "Testing pose:";
400 qDebug() << "Using robot: " << ROBOT;
401 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);
403 pose_test.MakeHomogeneous();
404 qDebug() << pose_test;
405
406 // Calculate a single solution (closest to the current robot position):
407 tJoints joints = ROBOT->SolveIK(pose_test); //, &tool_pose, &ref_pose);
408 qDebug() << "Solution : " << joints;
409
410 // Iterate through all possible solutions
411 // Calculate all nominal solutions:
413 auto all_solutions = ROBOT->SolveIK_All(pose_test); //, &tool_pose, &ref_pose);
414 // Use accurate kinematics and calculate inverse kinematics using the closest point
416 for (int i=0; i<all_solutions.length(); i++){
417 tJoints joints_nominal_i = all_solutions.at(i);
418 qDebug() << "Nominal solution " << i << ": " << joints_nominal_i;
419 tJoints joints_accurate_i = ROBOT->SolveIK(pose_test, joints_nominal_i); //, &tool_pose, &ref_pose);
420 qDebug() << "Accurate solution " << i << ": " << joints_accurate_i;
421 }
422
423
424
425
426 /*qDebug() << joints.ToString();
427 tJoints joints = ROBOT->SolveIK(pose_problems);
428 qDebug() << joints.ToString();
429 */
430 return;
431
432
433 /*
434 // Example to create the ISO cube program
435 tXYZ xyz;
436 xyz[0] = 100;
437 xyz[1] = 200;
438 xyz[2] = 300;
439 RDK->Popup_ISO9283_CubeProgram(ROBOT, xyz, 100, false);
440 return;
441 */
442
443}
444
445void MainWindow::on_btnTXn_clicked(){ IncrementalMove(0, -1); }
446void MainWindow::on_btnTYn_clicked(){ IncrementalMove(1, -1); }
447void MainWindow::on_btnTZn_clicked(){ IncrementalMove(2, -1); }
448void MainWindow::on_btnRXn_clicked(){ IncrementalMove(3, -1); }
449void MainWindow::on_btnRYn_clicked(){ IncrementalMove(4, -1); }
450void MainWindow::on_btnRZn_clicked(){ IncrementalMove(5, -1); }
451
452void MainWindow::on_btnTXp_clicked(){ IncrementalMove(0, +1); }
453void MainWindow::on_btnTYp_clicked(){ IncrementalMove(1, +1); }
454void MainWindow::on_btnTZp_clicked(){ IncrementalMove(2, +1); }
455void MainWindow::on_btnRXp_clicked(){ IncrementalMove(3, +1); }
456void MainWindow::on_btnRYp_clicked(){ IncrementalMove(4, +1); }
457void MainWindow::on_btnRZp_clicked(){ IncrementalMove(5, +1); }
458
459void MainWindow::IncrementalMove(int id, double sense){
460 if (!Check_Robot()) { return; }
461
462 // check the index
463 if (id < 0 || id >= 6){
464 qDebug()<< "Invalid id provided to for an incremental move";
465 return;
466 }
467
468 // calculate the relative movement
469 double step = sense * ui->spnStep->value();
470
471 // apply to XYZWPR
472 tXYZWPR xyzwpr;
473 for (int i=0; i<6; i++){
474 xyzwpr[i] = 0;
475 }
476 xyzwpr[id] = step;
477
478 Mat pose_increment;
479 pose_increment.FromXYZRPW(xyzwpr);
480
481 Mat pose_robot = ROBOT->Pose();
482
483 Mat pose_robot_new;
484
485 // apply relative to the TCP:
486 pose_robot_new = pose_robot * pose_increment;
487
488 ROBOT->MoveJ(pose_robot_new);
489
490}
491
492
493
494
495
496void MainWindow::on_radSimulation_clicked()
497{
498 if (!Check_Robot()) { return; }
499
500 // Important: stop any previous program generation (if we selected offline programming mode)
501 ROBOT->Finish();
502
503 // Set simulation mode
505}
506
507void MainWindow::on_radOfflineProgramming_clicked()
508{
509 if (!Check_Robot()) { return; }
510
511 // Important: stop any previous program generation (if we selected offline programming mode)
512 ROBOT->Finish();
513
514 // Set simulation mode
516
517 // specify a program name, a folder to save the program and a post processor if desired
518 RDK->ProgramStart("NewProgram");
519}
520
521void MainWindow::on_radRunOnRobot_clicked()
522{
523 if (!Check_Robot()) { return; }
524
525 // Important: stop any previous program generation (if we selected offline programming mode)
526 ROBOT->Finish();
527
528 // Connect to real robot
529 if (ROBOT->Connect())
530 {
531 // Set simulation mode
533 }
534 else
535 {
536 ui->statusBar->showMessage("Can't connect to the robot. Check connection and parameters.");
537 }
538
539}
540
541void MainWindow::on_btnMakeProgram_clicked()
542{
543 if (!Check_Robot()) { return; }
544
545 // Trigger program generation
546 ROBOT->Finish();
547
548}
549
550
551
552void MainWindow::robodk_window_clear(){
553 if (robodk_window != NULL){
554 robodk_window->setParent(NULL);
555 robodk_window->setFlags(Qt::Window);
556 //robodk_window->deleteLater();
557 robodk_window = NULL;
558 ui->widgetRoboDK->layout()->deleteLater();
559 }
560 // Make sure RoboDK widget is hidden
561 ui->widgetRoboDK->hide();
562
563 // Adjust the main window size
564 adjustSize();
565}
566
567
568void MainWindow::on_radShowRoboDK_clicked()
569{
570 if (!Check_RoboDK()){ return; }
571
572 // Hide embedded window
573 robodk_window_clear();
574
577}
578
579void MainWindow::on_radHideRoboDK_clicked()
580{
581 if (!Check_RoboDK()){ return; }
582
583 // Hide embedded window
584 robodk_window_clear();
585
587
588}
589
590#ifdef _MSC_VER
591HWND FindTopWindow(DWORD pid)
592{
593 std::pair<HWND, DWORD> params = { 0, pid };
594
595 // Enumerate the windows using a lambda to process each window
596 BOOL bResult = EnumWindows([](HWND hwnd, LPARAM lParam) -> BOOL
597 {
598 auto pParams = (std::pair<HWND, DWORD>*)(lParam);
599
600 DWORD processId;
601 if (GetWindowThreadProcessId(hwnd, &processId) && processId == pParams->second)
602 {
603 // Stop enumerating
604 SetLastError(-1);
605 pParams->first = hwnd;
606 return FALSE;
607 }
608
609 // Continue enumerating
610 return TRUE;
611 }, (LPARAM)&params);
612
613 if (!bResult && GetLastError() == -1 && params.first)
614 {
615 return params.first;
616 }
617
618 return 0;
619}
620#endif
621
622void MainWindow::on_radIntegrateRoboDK_clicked()
623{
624 if (!Check_RoboDK()){ return; }
625
626 qint64 procWID = RDK->ProcessID();
627 if (procWID == 0) {
628 ui->statusBar->showMessage("Invalid handle. Close RoboDK and open RoboDK with this application");
629 return;
630 }
631
632
633#ifdef _MSC_VER
634 if (procWID != 0){
635 qDebug() << "Using parent process=" << procWID;
636 //SetParent((HWND) procWID, (HWND)widget_container->window()->winId());
637
638 // Retrieve the top level window
639 HWND wid_rdk = FindTopWindow(procWID);
640 qDebug() << "HWND RoboDK window: " << wid_rdk;
641 //SetParent((HWND) wid_rdk, (HWND)widget_container->winId());//->window()->winId());
642 if (wid_rdk == NULL){
643 ui->statusBar->showMessage("RoboDK top level window was not found...");
644 return;
645 }
646 //HWND wid_rdk = (HWND) RDK->WindowID();
647 // set parent widget
648 robodk_window = QWindow::fromWinId((WId)wid_rdk);
649 QWidget *new_widget = createWindowContainer(robodk_window);
650 QVBoxLayout *vl = new QVBoxLayout();
651 ui->widgetRoboDK->setLayout(vl);
652 vl->addWidget(new_widget);
653 new_widget->show();
654 this->adjustSize();
655
658
659 // Show the RoboDK widget (embedded screen)
660 ui->widgetRoboDK->show();
661 }
662#endif
663
664}
665
666
667
675{
676 qDebug() << "";
677 qDebug() << "**** New event ****";
678
679 //If this runs in a seperate thread from the api instance thaw sapwned it you won't be able to do
680 //Regular api calls like item.Valid()
681 //if (itm.Valid())
682 //{
683 //qDebug() << " Item: " + itm.Name() + " -> Type: " + itm.Type();
684 //}
685 //else
686 //{
687 //Console.WriteLine(" Item not applicable");
688 //}
689
690 switch (evt)
691 {
692 case RoboDK::EVENT_SELECTION_TREE_CHANGED:
693 qDebug() << "Event: Selection changed (the tree was selected)";
694 break;
695 case RoboDK::EVENT_ITEM_MOVED:
696 qDebug() << "Event: Item Moved";
697 break;
698 case RoboDK::EVENT_REFERENCE_PICKED:
699 qDebug() << "Event: Reference Picked";
700 break;
701 case RoboDK::EVENT_REFERENCE_RELEASED:
702 qDebug() << "Event: Reference Released";
703 break;
704 case RoboDK::EVENT_TOOL_MODIFIED:
705 qDebug() << "Event: Tool Modified";
706 break;
707 case RoboDK::EVENT_3DVIEW_MOVED:
708 qDebug() << "Event: 3D view moved"; // use ViewPose to retrieve the pose of the camera
709 break;
710 case RoboDK::EVENT_ROBOT_MOVED:
711 qDebug() << "Event: Robot moved";
712 break;
713
714 // Important: The following events require consuming additional data from the _COM_EVT buffer
715 case RoboDK::EVENT_SELECTION_3D_CHANGED:
716 {
717 qDebug() << "Event: Selection changed";
718 // data contains the following information (24 values):
719 // pose (16), xyz selection (3), ijk normal (3), picked feature id (1), picked id (1)
720 //double[] data = RDK._recv_Array(RDK->_COM_EVT);
721 double data[24];
722 int valueCount;
723 RDK->Event_Receive_3D_POS(data,&valueCount);
724 //
725 Mat pose_abs = Mat(data);
726 double xyz[3] = { data[16], data[17], data[18] };
727 double ijk[3] = { data[19], data[20], data[21] };
728 int feature_type = data[22];
729 int feature_id = data[23];
730 qDebug() << "Additional event data - Absolute position (PoseAbs):";
731 qDebug() << pose_abs.ToString();
732 qDebug() << "Additional event data - Point and Normal (point selected in relative coordinates)";
733 qDebug() << QString::number(xyz[0]) + "," + QString::number(xyz[1]) + "," + QString::number(xyz[2]);
734 qDebug() << QString::number(ijk[0]) + "," + QString::number(ijk[1]) + "," + QString::number(ijk[2]);
735 qDebug() << "Feature Type and ID";
736 qDebug() << QString::number(feature_type) + "-" + QString::number(feature_id);
737 break;
738 }
739 case RoboDK::EVENT_KEY:
740 {
741 int mouseData[3];
742 RDK->Event_Receive_Mouse_data(mouseData);
743 int key_press = mouseData[0]; // 1 = key pressed, 0 = key released
744 int key_id = mouseData[1]; // Key id as per Qt mappings: https://doc.qt.io/qt-5/qt.html#Key-enum
745 int modifiers = mouseData[2]; // Modifier bits as per Qt mappings: https://doc.qt.io/qt-5/qt.html#KeyboardModifier-enum
746 qDebug() << "Event: Key pressed: " + QString::number(key_id) + " " + ((key_press > 0) ? "Pressed" : "Released") + ". Modifiers: " + QString::number(modifiers);
747 break;
748 }
749 case RoboDK::EVENT_ITEM_MOVED_POSE:
750 {
751 Mat pose_rel;
752 bool flag = RDK->Event_Receive_Event_Moved(&pose_rel);
753 //int nvalues = _recv_Int(_COM_EVT);
754 //Mat pose_rel = _recv_Pose(_COM_EVT);
755 if (flag == false)
756 {
757 // future compatibility
758 }
759 qDebug() << "Event: item moved. Relative pose: " + pose_rel.ToString();
760 break;
761 }
762 default:
763 qDebug() << "Unknown event " + QString::number(evt);
764 break;
765 }
766 return true;
767}
768
769bool MainWindow::EventsLoop()
770{
771 RDK->EventsListen();
772
773 qDebug() << "Events loop started";
774 while (RDK->Event_Connected())
775 {
776 int evt;
777 Item itm;
778 RDK->WaitForEvent(evt,itm);
779 SampleRoboDkEvent(evt, itm);
780 }
781 qDebug() << "Event loop finished";
782 return true;
783}
784
785
786
787
788void MainWindow::on_btnEmbed_clicked()
789{
790 if (!Check_RoboDK()){ return; }
791 on_radShowRoboDK_clicked();
792 EmbedExample *newWindow = new EmbedExample();
793 newWindow->show();
794 QString windowName = newWindow->windowTitle();
795 qDebug() << windowName;
796 RDK->EmbedWindow(windowName);
797
798}
799
800void MainWindow::on_btnTestCamera_clicked(){
801 Item reference = RDK->ItemUserPick("Pick a coordinate system to attach the camera", RoboDK::ITEM_TYPE_FRAME);
802 if (!reference.Valid()){
803 qDebug() << "No item selected or available";
804 return;
805 }
806
807 // Get or set the camera location (reference it is linked to):
808 //Mat pose_rel = reference.Pose(); // get current pose (relative, with respect to parent)
809 //Mat pose_abs = reference.PoseAbs(); // get current pose (absolute, with respect to station reference)
810 //reference.setPose(transl(100,200,300) * rotz(M_PI));
811
812 // Set camera parameters so that it takes Full HD snapshot images and black background
813 QString cam_params = "NEAR_LENGTH=5 FAR_LENGTH=100000 FOV=30 SNAPSHOT=1920x1080 NO_TASKBAR BG_COLOR=black";
814 Item cam_item = RDK->Cam2D_Add(reference, cam_params);
815 QString image_file = QStandardPaths::writableLocation(QStandardPaths::DesktopLocation) + "/Camera-Snapshot.png";
816 int success = RDK->Cam2D_Snapshot(image_file, cam_item);
817 if (success == 0){
818 qDebug() << "Failed to save image to: " << image_file;
819 } else {
820 qDebug() << "Snapshot saved successfully: " << image_file;
821 }
822}
Example's main window (robot panel)
Definition mainwindow.h:21
void Select_Robot()
Select a robot.
Item * ROBOT
Pointer to the robot item.
Definition mainwindow.h:87
void IncrementalMove(int id, double sense)
Apply an incremental movement.
QWindow * robodk_window
Pointer to the RoboDK window.
Definition mainwindow.h:90
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.
Definition mainwindow.h:84
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...
Definition robodk_api.h:505
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 ...
Definition robodk_api.h:761
@ ITEM_TYPE_ROBOT
Item of type robot (.robot file).
@ ITEM_TYPE_TARGET
Target item.
@ ITEM_TYPE_FRAME
Item of type reference frame.
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...
@ INSTRUCTION_COMMENT
Comment output.
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...
@ CALIBRATE_FRAME_3P_P1_ON_X
Calibrate by 3 points: [X, X+, Y+] (p1 on X axis).
int Cam2D_Snapshot(const QString &file_save_img, const Item &cam_item, const QString &params="")
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...
@ WINDOWSTATE_NORMAL
Display the RoboDK window in a normal state (not maximized)
@ WINDOWSTATE_FULLSCREEN_CINEMA
Display RoboDK in cinema mode and fullscreen.
@ WINDOWSTATE_HIDDEN
Hide the RoboDK window. RoboDK will keep running as a process.
@ WINDOWSTATE_SHOW
Display the RoboDK window.
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...
@ RUNMODE_RUN_ROBOT
Moves the real robot from the PC (PC is the client, the robot behaves like a server).
@ RUNMODE_MAKE_ROBOTPROG
Makes the robot program.
@ RUNMODE_SIMULATE
Performs the simulation moving the robot (default)
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).
Definition robodk_api.h:385
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)
Definition robodk_api.h:297
The tMatrix2D struct represents a variable size 2d Matrix. Use the Matrix2D_... functions to oeprate ...
Definition robodk_api.h:362