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