diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..170be8b --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +*.pro.user +*.sh \ No newline at end of file diff --git a/CHANGELOG b/CHANGELOG new file mode 100644 index 0000000..47c8560 --- /dev/null +++ b/CHANGELOG @@ -0,0 +1,19 @@ +Initial commit of MarkCommander. + +This is the source code for the MarkCommander application as it was handed +in for the Robotics course at ULPGC. This version is the full GUI with +icons, and provides the following functionality: + +* Terminal for sending raw commands to the Mark IV controller. +* Direct kinematics solving, for positioning the end effector by providing + the joint angles. +* Inverse kinematics solving, for positioning the end effector by + providing the coordinates of the TCP (Tool Center Point) and a rotation + matrix that expreses the orientation of the end effector. +* Configuration dialog for configuring the Mark IV controller. + +This version of the application may still have some errors, particularly +in the inverse kinematics, but does a fairly good job and is quite usable. + +The code has been licensed under the terms of the Apache License. + diff --git a/ERRORS b/ERRORS new file mode 100644 index 0000000..5c650ac --- /dev/null +++ b/ERRORS @@ -0,0 +1,7 @@ +* En la configuración del controlador, la opción para habilitar/deshabilitar la pinza no sirve, y la de joint/XYZ mode tampoco. [La de la pinza ahora sí debería servir. En cualquier caso, hay que comprobar ambas, pero ahora sí deberían servir las dos.] +* Hay problemas al conectar signals y slots: + QMetaObject::connectSlotsByName: No matching signal for on_actionApplyConfiguration_triggered() + QMetaObject::connectSlotsByName: No matching signal for on_actionRevertConfiguration_triggered() + QMetaObject::connectSlotsByName: No matching signal for on_actionCloseConfiguration_triggered() +* El programa se queda colgado cuando se intenta salir, y la única forma de cerrarlo es matar el proceso (pero sólo pasa a veces). +* Las funciones "moveMotor" tienen un error: hay que convertir los ángulos a pasos y los pasos a grados [está corregido, pero conviene revisar que está bien hecho]. diff --git a/INFO b/INFO new file mode 100644 index 0000000..dbcbe36 --- /dev/null +++ b/INFO @@ -0,0 +1,4 @@ +* Tras la revisión 20, se volvió a la revisión 19 para eliminar el Segmentation Fault, pero parece ser que el Segmentation Fault no se debía a los cambios hechos para implementar el editor, sino a algún problema con el puerto serie (por ejemplo, la ausencia de un controlador Mark IV). [Al menos en Windows 7 y en la máquina de Windows XP. En el laboratorio la revisión 20 también daba un Segmentation Fault, pero no pude probar la revisión 19.] + Ayer me funcionaba esta revisión (con lo de la configuración y todo), y hoy me da el segmentation fault (>.<) Da cuando se abre el puerto serie en la clase 'Terminal' (en el método de QextSerialPort), así que parece que no es problema mío, sino de QextSerialport (o del SO), porque en el programa de la entrega 1 (revisión 19) no da el segmentation fault. + Me he pasado a un portátil, y ya no da el segmentation fault. Debía ser por culpa del puerto serie en el PC host. + Ahora en Windows 7 tampoco peta. ¿Puede que fuera que en la versión "debug" de MarkCommander se estaba usando la compilación "release" de QextSerialPort? \ No newline at end of file diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..7895e01 --- /dev/null +++ b/LICENSE @@ -0,0 +1,13 @@ +Copyright 2011 Jonan Cruz-Martin + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. \ No newline at end of file diff --git a/MarkCommander.pro b/MarkCommander.pro new file mode 100644 index 0000000..251ad71 --- /dev/null +++ b/MarkCommander.pro @@ -0,0 +1,63 @@ +#------------------------------------------------- +# +# Project created by QtCreator 2011-03-16T22:14:07 +# +#------------------------------------------------- + +QT += core gui webkit + +TARGET = MarkCommander +TEMPLATE = app + + +SOURCES += main.cpp\ + mainwindow.cpp \ + exception.cpp \ + errorcodes.cpp \ + terminal.cpp \ + rhinolang.cpp \ + cmdlineedit.cpp \ + rhinoprog.cpp \ + rhino_xr4.cpp \ + matrix.cpp + +HEADERS += \ + rhino_xr4.hpp \ + matrix.hpp \ + cmdlineedit.hpp \ + errorcodes.hpp \ + exception.hpp \ + mainwindow.hpp \ + rhinolang.hpp \ + rhinoprog.hpp \ + terminal.hpp + +FORMS += mainwindow.ui + +RESOURCES += \ + icons.qrc \ + files.qrc + +INCLUDEPATH += ../qextserialport/src + +#LIBS += -L../qextserialport/src-build-desktop/build -lqextserialportd1 +#LIBS += -L../qextserialport/src-build-desktop/build -lqextserialport1 +#macx:LIBS += -L../qextserialport-build-desktop-Desktop_Qt_4_7_4_for_GCC__Qt_SDK__Debug/src/build -lqextserialportd +macx:LIBS += -L../qextserialport-build-desktop-Desktop_Qt_4_7_4_for_GCC__Qt_SDK__Release/src/build -lqextserialport + +win32:RC_FILE = MarkCommander.rc +macx:ICON = appicon.icns + + + + + + + + + + + + + + diff --git a/MarkCommander.rc b/MarkCommander.rc new file mode 100644 index 0000000..d4298d4 --- /dev/null +++ b/MarkCommander.rc @@ -0,0 +1 @@ +IDI_ICON1 ICON DISCARDABLE "appicon.ico" \ No newline at end of file diff --git a/TODO b/TODO new file mode 100644 index 0000000..13c9f3c --- /dev/null +++ b/TODO @@ -0,0 +1,3 @@ +* Supuestamente, debería poderse parar el timer de polling una vez se recibe el Carriage Return del controlador. +* Añadir una barra de progreso a la barra de estado para indicar que se está esperando la respuesta del controlador. +* Corregir el control manual en el espacio de las articulaciones para que sea más fluido. diff --git a/appicon.icns b/appicon.icns new file mode 100644 index 0000000..514c426 Binary files /dev/null and b/appicon.icns differ diff --git a/appicon.ico b/appicon.ico new file mode 100644 index 0000000..07d2681 Binary files /dev/null and b/appicon.ico differ diff --git a/cmdlineedit.cpp b/cmdlineedit.cpp new file mode 100644 index 0000000..fe9463a --- /dev/null +++ b/cmdlineedit.cpp @@ -0,0 +1,60 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "cmdlineedit.hpp" + +#include + +CmdLineEdit::CmdLineEdit(QWidget *parent) : QLineEdit(parent) +{ + historyIndex = 0; +} + +void CmdLineEdit::addCmdToHistory(QString cmd) +{ + _cmdHistory.append(cmd); + historyIndex++; +} + +QStringList CmdLineEdit::cmdHistory() +{ + return _cmdHistory; +} + +void CmdLineEdit::keyPressEvent(QKeyEvent *event) +{ + if (event->key() == Qt::Key_Up) + { + if (!_cmdHistory.isEmpty() && historyIndex > 0) + { + historyIndex--; + setText(_cmdHistory.at(historyIndex)); + } + } + else if (event->key() == Qt::Key_Down) + { + if (!_cmdHistory.isEmpty()) + { + if (++historyIndex < _cmdHistory.size()) + setText(_cmdHistory.at(historyIndex)); + else + { + historyIndex = _cmdHistory.size(); + setText(currentCmd); + } + } + } + else + QLineEdit::keyPressEvent(event); +} diff --git a/cmdlineedit.hpp b/cmdlineedit.hpp new file mode 100644 index 0000000..48fb033 --- /dev/null +++ b/cmdlineedit.hpp @@ -0,0 +1,38 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef CMDLINEEDIT_H +#define CMDLINEEDIT_H + +#include + +class CmdLineEdit : public QLineEdit +{ + Q_OBJECT + +public: + CmdLineEdit(QWidget *parent=0); + void addCmdToHistory(QString cmd); + QStringList cmdHistory(); + +protected: + void keyPressEvent(QKeyEvent *event); + +private: + QStringList _cmdHistory; + int historyIndex; + QString currentCmd; +}; + +#endif // CMDLINEEDIT_H diff --git a/errorcodes.cpp b/errorcodes.cpp new file mode 100644 index 0000000..d428fd9 --- /dev/null +++ b/errorcodes.cpp @@ -0,0 +1,133 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "errorcodes.hpp" + +// Reg exp for Notepad++'s Ctrl-H (Search & Replace): +// >>(\#define)( )([A-Z\_]+)([ ]+[0-9]+[ ]+//[ ])([A-Za-z0-9 \'\(\)\,\.=]+)<< +// >> case \3: return "\5";<< + +const char * errcode_meaning(int errorno) +{ + switch (errorno) + { + /*********************************************************************** + * COMMAND ERRORS + ***********************************************************************/ + + case INV_CMD: return "Invalid command"; + case PAR_OUT: return "Parameter out of bounds"; + case MIS_PAR: return "Missing parameter"; + case NO_DLIM: return "Expected delimiter not seen"; + case TOO_MNY: return "Command string too long"; + case TP_ACTV: return "The teach pendant is active or busy"; + + /*********************************************************************** + * COMMUNICATION ERRORS + ***********************************************************************/ + + case HST_OVF: return "Host input buffer overflow"; + case HST_TMO: return "Host USART timed out"; + case HST_ERR: return "Host USART error (framing, parity, etc.)"; + case TP_OVF: return "Teach pendant input buffer overflow"; + case TP_TMO: return "Teach pendant USART timed out"; + case TP_ERRO: return "Teach pendant USART error (framing, parity, etc.)"; + case TP_OVRN: return "Teach pendant USART overrun"; + case HST_OVR: return "Host USART overrun"; + + /*********************************************************************** + * DIAGNOSTIC ERRORS + ***********************************************************************/ + + case BAD_RAM: return "Bad RAM location"; + case TP_ERR: return "Teach pendant returned diagnostic error"; + case NO_TP: return "Teach pendant not present"; + + /*********************************************************************** + * TEACH PENDANT PROGRAM ERRORS + ***********************************************************************/ + + case LAB_ERR: return "Missing label"; + case NO_PGRM: return "No program in memory"; + case MEM_FUL: return "Insufficient teach pendant memory"; + case EPM_FUL: return "Insufficient EEPROM memory"; + case RPL_ERR: return "Can't replace first record"; + case PROGRAM: return "A pendant program already exists"; + + /*********************************************************************** + * EXECUTION ERRORS + ***********************************************************************/ + + case HRD_ERR: return "Hard home routine failed"; + case NO_HARD: return "Hard home not set"; + case NO_SOFT: return "Soft home not set"; + case AR_OVFL: return "Arithmetic overflow"; + case TRG_ERR: return "Trig function return error"; + case STK_ERR: return "Error stack overflow"; + case BUSY: return "Still executing a trapezoidal move"; + case NO_MOTR: return "Inactive motor referenced"; + case MOV_DAT: return "Insufficient move data (velocity or acceleration = 0)"; + case BAD_MOD: return "Improper motor mode for command"; + case NO_A_SW: return "Limit switch A not found"; + case NO_B_SW: return "Limit switch B not found"; + case NO_C_SW: return "Limit switch C not found"; + case NO_D_SW: return "Limit switch D not found"; + case NO_E_SW: return "Limit switch E not found"; + case NO_F_SW: return "Limit switch F not found"; + case NO_G_SW: return "Limit switch G not found"; + case NO_H_SW: return "Limit switch H not found"; + case IMODE: return "Interpolation move out of bounds"; + case POS_OUT: return "XYZ position out of bounds"; + case STK_A_S: return "Limit switch A stuck"; + case STK_B_S: return "Limit switch B stuck"; + case STK_C_S: return "Limit switch C stuck"; + case STK_D_S: return "Limit switch D stuck"; + case STK_E_S: return "Limit switch E stuck"; + case STK_F_S: return "Limit switch F stuck"; + case STK_G_S: return "Limit switch G stuck"; + case STK_H_S: return "Limit switch H stuck"; + case INV_RBT: return "Invalid robot type specifier"; + case INV_MOT: return "Invalid motor specifier"; + case INV_CTL: return "Invalid controller type"; + case INV_PND: return "Invalid pendant mode"; + case STOP: return "Emergency stop"; + case INV_XYZ: return "Invalid xyz specifier"; + case XYZ_PAR: return "Invalid xyz parameter"; + + /*********************************************************************** + * MOTOR ERRORS + ***********************************************************************/ + + case A_STALL: return "Motor A stalled"; + case B_STALL: return "Motor B stalled"; + case C_STALL: return "Motor C stalled"; + case D_STALL: return "Motor D stalled"; + case E_STALL: return "Motor E stalled"; + case F_STALL: return "Motor F stalled"; + case G_STALL: return "Motor G stalled"; + case H_STALL: return "Motor H stalled"; + case A_CURLIM: return "Motor A's current limit circuit was activated"; + case B_CURLIM: return "Motor B's current limit circuit was activated"; + case C_CURLIM: return "Motor C's current limit circuit was activated"; + case D_CURLIM: return "Motor D's current limit circuit was activated"; + case E_CURLIM: return "Motor E's current limit circuit was activated"; + case F_CURLIM: return "Motor F's current limit circuit was activated"; + case G_CURLIM: return "Motor G's current limit circuit was activated"; + case H_CURLIM: return "Motor H's current limit circuit was activated"; + case I_CURLIM: return "Aux Port 1's current limit circuit was activated"; + case J_CURLIM: return "Aux Port 2's current limit circuit was activated"; + + default: return "Unknown error code"; + } +} diff --git a/errorcodes.hpp b/errorcodes.hpp new file mode 100644 index 0000000..91258a9 --- /dev/null +++ b/errorcodes.hpp @@ -0,0 +1,126 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef ERRORCODES_H +#define ERRORCODES_H + +/*********************************************************************** + * COMMAND ERRORS + ***********************************************************************/ + +#define INV_CMD 10 // Invalid command +#define PAR_OUT 11 // Parameter out of bounds +#define MIS_PAR 12 // Missing parameter +#define NO_DLIM 13 // Expected delimiter not seen +#define TOO_MNY 14 // Command string too long +#define TP_ACTV 16 // The teach pendant is active or busy + +/*********************************************************************** + * COMMUNICATION ERRORS + ***********************************************************************/ + +#define HST_OVF 20 // Host input buffer overflow +#define HST_TMO 21 // Host USART timed out +#define HST_ERR 22 // Host USART error (framing, parity, etc.) +#define TP_OVF 23 // Teach pendant input buffer overflow +#define TP_TMO 24 // Teach pendant USART timed out +#define TP_ERRO 25 // Teach pendant USART error (framing, parity, etc.) +#define TP_OVRN 26 // Teach pendant USART overrun +#define HST_OVR 27 // Host USART overrun + +/*********************************************************************** + * DIAGNOSTIC ERRORS + ***********************************************************************/ + +#define BAD_RAM 30 // Bad RAM location +#define TP_ERR 32 // Teach pendant returned diagnostic error +#define NO_TP 34 // Teach pendant not present + +/*********************************************************************** + * TEACH PENDANT PROGRAM ERRORS + ***********************************************************************/ + +#define LAB_ERR 40 // Missing label +#define NO_PGRM 41 // No program in memory +#define MEM_FUL 42 // Insufficient teach pendant memory +#define EPM_FUL 43 // Insufficient EEPROM memory +#define RPL_ERR 44 // Can't replace first record +#define PROGRAM 45 // A pendant program already exists + +/*********************************************************************** + * EXECUTION ERRORS + ***********************************************************************/ + +#define HRD_ERR 50 // Hard home routine failed +#define NO_HARD 51 // Hard home not set +#define NO_SOFT 52 // Soft home not set +#define AR_OVFL 53 // Arithmetic overflow +#define TRG_ERR 54 // Trig function return error +#define STK_ERR 55 // Error stack overflow +#define BUSY 56 // Still executing a trapezoidal move +#define NO_MOTR 57 // Inactive motor referenced +#define MOV_DAT 58 // Insufficient move data (velocity or acceleration = 0) +#define BAD_MOD 59 // Improper motor mode for command +#define NO_A_SW 60 // Limit switch A not found +#define NO_B_SW 61 // Limit switch B not found +#define NO_C_SW 62 // Limit switch C not found +#define NO_D_SW 63 // Limit switch D not found +#define NO_E_SW 64 // Limit switch E not found +#define NO_F_SW 65 // Limit switch F not found +#define NO_G_SW 66 // Limit switch G not found +#define NO_H_SW 67 // Limit switch H not found +#define IMODE 69 // Interpolation move out of bounds +#define POS_OUT 70 // XYZ position out of bounds +#define STK_A_S 80 // Limit switch A stuck +#define STK_B_S 81 // Limit switch B stuck +#define STK_C_S 82 // Limit switch C stuck +#define STK_D_S 83 // Limit switch D stuck +#define STK_E_S 84 // Limit switch E stuck +#define STK_F_S 85 // Limit switch F stuck +#define STK_G_S 86 // Limit switch G stuck +#define STK_H_S 87 // Limit switch H stuck +#define INV_RBT 91 // Invalid robot type specifier +#define INV_MOT 92 // Invalid motor specifier +#define INV_CTL 93 // Invalid controller type +#define INV_PND 94 // Invalid pendant mode +#define STOP 95 // Emergency stop +#define INV_XYZ 96 // Invalid xyz specifier +#define XYZ_PAR 97 // Invalid xyz parameter + +/*********************************************************************** + * MOTOR ERRORS + ***********************************************************************/ + +#define A_STALL 100 // Motor A stalled +#define B_STALL 101 // Motor B stalled +#define C_STALL 102 // Motor C stalled +#define D_STALL 103 // Motor D stalled +#define E_STALL 104 // Motor E stalled +#define F_STALL 105 // Motor F stalled +#define G_STALL 106 // Motor G stalled +#define H_STALL 107 // Motor H stalled +#define A_CURLIM 110 // Motor A's current limit circuit was activated +#define B_CURLIM 111 // Motor B's current limit circuit was activated +#define C_CURLIM 112 // Motor C's current limit circuit was activated +#define D_CURLIM 113 // Motor D's current limit circuit was activated +#define E_CURLIM 114 // Motor E's current limit circuit was activated +#define F_CURLIM 115 // Motor F's current limit circuit was activated +#define G_CURLIM 116 // Motor G's current limit circuit was activated +#define H_CURLIM 117 // Motor H's current limit circuit was activated +#define I_CURLIM 118 // Aux Port 1's current limit circuit was activated +#define J_CURLIM 119 // Aux Port 2's current limit circuit was activated + +const char * errcode_meaning(int errorno); + +#endif // ERRORCODES_H diff --git a/exception.cpp b/exception.cpp new file mode 100644 index 0000000..e476b15 --- /dev/null +++ b/exception.cpp @@ -0,0 +1,46 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "exception.hpp" + +#include + +#include +using namespace std; + +Exception::Exception(QString newMsg) +{ + _description = QObject::tr("Generic exception"); + setMessage(newMsg); +} + +QString Exception::description() +{ + return _description; +} + +QString Exception::message() +{ + return _message; +} + +void Exception::setMessage(QString newMsg) +{ + _message = newMsg; +} + +void Exception::printMessage() +{ + cout << message().toStdString() << endl; +} diff --git a/exception.hpp b/exception.hpp new file mode 100644 index 0000000..336f76f --- /dev/null +++ b/exception.hpp @@ -0,0 +1,34 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef EXCEPTION_H +#define EXCEPTION_H + +#include +#include + +class Exception +{ +protected: + QString _description; // brief description (or name) of the exception + QString _message; // longer message describing the exception +public: + Exception(QString newMsg=""); + QString description(); + QString message(); + void setMessage(QString newMsg); + void printMessage(); +}; + +#endif // EXCEPTION_H diff --git a/files.qrc b/files.qrc new file mode 100644 index 0000000..de37373 --- /dev/null +++ b/files.qrc @@ -0,0 +1,7 @@ + + + files/mark-iv-commands.html + files/mark-iv-commands.pdf + files/mark-iv-error-codes.txt + + diff --git a/files/mark-iv-commands.html b/files/mark-iv-commands.html new file mode 100644 index 0000000..cb44307 --- /dev/null +++ b/files/mark-iv-commands.html @@ -0,0 +1 @@ +Comandos de Rhino Mark IV

Referencia de comandos del controlador Mark IV

System Commands

SA

Read motor status.

SC

Read system configuration.

Bit 7:    1 = host mode               0 = pendant mode

Bit 6:    1 = pendant enabled     0 = pendant disabled

Bit 5:    1 = generic controller    0 = robot controller

Bit 4:    1 = SCARA mode         0 = XR-3 mode

Bit 3:    1 = gripper disabled      0 = gripper enabled

Bit 2:    1 = xyz coordinate        0 = joint coordinate

Bit 1 and 0 are always 0.

SD,d

Stop/start delay timer.

0 <= d <= 3000.

SE

Read host error stack.

SM,m

Read motor mode.

0 = Idle mode

1 = Trapezoidal mode

2 = Velocity mode

3 = Open loop mode

SP

Read teach pendant error byte.

SR

Reset motor current limit circuitry.

SS

Read system status.

Bit 7:    1 = At least one motor is busy.

Bit 6:    1 = A system error has occurred.

Bit 5:    1 = The delay timer is active.

Bit 4:    1 = Wait on input/switch still pending.

Bit 3:    1 = No teach pendant is connected.

Bit 2:    1 = The ENTER key has been pressed.

Bit 1: The ESCAPE key has been pressed.

Bit 0: A teach pendant error has occurred.

ST

Execute diagnostics.

SU

Read usage time.

SV

Read version and I.D. number.

SX

Execute diagnostics and return results.

SZ

Read the delay timer.

Configuration Commands

CC,d

Set coordinate position.

CG,s

Enable (1) gripper mode (0) disable.

CM,m,d

Set motor mode.

0 = Idle mode

1 = Trapezoidal mode

2 = Velocity mode

3 = Open loop mode

CR,d

Set robot type.

0 = XR-3 robot mode.

1 = SCARA robot mode.

2 = GENERIC controller mode.

Motor Read Commands

AR

Read system acceleration.

DR,m

Read motor pwm level and direction

GS

Read gripper status.

HR,m

Read soft home position.

PA,m

Read actual position.

PW,m

Read destination position.

PZ,x

Read xyz destination position.

RL

Read limit switches.

UA

Read xyz rotation angle.

UH,x

Read xyz home position.

UO,x

Read xyz offset.

UT

Read xyz tool length.

UY

Read xyz height of the elbow rotation axis (H0).

VA,m

Read motor actual velocity.

VR,m

Read motor desired velocity.

VX

Read system velocity.

XR,m

Read auxiliary port level and direction.

1 <= d <= 2

Motor Set Commands

AC,m

Clear motor actual position.

AS,d

Set system acceleration.

DS,m,d

Set motor pwm level and direction.

GC

Close gripper.

GO

Open gripper.

HA

Go to the hard home position.

HG

Go to the soft home position.

HH

Execute a hard home.

HL,m

Hard home on limit switch.

HS

Set soft home.

MA

Stop all motors and auxiliary ports.

MC

Start all motors, coordinated.

MI

Start all motor, independent.

MM,m

Stop single motor.

MS,m

Start single motor.

MX

Start xyz move.

PD,m,d

Set motor destination position, absolute.

PR,m,d

Set motor destination position, relative.

PX,x,f

Set axis destination position, absolute.

PY,x,f

Set axis destination position, relative.

VG,d

Set system velocity.

VS,m,d

Set motor velocity.

XA,f

Set xyz rotation angle.

XH,x,f

Set xyz home position.

XO,x,f

Set xyz offset.

XS,m,d

Set auxiliary port level and direction.

1 <= m <= 2

XT,f

Set xyz tool length.

XY,f

Set xyz height of the elbow rotation axis (H0).

Teach Pendant Commands

FR

Receive teach pendant file from host.

FT

Transmit teach pendant file to host.

FX

Execute teach pendant program.

TA

Abort/terminate teach pendant program.

TC

Clear teach pendant display.

TD,”msg”

Print to teach pendant display.

TE,d

Enable(1)\disable (0) teach pendant to move motors.

TH

Give control to host.

TK

Return to host the next key code.

TL

Return to host the last key code.

TR

Reset the teach pendant.

TS,r,c

Set teach pendant display cursor.

TT

Execute teach pendant diagnostics and return results.

TX

Give control to teach pendant.

Gain Commands

KA,m,d

Set propotional gain.

KB,m,d

Set differential gain.

KC,m,d

Set integral gain.

RA,m

Read proportional gain.

RB,m

Read differential gain.

RC,m

Read integral gain.

KR

Restore user gains from EEPROM.

KS

Store user gains to EEPROM.

KX

Restore factory gains.

Input and Output Commands

IB,b

Read input or switch bit.

IP

Read input port.

IX

Read switch port.

OB,b,s

Set output bit.

OP,d

Set output port.

OR

Read output port.

OT,b,s

Toggle output bit.

WA

Abort all wait on inputs and switches.

WI,b,s

Wait on input or switch bit.

\ No newline at end of file diff --git a/files/mark-iv-commands.pdf b/files/mark-iv-commands.pdf new file mode 100644 index 0000000..fe4dad1 Binary files /dev/null and b/files/mark-iv-commands.pdf differ diff --git a/files/mark-iv-error-codes.txt b/files/mark-iv-error-codes.txt new file mode 100644 index 0000000..a88a125 --- /dev/null +++ b/files/mark-iv-error-codes.txt @@ -0,0 +1,105 @@ +####################################################################### +# COMMAND ERRORS +####################################################################### + +INV_CMD 10 Invalid command +PAR_OUT 11 Parameter out of bounds +MIS_PAR 12 Missing parameter +NO_DLIM 13 Expected delimiter not seen +TOO_MNY 14 Command string too long +TP_ACTV 16 The teach pendant is active or busy + +####################################################################### +# COMMUNICATION ERRORS +####################################################################### + +HST_OVF 20 Host input buffer overflow +HST_TMO 21 Host USART timed out +HST_ERR 22 Host USART error (framing, parity, etc.) +TP_OVF 23 Teach pendant input buffer overflow +TP_TMO 24 Teach pendant USART timed out +TP_ERRO 25 Teach pendant USART error (framing, parity, etc.) +TP_OVRN 26 Teach pendant USART overrun +HST_OVR 27 Host USART overrun + +####################################################################### +# DIAGNOSTIC ERRORS +####################################################################### + +BAD_RAM 30 Bad RAM location +TP_ERR 32 Teach pendant returned diagnostic error +NO_TP 34 Teach pendant not present + +####################################################################### +# TEACH PENDANT PROGRAM ERRORS +####################################################################### + +LAB_ERR 40 Missing label +NO_PGRM 41 No program in memory +MEM_FUL 42 Insufficient teach pendant memory +EPM_FUL 43 Insufficient EEPROM memory +RPL_ERR 44 Can't replace first record +PROGRAM 45 A pendant program already exists + +####################################################################### +# EXECUTION ERRORS +####################################################################### + +HRD_ERR 50 Hard home routine failed +NO_HARD 51 Hard home not set +NO_SOFT 52 Soft home not set +AR_OVFL 53 Arithmetic overflow +TRG_ERR 54 Trig function return error +STK_ERR 55 Error stack overflow +BUSY 56 Still executing a trapezoidal move +NO_MOTR 57 Inactive motor referenced +MOV_DAT 58 Insufficient move data (velocity or acceleration = 0) +BAD_MOD 59 Improper motor mode for command +NO_A_SW 60 Limit switch A not found +NO_B_SW 61 Limit switch B not found +NO_C_SW 62 Limit switch C not found +NO_D_SW 63 Limit switch D not found +NO_E_SW 64 Limit switch E not found +NO_F_SW 65 Limit switch F not found +NO_G_SW 66 Limit switch G not found +NO_H_SW 67 Limit switch H not found +IMODE 69 Interpolation move out of bounds +POS_OUT 70 XYZ position out of bounds +STK_A_S 80 Limit switch A stuck +STK_B_S 81 Limit switch B stuck +STK_C_S 82 Limit switch C stuck +STK_D_S 83 Limit switch D stuck +STK_E_S 84 Limit switch E stuck +STK_F_S 85 Limit switch F stuck +STK_G_S 86 Limit switch G stuck +STK_H_S 87 Limit switch H stuck +INV_RBT 91 Invalid robot type specifier +INV_MOT 92 Invalid motor specifier +INV_CTL 93 Invalid controller type +INV_PND 94 Invalid pendant mode +STOP 95 Emergency stop +INV_XYZ 96 Invalid xyz specifier +XYZ_PAR 97 Invalid xyz parameter + +####################################################################### +# MOTOR ERRORS +####################################################################### + +A_STALL 100 Motor A stalled +B_STALL 101 Motor B stalled +C_STALL 102 Motor C stalled +D_STALL 103 Motor D stalled +E_STALL 104 Motor E stalled +F_STALL 105 Motor F stalled +G_STALL 106 Motor G stalled +H_STALL 107 Motor H stalled +A_CURLIM 110 Motor A's current limit circuit was activated +B_CURLIM 111 Motor B's current limit circuit was activated +C_CURLIM 112 Motor C's current limit circuit was activated +D_CURLIM 113 Motor D's current limit circuit was activated +E_CURLIM 114 Motor E's current limit circuit was activated +F_CURLIM 115 Motor F's current limit circuit was activated +G_CURLIM 116 Motor G's current limit circuit was activated +H_CURLIM 117 Motor H's current limit circuit was activated +I_CURLIM 118 Aux Port 1's current limit circuit was activated +J_CURLIM 119 Aux Port 2's current limit circuit was activated \ No newline at end of file diff --git a/icons.qrc b/icons.qrc new file mode 100644 index 0000000..c0106f0 --- /dev/null +++ b/icons.qrc @@ -0,0 +1,54 @@ + + + icons/document-new.png + icons/document-open.png + icons/document-save.png + icons/down.png + icons/editcopy.png + icons/edit-copy.png + icons/editcut.png + icons/edit-cut.png + icons/editpaste.png + icons/edit-paste.png + icons/edit-redo.png + icons/edit-select-all.png + icons/edit-undo.png + icons/filenew.png + icons/fileopen.png + icons/filesave.png + icons/filesaveas.png + icons/format-indent-less.png + icons/format-indent-more.png + icons/gnome-terminal.png + icons/gtk-cancel.png + icons/gtk-close.png + icons/gtk-copy.png + icons/gtk-cut.png + icons/gtk-save.png + icons/gtk-save-as.png + icons/gtk-stop.png + icons/openterm.png + icons/stock_exit.png + icons/terminal.png + icons/up.png + icons/1300233017_eraser.png + icons/1300233114_utilities-terminal.png + icons/1300233134_eraser.png + icons/clear_term.png + icons/1300233417_document-save.png + icons/1300233418_document-save.png + icons/1300233422_document-save-as.png + icons/1300233423_document-save-as.png + icons/1300233427_save-all.png + icons/1300233428_save-all.png + icons/1300233544_document-save.png + icons/save_term_buffer.png + icons/close_term.png + icons/gtk-close-16x16.png + icons/gtk-close-22x22.png + icons/gtk-close-24x24.png + icons/appicon1.png + icons/appicon2.png + icons/appicon3.png + + diff --git a/icons/1300233017_eraser.png b/icons/1300233017_eraser.png new file mode 100644 index 0000000..efc4b5a Binary files /dev/null and b/icons/1300233017_eraser.png differ diff --git a/icons/1300233114_utilities-terminal.png b/icons/1300233114_utilities-terminal.png new file mode 100644 index 0000000..d7fceac Binary files /dev/null and b/icons/1300233114_utilities-terminal.png differ diff --git a/icons/1300233134_eraser.png b/icons/1300233134_eraser.png new file mode 100644 index 0000000..cca100f Binary files /dev/null and b/icons/1300233134_eraser.png differ diff --git a/icons/1300233417_document-save.png b/icons/1300233417_document-save.png new file mode 100644 index 0000000..e1617ad Binary files /dev/null and b/icons/1300233417_document-save.png differ diff --git a/icons/1300233418_document-save.png b/icons/1300233418_document-save.png new file mode 100644 index 0000000..e8db1aa Binary files /dev/null and b/icons/1300233418_document-save.png differ diff --git a/icons/1300233422_document-save-as.png b/icons/1300233422_document-save-as.png new file mode 100644 index 0000000..cc486c5 Binary files /dev/null and b/icons/1300233422_document-save-as.png differ diff --git a/icons/1300233423_document-save-as.png b/icons/1300233423_document-save-as.png new file mode 100644 index 0000000..0fc2de2 Binary files /dev/null and b/icons/1300233423_document-save-as.png differ diff --git a/icons/1300233427_save-all.png b/icons/1300233427_save-all.png new file mode 100644 index 0000000..7208f6a Binary files /dev/null and b/icons/1300233427_save-all.png differ diff --git a/icons/1300233428_save-all.png b/icons/1300233428_save-all.png new file mode 100644 index 0000000..4a44028 Binary files /dev/null and b/icons/1300233428_save-all.png differ diff --git a/icons/1300233544_document-save.png b/icons/1300233544_document-save.png new file mode 100644 index 0000000..5027fed Binary files /dev/null and b/icons/1300233544_document-save.png differ diff --git a/icons/Rhino XR-3 128x128.png b/icons/Rhino XR-3 128x128.png new file mode 100644 index 0000000..42168cc Binary files /dev/null and b/icons/Rhino XR-3 128x128.png differ diff --git a/icons/Rhino XR-3 16x16.png b/icons/Rhino XR-3 16x16.png new file mode 100644 index 0000000..de7d7ad Binary files /dev/null and b/icons/Rhino XR-3 16x16.png differ diff --git a/icons/Rhino XR-3 256x256.png b/icons/Rhino XR-3 256x256.png new file mode 100644 index 0000000..e4ca1cc Binary files /dev/null and b/icons/Rhino XR-3 256x256.png differ diff --git a/icons/Rhino XR-3 256x256.psd b/icons/Rhino XR-3 256x256.psd new file mode 100644 index 0000000..67a598c Binary files /dev/null and b/icons/Rhino XR-3 256x256.psd differ diff --git a/icons/Rhino XR-3 32x32.png b/icons/Rhino XR-3 32x32.png new file mode 100644 index 0000000..10f4d24 Binary files /dev/null and b/icons/Rhino XR-3 32x32.png differ diff --git a/icons/Rhino XR-3 48x48.png b/icons/Rhino XR-3 48x48.png new file mode 100644 index 0000000..cbeb6bc Binary files /dev/null and b/icons/Rhino XR-3 48x48.png differ diff --git a/icons/Rhino XR-3.psd b/icons/Rhino XR-3.psd new file mode 100644 index 0000000..3f93583 Binary files /dev/null and b/icons/Rhino XR-3.psd differ diff --git a/icons/appicon.icns b/icons/appicon.icns new file mode 100644 index 0000000..514c426 Binary files /dev/null and b/icons/appicon.icns differ diff --git a/icons/appicon.ico b/icons/appicon.ico new file mode 100644 index 0000000..07d2681 Binary files /dev/null and b/icons/appicon.ico differ diff --git a/icons/appicon1.png b/icons/appicon1.png new file mode 100644 index 0000000..bf94f29 Binary files /dev/null and b/icons/appicon1.png differ diff --git a/icons/appicon2.png b/icons/appicon2.png new file mode 100644 index 0000000..e4ca1cc Binary files /dev/null and b/icons/appicon2.png differ diff --git a/icons/appicon3.png b/icons/appicon3.png new file mode 100644 index 0000000..9e8e913 Binary files /dev/null and b/icons/appicon3.png differ diff --git a/icons/clear_term.png b/icons/clear_term.png new file mode 100644 index 0000000..5e35e52 Binary files /dev/null and b/icons/clear_term.png differ diff --git a/icons/clear_term.xcf b/icons/clear_term.xcf new file mode 100644 index 0000000..08c5af4 Binary files /dev/null and b/icons/clear_term.xcf differ diff --git a/icons/close_term.png b/icons/close_term.png new file mode 100644 index 0000000..367933c Binary files /dev/null and b/icons/close_term.png differ diff --git a/icons/close_term.xcf b/icons/close_term.xcf new file mode 100644 index 0000000..aa60673 Binary files /dev/null and b/icons/close_term.xcf differ diff --git a/icons/document-new.png b/icons/document-new.png new file mode 100644 index 0000000..18a6473 Binary files /dev/null and b/icons/document-new.png differ diff --git a/icons/document-open.png b/icons/document-open.png new file mode 100644 index 0000000..1cb6ec2 Binary files /dev/null and b/icons/document-open.png differ diff --git a/icons/document-save.png b/icons/document-save.png new file mode 100644 index 0000000..dda2d46 Binary files /dev/null and b/icons/document-save.png differ diff --git a/icons/down.png b/icons/down.png new file mode 100644 index 0000000..4315f08 Binary files /dev/null and b/icons/down.png differ diff --git a/icons/edit-copy.png b/icons/edit-copy.png new file mode 100644 index 0000000..64a0f80 Binary files /dev/null and b/icons/edit-copy.png differ diff --git a/icons/edit-cut.png b/icons/edit-cut.png new file mode 100644 index 0000000..710386b Binary files /dev/null and b/icons/edit-cut.png differ diff --git a/icons/edit-paste.png b/icons/edit-paste.png new file mode 100644 index 0000000..a94d751 Binary files /dev/null and b/icons/edit-paste.png differ diff --git a/icons/edit-redo.png b/icons/edit-redo.png new file mode 100644 index 0000000..13b7972 Binary files /dev/null and b/icons/edit-redo.png differ diff --git a/icons/edit-select-all.png b/icons/edit-select-all.png new file mode 100644 index 0000000..2903a71 Binary files /dev/null and b/icons/edit-select-all.png differ diff --git a/icons/edit-undo.png b/icons/edit-undo.png new file mode 100644 index 0000000..f20602c Binary files /dev/null and b/icons/edit-undo.png differ diff --git a/icons/editcopy.png b/icons/editcopy.png new file mode 100644 index 0000000..64a0f80 Binary files /dev/null and b/icons/editcopy.png differ diff --git a/icons/editcut.png b/icons/editcut.png new file mode 100644 index 0000000..710386b Binary files /dev/null and b/icons/editcut.png differ diff --git a/icons/editpaste.png b/icons/editpaste.png new file mode 100644 index 0000000..a94d751 Binary files /dev/null and b/icons/editpaste.png differ diff --git a/icons/filenew.png b/icons/filenew.png new file mode 100644 index 0000000..18a6473 Binary files /dev/null and b/icons/filenew.png differ diff --git a/icons/fileopen.png b/icons/fileopen.png new file mode 100644 index 0000000..1cb6ec2 Binary files /dev/null and b/icons/fileopen.png differ diff --git a/icons/filesave.png b/icons/filesave.png new file mode 100644 index 0000000..dda2d46 Binary files /dev/null and b/icons/filesave.png differ diff --git a/icons/filesaveas.png b/icons/filesaveas.png new file mode 100644 index 0000000..ad62d0c Binary files /dev/null and b/icons/filesaveas.png differ diff --git a/icons/format-indent-less.png b/icons/format-indent-less.png new file mode 100644 index 0000000..f14a49c Binary files /dev/null and b/icons/format-indent-less.png differ diff --git a/icons/format-indent-more.png b/icons/format-indent-more.png new file mode 100644 index 0000000..a12e955 Binary files /dev/null and b/icons/format-indent-more.png differ diff --git a/icons/gnome-terminal.png b/icons/gnome-terminal.png new file mode 100644 index 0000000..7024509 Binary files /dev/null and b/icons/gnome-terminal.png differ diff --git a/icons/gtk-cancel.png b/icons/gtk-cancel.png new file mode 100644 index 0000000..fc2c756 Binary files /dev/null and b/icons/gtk-cancel.png differ diff --git a/icons/gtk-close-16x16.png b/icons/gtk-close-16x16.png new file mode 100644 index 0000000..583072c Binary files /dev/null and b/icons/gtk-close-16x16.png differ diff --git a/icons/gtk-close-22x22.png b/icons/gtk-close-22x22.png new file mode 100644 index 0000000..af07983 Binary files /dev/null and b/icons/gtk-close-22x22.png differ diff --git a/icons/gtk-close-24x24.png b/icons/gtk-close-24x24.png new file mode 100644 index 0000000..8fb79fc Binary files /dev/null and b/icons/gtk-close-24x24.png differ diff --git a/icons/gtk-close.png b/icons/gtk-close.png new file mode 100644 index 0000000..1a741ba Binary files /dev/null and b/icons/gtk-close.png differ diff --git a/icons/gtk-copy.png b/icons/gtk-copy.png new file mode 100644 index 0000000..64a0f80 Binary files /dev/null and b/icons/gtk-copy.png differ diff --git a/icons/gtk-cut.png b/icons/gtk-cut.png new file mode 100644 index 0000000..710386b Binary files /dev/null and b/icons/gtk-cut.png differ diff --git a/icons/gtk-save-as.png b/icons/gtk-save-as.png new file mode 100644 index 0000000..ad62d0c Binary files /dev/null and b/icons/gtk-save-as.png differ diff --git a/icons/gtk-save.png b/icons/gtk-save.png new file mode 100644 index 0000000..dda2d46 Binary files /dev/null and b/icons/gtk-save.png differ diff --git a/icons/gtk-stop.png b/icons/gtk-stop.png new file mode 100644 index 0000000..fc2c756 Binary files /dev/null and b/icons/gtk-stop.png differ diff --git a/icons/markiv.jpg b/icons/markiv.jpg new file mode 100644 index 0000000..2d50e65 Binary files /dev/null and b/icons/markiv.jpg differ diff --git a/icons/openterm.png b/icons/openterm.png new file mode 100644 index 0000000..7024509 Binary files /dev/null and b/icons/openterm.png differ diff --git a/icons/rhino_robot_white.jpg b/icons/rhino_robot_white.jpg new file mode 100644 index 0000000..0a47577 Binary files /dev/null and b/icons/rhino_robot_white.jpg differ diff --git a/icons/save_term_buffer.png b/icons/save_term_buffer.png new file mode 100644 index 0000000..8992bfb Binary files /dev/null and b/icons/save_term_buffer.png differ diff --git a/icons/save_term_buffer.xcf b/icons/save_term_buffer.xcf new file mode 100644 index 0000000..45f0b29 Binary files /dev/null and b/icons/save_term_buffer.xcf differ diff --git a/icons/stock_exit.png b/icons/stock_exit.png new file mode 100644 index 0000000..b1fdd57 Binary files /dev/null and b/icons/stock_exit.png differ diff --git a/icons/terminal.png b/icons/terminal.png new file mode 100644 index 0000000..7024509 Binary files /dev/null and b/icons/terminal.png differ diff --git a/icons/tp4.jpg b/icons/tp4.jpg new file mode 100644 index 0000000..9af6f2e Binary files /dev/null and b/icons/tp4.jpg differ diff --git a/icons/up.png b/icons/up.png new file mode 100644 index 0000000..0fa3ad3 Binary files /dev/null and b/icons/up.png differ diff --git a/icons/url.txt b/icons/url.txt new file mode 100644 index 0000000..24305c1 --- /dev/null +++ b/icons/url.txt @@ -0,0 +1 @@ +http://www.iconfinder.com/search/?q=iconset:oxygen \ No newline at end of file diff --git a/main.cpp b/main.cpp new file mode 100644 index 0000000..ddc6d16 --- /dev/null +++ b/main.cpp @@ -0,0 +1,27 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include "mainwindow.hpp" + +int main(int argc, char *argv[]) +{ + QApplication a(argc, argv); + a.setWindowIcon(QIcon(":/icons/appicon.png")); + + MainWindow w; + w.show(); + + return a.exec(); +} diff --git a/mainwindow.cpp b/mainwindow.cpp new file mode 100644 index 0000000..83413cc --- /dev/null +++ b/mainwindow.cpp @@ -0,0 +1,1922 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "mainwindow.hpp" +#include "ui_mainwindow.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "errorcodes.hpp" + +QTableWidget * createErrorCodesTable() +{ + QTableWidget *errorCodesTable = new QTableWidget(); + QTableWidgetItem *newItem; + + QStringList horizontalHeaders; + horizontalHeaders << QObject::tr("Código de error") << QObject::tr("Descripción"); + errorCodesTable->setColumnCount(2); + errorCodesTable->setHorizontalHeaderLabels(horizontalHeaders); + errorCodesTable->setColumnWidth(1, 300); + errorCodesTable->verticalHeader()->hide(); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(10)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid command")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(11)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Parameter out of bounds")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(12)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Missing parameter")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(13)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Expected delimiter not seen")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(14)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Command string too long")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(16)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("The teach pendant is active or busy")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(20)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Host input buffer overflow")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(21)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Host USART timed out")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(22)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Host USART error (framing, parity, etc.)")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(23)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant input buffer overflow")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(24)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant USART timed out")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(25)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant USART error (framing, parity, etc.)")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(26)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant USART overrun")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(27)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Host USART overrun")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(30)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Bad RAM location")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(32)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant returned diagnostic error")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(34)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Teach pendant not present")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(40)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Missing label")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(41)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("No program in memory")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(42)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Insufficient teach pendant memory")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(43)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Insufficient EEPROM memory")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(44)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Can't replace first record")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(45)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("A pendant program already exists")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(50)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Hard home routine failed")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(51)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Hard home not set")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(52)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Soft home not set")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(53)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Arithmetic overflow")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(54)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Trig function return error")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(55)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Error stack overflow")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(56)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Still executing a trapezoidal move")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(57)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Inactive motor referenced")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(58)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Insufficient move data (velocity or acceleration = 0)")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(59)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Improper motor mode for command")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(60)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch A not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(61)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch B not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(62)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch C not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(63)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch D not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(64)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch E not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(65)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch F not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(66)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch G not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(67)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch H not found")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(69)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Interpolation move out of bounds")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(70)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("XYZ position out of bounds")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(80)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch A stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(81)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch B stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(82)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch C stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(83)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch D stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(84)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch E stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(85)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch F stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(86)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch G stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(87)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Limit switch H stuck")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(91)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid robot type specifier")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(92)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid motor specifier")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(93)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid controller type")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(94)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid pendant mode")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(95)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Emergency stop")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(96)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid xyz specifier")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(97)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Invalid xyz parameter")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(100)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor A stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(101)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor B stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(102)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor C stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(103)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor D stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(104)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor E stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(105)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor F stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(106)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor G stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(107)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor H stalled")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(110)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor A's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(111)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor B's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(112)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor C's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(113)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor D's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(114)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor E's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(115)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor F's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(116)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor G's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(117)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Motor H's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(118)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Aux Port 1's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + errorCodesTable->insertRow(errorCodesTable->rowCount()); + newItem = new QTableWidgetItem(QString::number(119)); + newItem->setTextAlignment(Qt::AlignCenter); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 0, newItem); + newItem = new QTableWidgetItem(QString("Aux Port 2's current limit circuit was activated")); + errorCodesTable->setItem(errorCodesTable->rowCount() - 1, 1, newItem); + + return errorCodesTable; +} + +MainWindow::MainWindow(QWidget *parent) : + QMainWindow(parent), + ui(new Ui::MainWindow) +{ + ui->setupUi(this); + + editorProg = NULL; + errorCodesDialog = NULL; + cmdRefDialog = NULL; + showFileOnTerminal = true; + + disableTerminalActions(); + disableKinematics(); + ui->tabWidget_ctrlView->setCurrentIndex(0); + connectionStatus = new QLabel(); + connectionStatus->setText(tr("No hay ninguna conexión abierta")); + ui->statusBar->addPermanentWidget(connectionStatus); + editorFileStatus = new QLabel(); + editorFileStatus->setText(tr("No hay ningún fichero abierto")); + ui->statusBar->setSizeGripEnabled(false); + + // Hide undesireable or unimplemented menu actions + ui->actionSetSoftHome->setVisible(false); + ui->actionManualCtrl->setVisible(false); + ui->checkBox_dirkinKeepDirkin->setVisible(false); + //ui->pushButton_computeDirKin->setVisible(false); + //ui->pushButton_computeInvKin->setVisible(false); + + // Set minimum + ui->doubleSpinBox_dirkinTheta1F->setMinimum(xr4.jointRangeDeg('F').min); + ui->doubleSpinBox_dirkinTheta2E->setMinimum(xr4.jointRangeDeg('E').min); + ui->doubleSpinBox_dirkinTheta3D->setMinimum(xr4.jointRangeDeg('D').min); + ui->doubleSpinBox_dirkinTheta4C->setMinimum(xr4.jointRangeDeg('C').min); + ui->doubleSpinBox_dirkinTheta5B->setMinimum(xr4.jointRangeDeg('B').min); + // Set maximum + ui->doubleSpinBox_dirkinTheta1F->setMaximum(xr4.jointRangeDeg('F', true).max); + ui->doubleSpinBox_dirkinTheta2E->setMaximum(xr4.jointRangeDeg('E').max); + ui->doubleSpinBox_dirkinTheta3D->setMaximum(xr4.jointRangeDeg('D').max); + ui->doubleSpinBox_dirkinTheta4C->setMaximum(xr4.jointRangeDeg('C').max); + ui->doubleSpinBox_dirkinTheta5B->setMaximum(xr4.jointRangeDeg('B').max); + // Set minimum + ui->dial_dirkinTheta1F->setMinimum(xr4.jointRangeDeg('F').min); + ui->dial_dirkinTheta2E->setMinimum(xr4.jointRangeDeg('E').min); + ui->dial_dirkinTheta3D->setMinimum(xr4.jointRangeDeg('D').min); + ui->dial_dirkinTheta4C->setMinimum(xr4.jointRangeDeg('C').min); + ui->dial_dirkinTheta5B->setMinimum(xr4.jointRangeDeg('B').min); + // Set maximum + ui->dial_dirkinTheta1F->setMaximum(xr4.jointRangeDeg('F', true).max); + ui->dial_dirkinTheta2E->setMaximum(xr4.jointRangeDeg('E').max); + ui->dial_dirkinTheta3D->setMaximum(xr4.jointRangeDeg('D').max); + ui->dial_dirkinTheta4C->setMaximum(xr4.jointRangeDeg('C').max); + ui->dial_dirkinTheta5B->setMaximum(xr4.jointRangeDeg('B').max); + + // Set minimum + ui->doubleSpinBox_invkinTheta1F->setMinimum(xr4.jointRangeDeg('F').min); + ui->doubleSpinBox_invkinTheta2E->setMinimum(xr4.jointRangeDeg('E').min); + ui->doubleSpinBox_invkinTheta3D->setMinimum(xr4.jointRangeDeg('D').min); + ui->doubleSpinBox_invkinTheta4C->setMinimum(xr4.jointRangeDeg('C').min); + ui->doubleSpinBox_invkinTheta5B->setMinimum(xr4.jointRangeDeg('B').min); + // Set maximum + ui->doubleSpinBox_invkinTheta1F->setMaximum(xr4.jointRangeDeg('F', true).max); + ui->doubleSpinBox_invkinTheta2E->setMaximum(xr4.jointRangeDeg('E').max); + ui->doubleSpinBox_invkinTheta3D->setMaximum(xr4.jointRangeDeg('D').max); + ui->doubleSpinBox_invkinTheta4C->setMaximum(xr4.jointRangeDeg('C').max); + ui->doubleSpinBox_invkinTheta5B->setMaximum(xr4.jointRangeDeg('B').max); + // Set minimum + ui->dial_invkinTheta1F->setMinimum(xr4.jointRangeDeg('F').min); + ui->dial_invkinTheta2E->setMinimum(xr4.jointRangeDeg('E').min); + ui->dial_invkinTheta3D->setMinimum(xr4.jointRangeDeg('D').min); + ui->dial_invkinTheta4C->setMinimum(xr4.jointRangeDeg('C').min); + ui->dial_invkinTheta5B->setMinimum(xr4.jointRangeDeg('B').min); + // Set maximum + ui->dial_invkinTheta1F->setMaximum(xr4.jointRangeDeg('F', true).max); + ui->dial_invkinTheta2E->setMaximum(xr4.jointRangeDeg('E').max); + ui->dial_invkinTheta3D->setMaximum(xr4.jointRangeDeg('D').max); + ui->dial_invkinTheta4C->setMaximum(xr4.jointRangeDeg('C').max); + ui->dial_invkinTheta5B->setMaximum(xr4.jointRangeDeg('B').max); + + createConfigurationDialog(); + + connect(&terminal, SIGNAL(receivedFullResponse(QString)), + this, SLOT(getCmdResponse(QString))); + connect(&terminal, SIGNAL(timeout(int)), this, SLOT(handleTimeout(int))); + connect(&terminal, SIGNAL(receivedProgram(RhinoProg*)), + this, SLOT(getProgram(RhinoProg*))); + + dirkinOldValue[0] = 0.0; + dirkinOldValue[1] = 0.0; + dirkinOldValue[2] = 0.0; + dirkinOldValue[3] = 0.0; + dirkinOldValue[4] = 0.0; + + //alreadyGoneToKinHome = false; +} + +MainWindow::~MainWindow() +{ + if (editorProg != NULL) + delete editorProg; + if (connectionStatus != NULL) + delete connectionStatus; + if (cmdRefDialog != NULL) + delete cmdRefDialog; + if (errorCodesDialog != NULL) + delete errorCodesDialog; + delete ui; +} + +void MainWindow::on_pushButton_sendCmd_clicked() +{ + ui->statusBar->clearMessage(); + if (!terminal.isConnected()) + { + QMessageBox::warning(this, + tr("No se puede enviar el comando"), + tr("No se puede enviar el comando especificado porque no se ha" + " abierto una conexión al controlador. Primero debe abrir la" + "conexión al controlador.")); + } + else + { + QString cmd = ui->lineEdit_cmd->text(); + insertPrompt(); + insertTxtIntoTerm(cmd + "\n"); + ui->lineEdit_cmd->setText(""); + if(terminal.sendCmdAndTellMustWait(cmd)) + lockTerminal(); + ui->lineEdit_cmd->addCmdToHistory(cmd); + } +} + +void MainWindow::on_actionTransmitProgram_triggered() +{ + if (!terminal.isConnected()) + { + QMessageBox::warning(this, + tr("No se puede transmitir ningún programa"), + tr("No se puede transmitir ningún programa. " + "Primero debe abrir una conexión al controlador" + " Mark IV.")); + } + else + { + QString progFilePath = QFileDialog::getOpenFileName(this, + tr("Transmitir programa"), + QDir::homePath(), + tr("Programa de Rhino Mark IV (*.mkc)")); + if (!progFilePath.isEmpty()) + { + RhinoProg *prog; + + // open program file and get code + /*if (progFilePath == editorProg->path()) + prog = editorProg; + else + {*/ + QFile progFile(progFilePath); + progFile.open(QFile::ReadOnly | QFile::Text); + prog = new RhinoProg(progFile.readAll()); + progFile.close(); + /*}*/ + + // transmit program + terminal.sendProgram(prog->getCode()); + ui->statusBar->showMessage(tr("Programa transmitido correctamente")); + + // delete program file if it is not the file open in the editor + if (prog != editorProg) + delete prog; + } + ui->lineEdit_cmd->setFocus(); + } +} + +void MainWindow::on_actionReceiveProgram_triggered() +{ + if (!terminal.isConnected()) + { + QMessageBox::warning(this, + tr("No se puede transmitir ningún programa"), + tr("No se puede transmitir ningún programa. " + "Primero debe abrir una conexión al controlador" + " Mark IV.")); + } + else + { + receivedProgFilePath = QFileDialog::getSaveFileName(this, + tr("Recibir programa"), + QDir::homePath(), + tr("Programa de Rhino Mark IV (*.mkc)")); + + if (!receivedProgFilePath.isEmpty()) + { + terminal.getProgram(); + showFileOnTerminal = false; + lockTerminal(); + } + else + ui->lineEdit_cmd->setFocus(); + } +} + +void MainWindow::on_actionConnectToController_triggered() +{ + if (terminal.isConnected()) + { + QMessageBox::warning(this, + tr("No se puede conectar el terminal"), + tr("No se puede conectar al controlador porque ya hay una conexión " + "abierta. Para poder abrir una nueva conexión, rimero debe " + "cerrar la conexión.")); + } + else + { + QStringList comPorts; + QString selectedPort; + bool ok; + + comPorts << tr("COM1") << tr("COM2") << tr("COM3") << tr("COM4"); + selectedPort = QInputDialog::getItem(this, + tr("Elija el puerto serie"), + tr("Elija el puerto serie al que desea conectar el" + " terminal"), + comPorts, // list of items + 0, // default item + false, // not editable + &ok); + if (ok) + { + try + { + terminal.setPort(selectedPort); + terminal.connect(); + ui->plainTextEdit_terminalView->clear(); + connectionStatus->setText(tr("Conectado al puerto ") + selectedPort); + enableTerminalActions(); + unlockTerminal(); + ui->lineEdit_cmd->setFocus(); + } + catch (ErrorOpeningComPort *e) + { + QMessageBox::critical(this, + tr("Error al abrir conexión"), + tr("Se ha producido un error al intentar conectar al " + "puerto %1. O bien el puerto no existe, o no está " + "disponible en este momento. Asegúrese de que el " + "puerto existe e inténtelo de nuevo mas tarde.").arg(selectedPort)); + } + catch (Exception *e) + { + QMessageBox::critical(this, + tr("Error desconocido"), + tr("Se ha producido un error desconocido: %1").arg(e->message())); + delete e; + } + } + } +} + +void MainWindow::on_actionCloseConnection_triggered() +{ + if (terminal.isConnected()) + { + QMessageBox questionBox(this); + QPushButton *closeBtn; + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea cerrar la conexión?")); + questionBox.setInformativeText(tr("¿Desea cerrar la conexión con el controlador Mark IV?")); + closeBtn = questionBox.addButton(tr("Cerrar"), QMessageBox::YesRole); + questionBox.addButton(tr("No cerrar"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == closeBtn) + closeConnection(); + } +} + +void MainWindow::quitApp() +{ + bool quit = true; + if (terminal.isConnected()) + { + QMessageBox questionBox(this); + QPushButton *closeBtn; + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea cerrar la conexión?")); + questionBox.setInformativeText(tr("Para salir del programa, deberá cerrar la conexión. " + "¿Desea cerrar la conexión con el controlador Mark IV?")); + closeBtn = questionBox.addButton(tr("Cerrar"), QMessageBox::YesRole); + questionBox.addButton(tr("No cerrar"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == closeBtn) + closeConnection(); + else + quit = false; + } + if (quit) + qApp->quit(); +} + +void MainWindow::on_actionSaveTerminalOutput_triggered() +{ + QString filePath = QFileDialog::getSaveFileName(this, + tr("Guardar texto del terminal"), + QDir::homePath(), + tr("Texto plano (*.txt)")); + if (!filePath.isEmpty()) + { + QFile outFile(filePath); + outFile.open(QFile::WriteOnly | QFile::Truncate | QFile::Text); + QTextStream outStream(&outFile); + outStream << ui->plainTextEdit_terminalView->toPlainText(); + outStream.flush(); + outFile.close(); + } + ui->lineEdit_cmd->setFocus(); +} + +void MainWindow::on_actionClearTerminal_triggered() +{ + QMessageBox questionBox(this); + QPushButton *clearBtn; + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea borrar la pantalla?")); + questionBox.setInformativeText(tr("¿Desea borrar la pantalla del terminal?")); + clearBtn = questionBox.addButton(tr("Borrar"), QMessageBox::YesRole); + questionBox.addButton(tr("No borrar"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == clearBtn) + ui->plainTextEdit_terminalView->clear(); + ui->lineEdit_cmd->setFocus(); +} + +void MainWindow::insertPrompt() +{ + insertTxtIntoTerm(terminal.promptTxt()); +} + +void MainWindow::getCmdResponse(QString response) +{ + insertTxtIntoTerm(response + "\n"); + if (ui->lineEdit_cmd->cmdHistory().last().toLower() == "se") + { + int errCode = response.toInt(); + if (errCode != 0) + ui->statusBar->showMessage(tr("Error %1: %2").arg(response, QString(errcode_meaning(errCode)))); + } + unlockTerminal(); + ui->lineEdit_cmd->setFocus(); +} + +void MainWindow::handleTimeout(int time) +{ + insertTxtIntoTerm(tr("== TIMEOUT: Mark IV Controller has not responded yet, continuing... ==\n")); + ui->statusBar->showMessage(tr("Timeout: No se ha obtenido respuesta del controlador en los últimos" + " %1 segundo(s).").arg(QString::number(time / 1000))); + unlockTerminal(); + ui->lineEdit_cmd->setFocus(); +} + +void MainWindow::lockTerminal() +{ + ui->lineEdit_cmd->setEnabled(false); + ui->pushButton_sendCmd->setEnabled(false); +} + +void MainWindow::unlockTerminal() +{ + ui->lineEdit_cmd->setEnabled(true); + ui->pushButton_sendCmd->setEnabled(true); +} + +void MainWindow::closeConnection() +{ + terminal.disconnect(); + connectionStatus->setText(tr("No hay ninguna conexión abierta")); + lockTerminal(); + disableTerminalActions(); + disableKinematics(); +} + +void MainWindow::getProgram(RhinoProg *prog) +{ + if (showFileOnTerminal) + { + insertTxtIntoTerm(prog->getCode()); + } + else + { + /*if (editorFile->path() == receivedProgFilePath) + { + QMessageBox questionBox(this); + QPushButton *ovBtn; // overwrite button + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea sobreescribir el fichero abierto en el editor?")); + questionBox.setInformativeText(tr("Ha elegido guardar el programa recibido en el " + "mismo archivo que hay abierto en el editor. ¿Seguro" + " que desea sobreescribir el fichero abierto en " + "el editor?")); + ovBtn = questionBox.addButton(tr("Sobreescribir"), QMessageBox::YesRole); + questionBox.addButton(tr("No sobreescribir"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == ovBtn) // if overwrite + { + editorFile->close(true); // save file and then close + delete editorFile; + + prog->setPath(receivedProgFilePath); + prog->save(); + qDebug(prog->getTxtCode().toStdString().c_str()); + editorFile = prog; + } + else // if not overwrite + delete prog; + } + else // if path of received file is different from file open in editor + { + prog->setPath(receivedProgFilePath); + prog->close(true); // save file and then close + qDebug(prog->getTxtCode().toStdString().c_str()); + delete prog; + }*/ + bool save = true; + + if (QFile::exists(receivedProgFilePath)) + { + QMessageBox questionBox(this); + QPushButton *ovBtn; // overwrite button + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea sobreescribir el fichero?")); + questionBox.setInformativeText(tr("El fichero que ha seleccionado " + "ya existe. ¿Seguro que desea " + "sobreescribir el fichero?")); + ovBtn = questionBox.addButton(tr("Sobreescribir"), QMessageBox::YesRole); + questionBox.addButton(tr("No sobreescribir"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == ovBtn) // if overwrite + QFile::remove(receivedProgFilePath); + else // if not overwrite + { + save = false; + ui->statusBar->showMessage(tr("Ha elegido no sobreescribir el " + "fichero")); + } + } + + if (save) + { + prog->saveToPath(receivedProgFilePath); + ui->statusBar->showMessage(tr("Programa recibido correctamente")); + } + showFileOnTerminal = true; + } + unlockTerminal(); + ui->lineEdit_cmd->setFocus(); +} + +void MainWindow::insertTxtIntoTerm(QString txt) +{ + ui->plainTextEdit_terminalView->insertPlainText(txt); + QScrollBar *sb = ui->plainTextEdit_terminalView->verticalScrollBar(); + sb->setValue(sb->maximum()-1); +} + +void MainWindow::closeEvent(QCloseEvent *event) +{ + bool quit = true; + if (terminal.isConnected()) + { + QMessageBox questionBox(this); + QPushButton *closeBtn; + questionBox.setIcon(QMessageBox::Question); + questionBox.setText(tr("¿Desea cerrar la conexión?")); + questionBox.setInformativeText(tr("Para salir del programa, deberá cerrar la conexión. " + "¿Desea cerrar la conexión con el controlador Mark IV?")); + closeBtn = questionBox.addButton(tr("Cerrar"), QMessageBox::YesRole); + questionBox.addButton(tr("No cerrar"), QMessageBox::NoRole); + questionBox.exec(); + if (questionBox.clickedButton() == closeBtn) + closeConnection(); + else + quit = false; + } + if (quit) + qApp->quit(); + else + event->ignore(); +} + +void MainWindow::on_actionErrorCodes_triggered() +{ + if (errorCodesDialog == NULL) + { + QVBoxLayout *layout = new QVBoxLayout(); + layout->addWidget(createErrorCodesTable()); + + errorCodesDialog = new QDialog(this); + errorCodesDialog->resize(500, 500); + errorCodesDialog->setWindowTitle(tr("MarkCommander") + " - " + + tr("Códigos de error de Rhino Mark IV")); + errorCodesDialog->setLayout(layout); + errorCodesDialog->show(); + } + else + { + errorCodesDialog->show(); + errorCodesDialog->raise(); + } +} + +void MainWindow::on_actionAboutThisApp_triggered() +{ + QHBoxLayout *layout = new QHBoxLayout(); + QLabel *appIcon = new QLabel(); + appIcon->setPixmap(QPixmap(":/icons/appicon3.png")); + layout->addWidget(appIcon); + QLabel *appInfo = new QLabel(tr("MarkCommander v0.1\n\n2011\nJonán Cruz Martín")); + appInfo->setStyleSheet("font: 14px"); + layout->addWidget(appInfo); + + QDialog aboutDialog(this); + aboutDialog.resize(200, 100); + aboutDialog.setWindowTitle(tr("Sobre MarkCommander")); + aboutDialog.setLayout(layout); + aboutDialog.exec(); +} + +void MainWindow::on_actionCommandRef_triggered() +{ + if (cmdRefDialog == NULL) + { + QVBoxLayout *layout = new QVBoxLayout(); + QWebView *webView = new QWebView(); + QFile webPage(":/files/mark-iv-commands.html"); + webPage.open(QFile::ReadOnly); + webView->setContent(webPage.readAll()); + layout->addWidget(webView); + + cmdRefDialog = new QDialog(this); + cmdRefDialog->resize(800, 800); + cmdRefDialog->setWindowTitle(tr("MarkCommander") + " - " + + tr("Referencia de comandos de Rhino Mark IV")); + cmdRefDialog->setLayout(layout); + cmdRefDialog->show(); + } + else + { + cmdRefDialog->show(); + cmdRefDialog->raise(); + } +} + +void MainWindow::on_actionHardHome_triggered() +{ + terminal.sendCmdAndTellMustWait("th"); + terminal.sendCmdAndTellMustWait("hh"); +} + +void MainWindow::enableTerminalActions() +{ + ui->actionTransmitProgram->setEnabled(true); + ui->actionReceiveProgram->setEnabled(true); + ui->actionCloseConnection->setEnabled(true); + ui->actionHardHome->setEnabled(true); + ui->actionSoftHome->setEnabled(true); + ui->actionConfigureController->setEnabled(true); + //ui->pushButton_dirkinGoToPos->setEnabled(true); + //ui->pushButton_invkinGoToPos->setEnabled(true); + ui->actionGoToKinHome->setEnabled(true); + ui->actionSetSoftHome->setEnabled(true); +} + +void MainWindow::disableTerminalActions() +{ + ui->actionTransmitProgram->setEnabled(false); + ui->actionReceiveProgram->setEnabled(false); + ui->actionCloseConnection->setEnabled(false); + ui->actionHardHome->setEnabled(false); + ui->actionSoftHome->setEnabled(false); + ui->actionConfigureController->setEnabled(false); + //ui->pushButton_dirkinGoToPos->setEnabled(false); + //ui->pushButton_invkinGoToPos->setEnabled(false); + ui->actionGoToKinHome->setEnabled(false); + ui->actionSetSoftHome->setEnabled(false); +} + +void MainWindow::on_actionSoftHome_triggered() +{ + terminal.sendCmdAndTellMustWait("th"); + moveMotorB(0, false); + moveMotorC(0, false); + moveMotorD(0, false); + moveMotorE(0, false); + moveMotorF(0, false); + terminal.sendCmdAndTellMustWait("mc"); + + bool checked = ui->checkBox_dirkinKeepDirkin->isChecked(); + ui->checkBox_dirkinKeepDirkin->setChecked(false); + + ui->dial_dirkinTheta5B->setValue(xr4.steps2deg(0, 'B')); + ui->dial_dirkinTheta4C->setValue(xr4.steps2deg(0, 'C')); + ui->dial_dirkinTheta3D->setValue(xr4.steps2deg(0, 'D')); + ui->dial_dirkinTheta2E->setValue(xr4.steps2deg(0, 'E')); + ui->dial_dirkinTheta1F->setValue(xr4.steps2deg(0, 'F')); + + ui->checkBox_dirkinKeepDirkin->setChecked(checked); +} + +void MainWindow::createConfigurationDialog() +{ + getConfigProgressDialog = new QProgressDialog(this, Qt::Popup); + getConfigProgressDialog->setCancelButton(0); + getConfigProgressDialog->setLabelText(tr("Esperando la configuración del controlador Mark IV")); + getConfigProgressDialog->setWindowModality(Qt::WindowModal); + getConfigProgressDialog->setMaximum(CMD_TIMEOUT/1000); + + getConfigTimer = new QTimer(); + getConfigTimer->setInterval(1000); // shoot timeout every second + connect(getConfigTimer, SIGNAL(timeout()), this, SLOT(getConfigTimerTimeout())); + + layout = new QVBoxLayout(); + grid = new QGridLayout(); + hbox = new QHBoxLayout(); + applyBtn = new QPushButton(tr("Apply configuration")); + closeBtn = new QPushButton(tr("Close")); + revertBtn = new QPushButton(tr("Revert configuration")); + + configBits[0] = new QComboBox(); // Bit 7 + configBits[0]->insertItem(0, tr("System is in pendant mode")); + configBits[0]->insertItem(1, tr("System is in host mode")); + + configBits[1] = new QComboBox(); // Bit 6 + configBits[1]->insertItem(0, tr("The pendant is disabled")); + configBits[1]->insertItem(1, tr("The pendant is enabled")); + configBits[1]->setEnabled(false); + + configBits[2] = new QComboBox(); // Bit 5 + configBits[2]->insertItem(0, tr("Robot controller mode")); + configBits[2]->insertItem(1, tr("Generic controller mode")); + + configBits[3] = new QComboBox(); // Bit 4 + configBits[3]->insertItem(0, tr("XR-3 mode")); + configBits[3]->insertItem(1, tr("SCARA mode")); + + configBits[4] = new QComboBox(); // Bit 3 + configBits[4]->insertItem(0, tr("The gripper is enabled")); + configBits[4]->insertItem(1, tr("The gripper is disabled")); + + configBits[5] = new QComboBox(); // Bit 2 + configBits[5]->insertItem(0, tr("Joint mode")); + configBits[5]->insertItem(1, tr("XYZ mode")); + + grid->addWidget(new QLabel(tr("System mode")), 0, 0); // Bit 7 + grid->addWidget(configBits[0], 0, 1); + + grid->addWidget(new QLabel(tr("Pendant status")), 1, 0); // Bit 6 + grid->addWidget(configBits[1], 1, 1); + + grid->addWidget(new QLabel(tr("Controller mode")), 2, 0); // Bit 5 + grid->addWidget(configBits[2], 2, 1); + + grid->addWidget(new QLabel(tr("Robot type")), 3, 0); // Bit 4 + grid->addWidget(configBits[3], 3, 1); + + grid->addWidget(new QLabel(tr("Gripper mode")), 4, 0); // Bit 3 + grid->addWidget(configBits[4], 4, 1); + + grid->addWidget(new QLabel(tr("Joint variables mode")), 5, 0); // Bit 2 + grid->addWidget(configBits[5], 5, 1); + + hbox->addWidget(applyBtn); + hbox->addWidget(revertBtn); + hbox->addWidget(closeBtn); + + layout->addLayout(grid); + layout->addLayout(hbox); + + configureControllerDialog = new QDialog(this); + configureControllerDialog->setWindowTitle(tr("Configuración del controlador Mark IV")); + configureControllerDialog->setLayout(layout); + + connect(configBits[0], SIGNAL(currentIndexChanged(int)), this, SLOT(systemModeChanged(int))); + // connect(configBits[1], SIGNAL(currentIndexChanged(int)), this, SLOT(pendantStatusChanged(int))); + connect(configBits[2], SIGNAL(currentIndexChanged(int)), this, SLOT(controllerModeChanged(int))); + connect(configBits[3], SIGNAL(currentIndexChanged(int)), this, SLOT(robotTypeChanged(int))); + connect(configBits[4], SIGNAL(currentIndexChanged(int)), this, SLOT(gripperModeChanged(int))); + connect(configBits[5], SIGNAL(currentIndexChanged(int)), this, SLOT(jointModeChanged(int))); + + connect(applyBtn, SIGNAL(clicked(bool)), this, SLOT(on_actionApplyConfiguration_triggered())); + connect(revertBtn, SIGNAL(clicked(bool)), this, SLOT(on_actionRevertConfiguration_triggered())); + connect(closeBtn, SIGNAL(clicked(bool)), this, SLOT(on_actionCloseConfiguration_triggered())); + connect(configureControllerDialog, SIGNAL(rejected()), this, SLOT(restoreSlotsAfterConfig())); +} + +void MainWindow::on_actionConfigureController_triggered() +{ + disconnect(&terminal, SIGNAL(receivedFullResponse(QString)), + this, SLOT(getCmdResponse(QString))); + disconnect(&terminal, SIGNAL(timeout(int)), this, SLOT(handleTimeout(int))); + + connect(&terminal, SIGNAL(receivedFullResponse(QString)), + this, SLOT(getConfiguration(QString))); + connect(&terminal, SIGNAL(timeout(int)), this, SLOT(handleConfigurationTimeout(int))); + + terminal.sendCmdAndTellMustWait("sc"); + showGetConfigProgressDialog(); +} + +void MainWindow::on_actionApplyConfiguration_triggered() +{ + terminal.sendCmdAndTellMustWait("th"); + + // Robot controller mode: set robot type (XR-3 / SCARA) + if ((configBitChanged[2] || configBitChanged[3]) + && configBits[2]->currentIndex() == 0) + { + terminal.sendCmdAndTellMustWait("cr," + QString::number(configBits[3]->currentIndex())); + } + // Generic controller mode + else if (configBitChanged[2] + && configBits[2]->currentIndex() == 1) + { + terminal.sendCmdAndTellMustWait("cr,2"); + } + + // Enable (1) / disable (0) gripper + if (configBitChanged[4]) + terminal.sendCmdAndTellMustWait("cg," + QString::number(1 - configBits[4]->currentIndex())); + + // Joint mode (0) / XYZ mode (1) + if (configBitChanged[5]) + terminal.sendCmdAndTellMustWait("cc," + QString::number(configBits[5]->currentIndex())); + + // Pendant (0) / Host (1) mode + if (configBits[0]->currentIndex() == 0) + terminal.sendCmdAndTellMustWait("tx"); + + terminal.sendCmdAndTellMustWait("sc"); + showGetConfigProgressDialog(); +} + +void MainWindow::on_actionRevertConfiguration_triggered() +{ + configBits[0]->setCurrentIndex(0); // Bit 7 + configBits[1]->setCurrentIndex(0); // Bit 6 + configBits[2]->setCurrentIndex(0); // Bit 5 + configBits[3]->setCurrentIndex(0); // Bit 4 + configBits[4]->setCurrentIndex(0); // Bit 3 + configBits[5]->setCurrentIndex(0); // Bit 2 +} + +void MainWindow::on_actionCloseConfiguration_triggered() +{ + configureControllerDialog->close(); +} + +void MainWindow::getConfiguration(QString configString) +{ + closeGetConfigProgressDialog(); + + int configByte = configString.toInt(); + + configBits[0]->setCurrentIndex((configByte & 128) >> 7); // Bit 7 + configBits[1]->setCurrentIndex((configByte & 64) >> 6); // Bit 6 + configBits[2]->setCurrentIndex((configByte & 32) >> 5); // Bit 5 + configBits[3]->setCurrentIndex((configByte & 16) >> 4); // Bit 4 + configBits[4]->setCurrentIndex((configByte & 8) >> 3); // Bit 3 + configBits[5]->setCurrentIndex((configByte & 2) >> 2); // Bit 2 + + configBitChanged[0] = false; + configBitChanged[1] = false; + configBitChanged[2] = false; + configBitChanged[3] = false; + configBitChanged[4] = false; + configBitChanged[5] = false; + + configureControllerDialog->exec(); +} + +void MainWindow::handleConfigurationTimeout(int time) +{ + qDebug("handleConfigurationTimeout"); + closeGetConfigProgressDialog(); + on_actionCloseConfiguration_triggered(); + restoreSlotsAfterConfig(); + QMessageBox::warning(this, + tr("Se ha agotado el tiempo"), + tr("Se ha agotado el tiempo de espera por los datos " + "de configuración. El controlador Mark IV no ha " + "respondido en los últimos %1 segundos.").arg(time/1000)); +} + +void MainWindow::restoreSlotsAfterConfig() +{ + qDebug("restoreSlotsAfterConfig"); + disconnect(&terminal, SIGNAL(receivedFullResponse(QString)), + this, SLOT(getConfiguration(QString))); + disconnect(&terminal, SIGNAL(timeout(int)), this, SLOT(handleConfigurationTimeout(int))); + + connect(&terminal, SIGNAL(receivedFullResponse(QString)), + this, SLOT(getCmdResponse(QString))); + connect(&terminal, SIGNAL(timeout(int)), this, SLOT(handleTimeout(int))); + + unlockTerminal(); +} + +void MainWindow::systemModeChanged(int curIndex) +{ + configBitChanged[0] = true; +} + +// void MainWindow::pendantStatusChanged(int curIndex); + +void MainWindow::controllerModeChanged(int curIndex) +{ + configBitChanged[2] = true; + if (curIndex == 0) // Robot controller mode + configBits[3]->setEnabled(true); + else // Generic controller mode + configBits[3]->setEnabled(false); +} + +void MainWindow::robotTypeChanged(int curIndex) +{ + configBitChanged[3] = true; +} + +void MainWindow::gripperModeChanged(int curIndex) +{ + configBitChanged[4] = true; +} + +void MainWindow::jointModeChanged(int curIndex) +{ + configBitChanged[5] = true; +} + +void MainWindow::getConfigTimerTimeout() +{ + getConfigProgressDialog->setValue(getConfigProgressDialog->value() + 1); +} + +void MainWindow::showGetConfigProgressDialog() +{ + lockTerminal(); + getConfigProgressDialog->show(); + getConfigTimer->start(); +} + +void MainWindow::closeGetConfigProgressDialog() +{ + qDebug("closeGetconfigProgressDialog"); + getConfigTimer->stop(); + getConfigProgressDialog->close(); +} + +void MainWindow::on_actionTerminal_triggered() +{ + ui->tabWidget_ctrlView->setCurrentIndex(0); +} + +void MainWindow::on_actionDirKin_triggered() +{ + ui->tabWidget_ctrlView->setCurrentIndex(1); +} + +void MainWindow::on_actionInvKin_triggered() +{ + ui->tabWidget_ctrlView->setCurrentIndex(2); +} + +void MainWindow::updateDirkin() +{ + double t1 = ui->doubleSpinBox_dirkinTheta1F->value(); + double t2 = ui->doubleSpinBox_dirkinTheta2E->value(); + double t3 = ui->doubleSpinBox_dirkinTheta3D->value(); + double t4 = ui->doubleSpinBox_dirkinTheta4C->value(); + double t5 = ui->doubleSpinBox_dirkinTheta5B->value(); + + JointAngles angles = JointAngles(t1, t2, t3, t4, t5); + const Matrix armMatrix = xr4.dirkin(angles); + + ui->lineEdit_dirkinArmMatrixN1->setText(QString::number((double)armMatrix.at(1, 1))); + ui->lineEdit_dirkinArmMatrixN2->setText(QString::number((double)armMatrix.at(2, 1))); + ui->lineEdit_dirkinArmMatrixN3->setText(QString::number((double)armMatrix.at(3, 1))); + + ui->lineEdit_dirkinArmMatrixS1->setText(QString::number((double)armMatrix.at(1, 2))); + ui->lineEdit_dirkinArmMatrixS2->setText(QString::number((double)armMatrix.at(2, 2))); + ui->lineEdit_dirkinArmMatrixS3->setText(QString::number((double)armMatrix.at(3, 2))); + + ui->lineEdit_dirkinArmMatrixA1->setText(QString::number((double)armMatrix.at(1, 3))); + ui->lineEdit_dirkinArmMatrixA2->setText(QString::number((double)armMatrix.at(2, 3))); + ui->lineEdit_dirkinArmMatrixA3->setText(QString::number((double)armMatrix.at(3, 3))); + + ui->lineEdit_dirkinArmMatrixP1->setText(QString::number((double)armMatrix.at(1, 4))); + ui->lineEdit_dirkinArmMatrixP2->setText(QString::number((double)armMatrix.at(2, 4))); + ui->lineEdit_dirkinArmMatrixP3->setText(QString::number((double)armMatrix.at(3, 4))); + + int incStepsE = xr4.deg2steps(t2 - 90, 'E', false); + int corSign = (nullify(t2 - 90) == 0.0 ? 1 : -1); + int incStepsD = corSign*(xr4.deg2steps(t3 + 90, 'D', false) + incStepsE); + + ui->plainTextEdit_dirkinCommands->setPlainText("pd,b," + QString::number((int)xr4.deg2steps(t5, 'B'))); + ui->plainTextEdit_dirkinCommands->appendPlainText("pd,c," + QString::number((int)xr4.deg2steps(t4, 'C') + incStepsD)); + ui->plainTextEdit_dirkinCommands->appendPlainText("pd,d," + QString::number((int)xr4.deg2steps(t3, 'D') + incStepsE)); + ui->plainTextEdit_dirkinCommands->appendPlainText("pd,e," + QString::number((int)xr4.deg2steps(t2, 'E'))); + ui->plainTextEdit_dirkinCommands->appendPlainText("pd,f," + QString::number((int)xr4.deg2steps(t1, 'F'))); + ui->plainTextEdit_dirkinCommands->appendPlainText("mc"); + + /*dirkinOldValue[0] = t1; + dirkinOldValue[1] = t2; + dirkinOldValue[2] = t3; + dirkinOldValue[3] = t4; + dirkinOldValue[4] = t5;*/ +} + +void MainWindow::on_doubleSpinBox_dirkinTheta1F_valueChanged(double angle) +{ + ui->dial_dirkinTheta1F->setValue(angle); + updateDirkin(); + /*dirkinOldValue[0] = angle;*/ +} + +void MainWindow::on_doubleSpinBox_dirkinTheta2E_valueChanged(double angle) +{ + ui->dial_dirkinTheta2E->setValue(angle); + /*if (ui->checkBox_dirkinKeepDirkin->isChecked()) + { + int inc = angle - dirkinOldValue[1]; + ui->doubleSpinBox_dirkinTheta3D->setValue(dirkinOldValue[2] - inc); + }*/ + updateDirkin(); + /*dirkinOldValue[1] = angle;*/ +} + +void MainWindow::on_doubleSpinBox_dirkinTheta3D_valueChanged(double angle) +{ + ui->dial_dirkinTheta3D->setValue(angle); + /*if (ui->checkBox_dirkinKeepDirkin->isChecked()) + { + int inc = angle - dirkinOldValue[2]; + ui->doubleSpinBox_dirkinTheta4C->setValue(dirkinOldValue[3] + inc); + }*/ + updateDirkin(); + /*dirkinOldValue[2] = angle;*/ +} + +void MainWindow::on_doubleSpinBox_dirkinTheta4C_valueChanged(double angle) +{ + ui->dial_dirkinTheta4C->setValue(angle); + updateDirkin(); + /*dirkinOldValue[3] = angle;*/ +} + +void MainWindow::on_doubleSpinBox_dirkinTheta5B_valueChanged(double angle) +{ + ui->dial_dirkinTheta5B->setValue(angle); + updateDirkin(); + /*dirkinOldValue[4] = angle;*/ +} + +void MainWindow::on_dial_dirkinTheta1F_valueChanged(int value) +{ + ui->doubleSpinBox_dirkinTheta1F->setValue(value); +} + +void MainWindow::on_dial_dirkinTheta2E_valueChanged(int value) +{ + ui->doubleSpinBox_dirkinTheta2E->setValue(value); +} + +void MainWindow::on_dial_dirkinTheta3D_valueChanged(int value) +{ + ui->doubleSpinBox_dirkinTheta3D->setValue(value); +} + +void MainWindow::on_dial_dirkinTheta4C_valueChanged(int value) +{ + ui->doubleSpinBox_dirkinTheta4C->setValue(value); +} + +void MainWindow::on_dial_dirkinTheta5B_valueChanged(int value) +{ + ui->doubleSpinBox_dirkinTheta5B->setValue(value); +} + +void MainWindow::on_pushButton_dirkinGoToPos_clicked() +{ + /*if (alreadyGoneToKinHome) + {*/ + terminal.sendCmdAndTellMustWait("th"); + QStringList cmds = ui->plainTextEdit_dirkinCommands->toPlainText().split('\n', QString::SkipEmptyParts); + for (int i = 0; i < cmds.size(); i++) + terminal.sendCmdAndTellMustWait(cmds.at(i)); + + dirkinOldValue[0] = ui->doubleSpinBox_dirkinTheta1F->value(); + dirkinOldValue[1] = ui->doubleSpinBox_dirkinTheta2E->value(); + dirkinOldValue[2] = ui->doubleSpinBox_dirkinTheta3D->value(); + dirkinOldValue[3] = ui->doubleSpinBox_dirkinTheta4C->value(); + dirkinOldValue[4] = ui->doubleSpinBox_dirkinTheta5B->value(); + /*} + else + { + QMessageBox::warning(this, + tr("El robot no ha hecho home"), + tr("El robot no ha hecho el home de la cinemática." + " Para poder usar la cinemática directa, debe " + "realizar el home de la cinemática.")); + }*/ +} + +void MainWindow::updateInvkin() +{ + Matrix matrix(4, 4); + + // N + matrix.at(1, 1) = ui->lineEdit_invkinArmMatrixN1->text().toDouble(); + matrix.at(2, 1) = ui->lineEdit_invkinArmMatrixN2->text().toDouble(); + matrix.at(3, 1) = ui->lineEdit_invkinArmMatrixN3->text().toDouble(); + // S + matrix.at(1, 2) = ui->lineEdit_invkinArmMatrixS1->text().toDouble(); + matrix.at(2, 2) = ui->lineEdit_invkinArmMatrixS2->text().toDouble(); + matrix.at(3, 2) = ui->lineEdit_invkinArmMatrixS3->text().toDouble(); + // A + matrix.at(1, 3) = ui->lineEdit_invkinArmMatrixA1->text().toDouble(); + matrix.at(2, 3) = ui->lineEdit_invkinArmMatrixA2->text().toDouble(); + matrix.at(3, 3) = ui->lineEdit_invkinArmMatrixA3->text().toDouble(); + // P + matrix.at(1, 4) = ui->lineEdit_invkinArmMatrixP1->text().toDouble(); + matrix.at(2, 4) = ui->lineEdit_invkinArmMatrixP2->text().toDouble(); + matrix.at(3, 4) = ui->lineEdit_invkinArmMatrixP3->text().toDouble(); + // Homogeneous coordinates + matrix.at(4, 1) = 0.0; + matrix.at(4, 2) = 0.0; + matrix.at(4, 3) = 0.0; + matrix.at(4, 4) = 1.0; + + JointAngles angles; + if (ui->comboBox_invkinVersion->currentIndex()) + angles = xr4.invkin(matrix); + else + angles = xr4.invkin2(matrix); + angles.t1 = rad2deg(angles.t1); + angles.t2 = rad2deg(angles.t2); + angles.t3 = rad2deg(angles.t3); + angles.t4 = rad2deg(angles.t4); + angles.t5 = rad2deg(angles.t5); + + ui->doubleSpinBox_invkinTheta1F->setValue(angles.t1); + ui->doubleSpinBox_invkinTheta2E->setValue(angles.t2); + ui->doubleSpinBox_invkinTheta3D->setValue(angles.t3); + ui->doubleSpinBox_invkinTheta4C->setValue(angles.t4); + ui->doubleSpinBox_invkinTheta5B->setValue(angles.t5); + + int incStepsE = xr4.deg2steps(angles.t2 - 90, 'E', false); + int corSign = (nullify(angles.t2 - 90) == 0.0 ? 1 : -1); + int incStepsD = corSign*(xr4.deg2steps(angles.t3 + 90, 'D', false) + incStepsE); + + ui->plainTextEdit_invkinCommands->setPlainText("pd,b," + QString::number((int)xr4.deg2steps(angles.t5, 'B'))); + ui->plainTextEdit_invkinCommands->appendPlainText("pd,c," + QString::number((int)xr4.deg2steps(angles.t4, 'C') + incStepsD)); + ui->plainTextEdit_invkinCommands->appendPlainText("pd,d," + QString::number((int)xr4.deg2steps(angles.t3, 'D') + incStepsE)); + ui->plainTextEdit_invkinCommands->appendPlainText("pd,e," + QString::number((int)xr4.deg2steps(angles.t2, 'E'))); + ui->plainTextEdit_invkinCommands->appendPlainText("pd,f," + QString::number((int)xr4.deg2steps(angles.t1, 'F'))); + ui->plainTextEdit_invkinCommands->appendPlainText("mc"); + + /*dirkinOldValue[0] = angles.t1; + dirkinOldValue[1] = angles.t2; + dirkinOldValue[2] = angles.t3; + dirkinOldValue[3] = angles.t4; + dirkinOldValue[4] = angles.t5;*/ +} + +void MainWindow::on_doubleSpinBox_invkinTheta1F_valueChanged(double angle) +{ + ui->dial_invkinTheta1F->setValue(angle); +} + +void MainWindow::on_doubleSpinBox_invkinTheta2E_valueChanged(double angle) +{ + ui->dial_invkinTheta2E->setValue(angle); +} + +void MainWindow::on_doubleSpinBox_invkinTheta3D_valueChanged(double angle) +{ + ui->dial_invkinTheta3D->setValue(angle); +} + +void MainWindow::on_doubleSpinBox_invkinTheta4C_valueChanged(double angle) +{ + ui->dial_invkinTheta4C->setValue(angle); +} + +void MainWindow::on_doubleSpinBox_invkinTheta5B_valueChanged(double angle) +{ + ui->dial_invkinTheta5B->setValue(angle); +} + +void MainWindow::on_lineEdit_invkinArmMatrixN1_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixN2_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixN3_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixS1_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixS2_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixS3_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixA1_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixA2_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixA3_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixP1_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixP2_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::on_lineEdit_invkinArmMatrixP3_textChanged(QString newText) +{ + updateInvkin(); +} + +void MainWindow::moveMotorB(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pd,b," + QString::number(steps)); + xr4.angles.t5 = xr4.steps2deg(steps, 'B'); +} + +void MainWindow::moveMotorC(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pd,c," + QString::number(steps)); + xr4.angles.t4 = xr4.steps2deg(steps, 'C'); +} + +void MainWindow::moveMotorD(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pd,d," + QString::number(steps)); + if (keepKin) + moveMotorCRel(xr4.deg2steps(xr4.angles.t3, 'D') - steps, keepKin); + xr4.angles.t3 = xr4.steps2deg(steps, 'D'); +} + +void MainWindow::moveMotorE(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pd,e," + QString::number(steps)); + if (keepKin) + moveMotorDRel(xr4.deg2steps(xr4.angles.t2, 'E') - steps, keepKin); + xr4.angles.t2 = xr4.steps2deg(steps, 'E'); +} + +void MainWindow::moveMotorF(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pd,f," + QString::number(steps)); + xr4.angles.t1 = xr4.steps2deg(steps, 'F'); +} + +void MainWindow::moveMotorCRel(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pr,c," + QString::number(steps)); + xr4.angles.t4 += xr4.steps2deg(steps, 'C'); +} + +void MainWindow::moveMotorDRel(int steps, bool keepKin) +{ + terminal.sendCmdAndTellMustWait("pr,d," + QString::number(steps)); + if (keepKin) + moveMotorCRel(-steps, keepKin); + xr4.angles.t3 += xr4.steps2deg(steps, 'D'); +} + +void MainWindow::on_pushButton_invkinGoToPos_clicked() +{ + /*if (alreadyGoneToKinHome) + {*/ + terminal.sendCmdAndTellMustWait("th"); + QStringList cmds = ui->plainTextEdit_invkinCommands->toPlainText().split('\n', QString::SkipEmptyParts); + for (int i = 0; i < cmds.size(); i++) + terminal.sendCmdAndTellMustWait(cmds.at(i)); + + dirkinOldValue[0] = ui->doubleSpinBox_invkinTheta1F->value(); + dirkinOldValue[1] = ui->doubleSpinBox_invkinTheta2E->value(); + dirkinOldValue[2] = ui->doubleSpinBox_invkinTheta3D->value(); + dirkinOldValue[3] = ui->doubleSpinBox_invkinTheta4C->value(); + dirkinOldValue[4] = ui->doubleSpinBox_invkinTheta5B->value(); + /*} + else + { + QMessageBox::warning(this, + tr("El robot no ha hecho home"), + tr("El robot no ha hecho el home de la cinemática." + " Para poder usar la cinemática inversa, debe " + "realizar el home de la cinemática.")); + }*/ +} + +void MainWindow::on_pushButton_copyDirkin_clicked() +{ + // N + ui->lineEdit_invkinArmMatrixN1->setText(ui->lineEdit_dirkinArmMatrixN1->text()); + ui->lineEdit_invkinArmMatrixN2->setText(ui->lineEdit_dirkinArmMatrixN2->text()); + ui->lineEdit_invkinArmMatrixN3->setText(ui->lineEdit_dirkinArmMatrixN3->text()); + // S + ui->lineEdit_invkinArmMatrixS1->setText(ui->lineEdit_dirkinArmMatrixS1->text()); + ui->lineEdit_invkinArmMatrixS2->setText(ui->lineEdit_dirkinArmMatrixS2->text()); + ui->lineEdit_invkinArmMatrixS3->setText(ui->lineEdit_dirkinArmMatrixS3->text()); + // A + ui->lineEdit_invkinArmMatrixA1->setText(ui->lineEdit_dirkinArmMatrixA1->text()); + ui->lineEdit_invkinArmMatrixA2->setText(ui->lineEdit_dirkinArmMatrixA2->text()); + ui->lineEdit_invkinArmMatrixA3->setText(ui->lineEdit_dirkinArmMatrixA3->text()); + // P + ui->lineEdit_invkinArmMatrixP1->setText(ui->lineEdit_dirkinArmMatrixP1->text()); + ui->lineEdit_invkinArmMatrixP2->setText(ui->lineEdit_dirkinArmMatrixP2->text()); + ui->lineEdit_invkinArmMatrixP3->setText(ui->lineEdit_dirkinArmMatrixP3->text()); +} + +void MainWindow::on_actionGoToKinHome_triggered() +{ + terminal.sendCmdAndTellMustWait("th"); + moveMotorB(0, false); + moveMotorC(0, false); + moveMotorD(0, false); + moveMotorE(1200, false); // Home de la cinemática: 1196 + moveMotorF(0, false); + terminal.sendCmdAndTellMustWait("mc"); + while (terminal.sendCmdSynchronous("ss") == "128"); + terminal.sendCmdAndTellMustWait("ac,e"); + + enableKinematics(); + + //bool checked = ui->checkBox_dirkinKeepDirkin->isChecked(); + //ui->checkBox_dirkinKeepDirkin->setChecked(false); + + ui->dial_dirkinTheta5B->setValue(xr4.steps2deg(0, 'B')); + ui->dial_dirkinTheta4C->setValue(xr4.steps2deg(0, 'C')); + ui->dial_dirkinTheta3D->setValue(xr4.steps2deg(0, 'D')); + ui->dial_dirkinTheta2E->setValue(xr4.steps2deg(0, 'E')); // antes: 1200 (por home cinemática) + ui->dial_dirkinTheta1F->setValue(xr4.steps2deg(0, 'F')); + + dirkinOldValue[0] = 90; + dirkinOldValue[1] = 90; + dirkinOldValue[2] = -90; + dirkinOldValue[3] = 0; + dirkinOldValue[4] = 180; + + updateDirkin(); + + //ui->checkBox_dirkinKeepDirkin->setChecked(checked); +} + +void MainWindow::on_actionSetSoftHome_triggered() +{ + terminal.sendCmdAndTellMustWait("th"); + terminal.sendCmdAndTellMustWait("ac,b"); + terminal.sendCmdAndTellMustWait("ac,c"); + terminal.sendCmdAndTellMustWait("ac,d"); + terminal.sendCmdAndTellMustWait("ac,e"); + terminal.sendCmdAndTellMustWait("ac,f"); + on_actionSoftHome_triggered(); +} + +void MainWindow::on_pushButton_copyInvkin_clicked() +{ + ui->doubleSpinBox_dirkinTheta1F->setValue(ui->doubleSpinBox_invkinTheta1F->value()); + ui->doubleSpinBox_dirkinTheta2E->setValue(ui->doubleSpinBox_invkinTheta2E->value()); + ui->doubleSpinBox_dirkinTheta3D->setValue(ui->doubleSpinBox_invkinTheta3D->value()); + ui->doubleSpinBox_dirkinTheta4C->setValue(ui->doubleSpinBox_invkinTheta4C->value()); + ui->doubleSpinBox_dirkinTheta5B->setValue(ui->doubleSpinBox_invkinTheta5B->value()); +} + +void MainWindow::on_comboBox_invkinVersion_currentIndexChanged(int index) +{ + updateInvkin(); +} + +void MainWindow::on_pushButton_computeDirKin_clicked() +{ + updateDirkin(); +} + +void MainWindow::on_pushButton_computeInvKin_clicked() +{ + updateInvkin(); +} + +void MainWindow::enableKinematics() +{ + /*ui->doubleSpinBox_dirkinTheta1F->setEnabled(true); + ui->doubleSpinBox_dirkinTheta2E->setEnabled(true); + ui->doubleSpinBox_dirkinTheta3D->setEnabled(true); + ui->doubleSpinBox_dirkinTheta4C->setEnabled(true); + ui->doubleSpinBox_dirkinTheta5B->setEnabled(true); + + ui->dial_dirkinTheta1F->setEnabled(true); + ui->dial_dirkinTheta2E->setEnabled(true); + ui->dial_dirkinTheta3D->setEnabled(true); + ui->dial_dirkinTheta4C->setEnabled(true); + ui->dial_dirkinTheta5B->setEnabled(true); + + ui->pushButton_copyDirkin->setEnabled(true); + ui->pushButton_computeDirKin->setEnabled(true);*/ + + ui->label_dirkinWarning->setVisible(false); + ui->label_invkinWarning->setVisible(false); + ui->pushButton_dirkinGoToPos->setVisible(true); + ui->pushButton_invkinGoToPos->setVisible(true); +} + +void MainWindow::disableKinematics() +{ + ui->label_dirkinWarning->setVisible(true); + ui->label_invkinWarning->setVisible(true); + ui->pushButton_dirkinGoToPos->setVisible(false); + ui->pushButton_invkinGoToPos->setVisible(false); +} diff --git a/mainwindow.hpp b/mainwindow.hpp new file mode 100644 index 0000000..550c003 --- /dev/null +++ b/mainwindow.hpp @@ -0,0 +1,173 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MAINWINDOW_H +#define MAINWINDOW_H + +#include +#include +#include +#include +#include +#include +#include + +#include "terminal.hpp" +#include "rhinoprog.hpp" +#include "rhino_xr4.hpp" + +namespace Ui { + class MainWindow; +} + +class MainWindow : public QMainWindow +{ + Q_OBJECT + +public: + explicit MainWindow(QWidget *parent = 0); + ~MainWindow(); + +private: + Ui::MainWindow *ui; + + Terminal terminal; + RhinoProg *editorProg; + QString receivedProgFilePath; + bool showFileOnTerminal; + QLabel *connectionStatus; + QLabel *editorFileStatus; + QDialog *errorCodesDialog; + QDialog *cmdRefDialog; + + QProgressDialog *getConfigProgressDialog; + QTimer *getConfigTimer; + + QDialog *configureControllerDialog; + QVBoxLayout *layout; + QGridLayout *grid; + QHBoxLayout *hbox; + QComboBox *configBits[6]; + bool configBitChanged[6]; + QPushButton *applyBtn; + QPushButton *closeBtn; + QPushButton *revertBtn; + + RhinoXR4 xr4; + + double dirkinOldValue[5]; + + //bool alreadyGoneToKinHome; + + void insertPrompt(); + void lockTerminal(); + void unlockTerminal(); + void closeConnection(); + void insertTxtIntoTerm(QString txt); + void enableTerminalActions(); + void disableTerminalActions(); + void createConfigurationDialog(); + void showGetConfigProgressDialog(); + void closeGetConfigProgressDialog(); + void updateDirkin(); + void updateInvkin(); + void enableKinematics(); + void disableKinematics(); + + void moveMotorB(int steps, bool keepKin); + void moveMotorC(int steps, bool keepKin); + void moveMotorD(int steps, bool keepKin); + void moveMotorE(int steps, bool keepKin); + void moveMotorF(int steps, bool keepKin); + void moveMotorCRel(int steps, bool keepKin); + void moveMotorDRel(int steps, bool keepKin); + +private slots: + void on_pushButton_computeInvKin_clicked(); + void on_pushButton_computeDirKin_clicked(); + void on_comboBox_invkinVersion_currentIndexChanged(int index); + void on_pushButton_copyInvkin_clicked(); + void on_actionSetSoftHome_triggered(); + void on_actionGoToKinHome_triggered(); + void on_pushButton_copyDirkin_clicked(); + void on_pushButton_invkinGoToPos_clicked(); + void on_lineEdit_invkinArmMatrixP3_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixP2_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixP1_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixA3_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixA2_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixA1_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixS3_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixS2_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixS1_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixN3_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixN2_textChanged(QString newText); + void on_lineEdit_invkinArmMatrixN1_textChanged(QString newText); + void on_doubleSpinBox_invkinTheta5B_valueChanged(double angle); + void on_doubleSpinBox_invkinTheta4C_valueChanged(double angle); + void on_doubleSpinBox_invkinTheta3D_valueChanged(double angle); + void on_doubleSpinBox_invkinTheta2E_valueChanged(double angle); + void on_doubleSpinBox_invkinTheta1F_valueChanged(double angle); + void on_pushButton_dirkinGoToPos_clicked(); + void on_dial_dirkinTheta5B_valueChanged(int value); + void on_dial_dirkinTheta4C_valueChanged(int value); + void on_dial_dirkinTheta3D_valueChanged(int value); + void on_dial_dirkinTheta2E_valueChanged(int value); + void on_dial_dirkinTheta1F_valueChanged(int value); + void on_doubleSpinBox_dirkinTheta5B_valueChanged(double angle); + void on_doubleSpinBox_dirkinTheta4C_valueChanged(double angle); + void on_doubleSpinBox_dirkinTheta3D_valueChanged(double angle); + void on_doubleSpinBox_dirkinTheta2E_valueChanged(double angle); + void on_doubleSpinBox_dirkinTheta1F_valueChanged(double angle); + void on_actionInvKin_triggered(); + void on_actionDirKin_triggered(); + void on_actionTerminal_triggered(); + void on_actionConfigureController_triggered(); + void on_actionSoftHome_triggered(); + void on_actionHardHome_triggered(); + void on_actionCommandRef_triggered(); + void on_actionAboutThisApp_triggered(); + void on_actionErrorCodes_triggered(); + void on_actionClearTerminal_triggered(); + void on_actionSaveTerminalOutput_triggered(); + void on_actionCloseConnection_triggered(); + void on_actionConnectToController_triggered(); + void on_actionReceiveProgram_triggered(); + void on_actionTransmitProgram_triggered(); + void on_pushButton_sendCmd_clicked(); + void quitApp(); + +public slots: + void getCmdResponse(QString response); + void handleTimeout(int time); + void getProgram(RhinoProg *prog); + void getConfiguration(QString configString); + void handleConfigurationTimeout(int time); + void on_actionApplyConfiguration_triggered(); + void on_actionRevertConfiguration_triggered(); + void on_actionCloseConfiguration_triggered(); + void restoreSlotsAfterConfig(); + void systemModeChanged(int curIndex); + // void pendantStatusChanged(int curIndex); + void controllerModeChanged(int curIndex); + void robotTypeChanged(int curIndex); + void gripperModeChanged(int curIndex); + void jointModeChanged(int curIndex); + void getConfigTimerTimeout(); + +protected: + void closeEvent(QCloseEvent *event); +}; + +#endif // MAINWINDOW_H diff --git a/mainwindow.ui b/mainwindow.ui new file mode 100644 index 0000000..3738c4d --- /dev/null +++ b/mainwindow.ui @@ -0,0 +1,1719 @@ + + + MainWindow + + + + 0 + 0 + 831 + 595 + + + + MarkCommander + + + + + + + true + + + 0 + + + + Terminal + + + + + + false + + + font: 12pt "Courier New"; +color: rgb(186, 186, 186); +background-color: rgb(0, 0, 0); + + + true + + + + + + + + + font: 12pt "Courier New"; + + + >> + + + + + + + false + + + font: 12pt "Courier New"; + + + + + + + false + + + Enviar comando + + + + + + + + + + Cinemática directa + + + + + + Espacio de articulaciones (ángulos) + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor F (θ</span><span style=" font-weight:600; vertical-align:sub;">1</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor E (θ</span><span style=" font-weight:600; vertical-align:sub;">2</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">Motor D (θ</span><span style=" font-size:8pt; font-weight:600; vertical-align:sub;">3</span><span style=" font-size:8pt; font-weight:600;">)</span></p></body></html> + + + + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor C (θ</span><span style=" font-weight:600; vertical-align:sub;">4</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">Motor B (θ</span><span style=" font-size:8pt; font-weight:600; vertical-align:sub;">5</span><span style=" font-size:8pt; font-weight:600;">)</span></p></body></html> + + + + + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Preservar ángulos de las otras articulaciones + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Copiar cinemática inversa + + + + + + + Calcular cinemática directa + + + + + + + + + + + + + + Matriz del brazo + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + true + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + 1 + + + Qt::AlignCenter + + + true + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">N</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">S</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">A</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">P</span></p></body></html> + + + + + + + Qt::AlignCenter + + + true + + + + + + + Qt::AlignCenter + + + true + + + + + + + + + + Instrucciones + + + + + + true + + + + + + + font-weight: bold; +color: rgb(170, 0, 0); +/*background-color: red;*/ +padding: 2px; + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:600; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt;">Debe hacer el home</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt;">de la cinemática</span></p></body></html> + + + + + + + Ir a la posición + + + + + + + + + + + + + Cinemática inversa + + + + + + Matriz del brazo + + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">N</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">S</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">A</span></p></body></html> + + + + + + + + 0 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">P</span></p></body></html> + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + Qt::AlignCenter + + + false + + + + + + + true + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + 0 + + + Qt::AlignCenter + + + true + + + + + + + true + + + 1 + + + Qt::AlignCenter + + + true + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + Cinemática inversa de clase + + + + + Cinemática inversa propia + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Copiar cinemática directa + + + + + + + Calcular cinemática inversa + + + + + + + + + + + + + + Espacio de articulaciones (ángulos) + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor F (θ</span><span style=" font-weight:600; vertical-align:sub;">1</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + true + + + + + + + true + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor E (θ</span><span style=" font-weight:600; vertical-align:sub;">2</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + true + + + false + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">Motor D (θ</span><span style=" font-size:8pt; font-weight:600; vertical-align:sub;">3</span><span style=" font-size:8pt; font-weight:600;">)</span></p></body></html> + + + + + + + true + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-weight:600;">Motor C (θ</span><span style=" font-weight:600; vertical-align:sub;">4</span><span style=" font-weight:600;">)</span></p></body></html> + + + + + + + true + + + + + + + + + + + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt; font-weight:600;">Motor B (θ</span><span style=" font-size:8pt; font-weight:600; vertical-align:sub;">5</span><span style=" font-size:8pt; font-weight:600;">)</span></p></body></html> + + + + + + + true + + + + + + + + + + + + + + + Instrucciones + + + + + + true + + + + + + + font-weight: bold; +color: rgb(170, 0, 0); +/*background-color: red;*/ +padding: 2px; + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> +<html><head><meta name="qrichtext" content="1" /><style type="text/css"> +p, li { white-space: pre-wrap; } +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:600; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt;">Debe hacer el home</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt;">de la cinemática</span></p></body></html> + + + + + + + Ir a la posición + + + + + + + + + + + + + + + + + + 0 + 0 + 831 + 22 + + + + + &Terminal + + + + + + + + + + + + + + true + + + &Ayuda + + + + + + + + + + &Robot + + + + + + + + + + + &Ventana + + + + + + + + + + + + + + TopToolBarArea + + + false + + + + + + + + + + + + + + + + + + + + + + + + + + false + + + + :/icons/filenew.png:/icons/filenew.png + + + Nuevo archivo + + + Ctrl+N + + + true + + + + + + :/icons/clear_term.png:/icons/clear_term.png + + + Borrar pantalla del terminal + + + Ctrl+K + + + + + + :/icons/stock_exit.png:/icons/stock_exit.png + + + Salir de MarkCommander + + + Ctrl+Q + + + + + false + + + + :/icons/fileopen.png:/icons/fileopen.png + + + Abrir archivo + + + Ctrl+O + + + + + false + + + Abrir reciente + + + + + false + + + + :/icons/gtk-close.png:/icons/gtk-close.png + + + Cerrar archivo + + + Ctrl+W + + + + + false + + + + :/icons/1300233417_document-save.png:/icons/1300233417_document-save.png + + + Guardar archivo + + + Ctrl+S + + + + + false + + + + :/icons/1300233422_document-save-as.png:/icons/1300233422_document-save-as.png + + + Guardar archivo como... + + + Ctrl+Shift+S + + + + + + :/icons/save_term_buffer.png:/icons/save_term_buffer.png + + + Guardar texto del terminal... + + + Ctrl+Alt+S + + + + + + :/icons/1300233114_utilities-terminal.png:/icons/1300233114_utilities-terminal.png + + + Conectar con el controlador + + + Ctrl+Alt+O + + + + + false + + + + :/icons/up.png:/icons/up.png + + + Transmitir programa + + + Ctrl+T + + + + + false + + + + :/icons/down.png:/icons/down.png + + + Recibir programa + + + Ctrl+R + + + + + false + + + + :/icons/close_term.png:/icons/close_term.png + + + Cerrar conexión + + + Cerrar conexión + + + Ctrl+Alt+W + + + + + false + + + + :/icons/edit-cut.png:/icons/edit-cut.png + + + Cortar + + + Ctrl+X + + + + + false + + + + :/icons/edit-copy.png:/icons/edit-copy.png + + + Copiar + + + Ctrl+C + + + + + false + + + + :/icons/edit-paste.png:/icons/edit-paste.png + + + Pegar + + + Ctrl+V + + + + + false + + + + :/icons/edit-select-all.png:/icons/edit-select-all.png + + + Seleccionar todo + + + Ctrl+A + + + + + false + + + + :/icons/edit-undo.png:/icons/edit-undo.png + + + Deshacer + + + Ctrl+Z + + + true + + + + + false + + + + :/icons/edit-redo.png:/icons/edit-redo.png + + + Rehacer + + + Ctrl+Shift+Z + + + + + false + + + Buscar... + + + Ctrl+F + + + + + false + + + Ir a la línea... + + + Ctrl+G + + + + + false + + + Ayuda de MarkCommander + + + + + true + + + Referencia de comandos de Rhino Mark IV + + + + + Sobre MarkCommander... + + + + + false + + + Preferencias... + + + + + true + + + Códigos de error de Rhino Mark IV + + + + + false + + + Hacer hard home + + + + + false + + + Ir a soft home + + + + + false + + + Configurar controlador... + + + Ctrl+, + + + + + Terminal + + + Alt+1 + + + + + Cinemática directa + + + Alt+2 + + + + + Cinemática inversa + + + Alt+3 + + + + + Control manual + + + Alt+4 + + + + + false + + + Almacenar posición actual como soft home + + + true + + + + + false + + + Ir a home de la cinemática + + + + + + + CmdLineEdit + QLineEdit +
cmdlineedit.hpp
+
+
+ + tabWidget_ctrlView + lineEdit_cmd + pushButton_sendCmd + doubleSpinBox_dirkinTheta1F + doubleSpinBox_dirkinTheta2E + doubleSpinBox_dirkinTheta3D + doubleSpinBox_dirkinTheta4C + doubleSpinBox_dirkinTheta5B + lineEdit_dirkinArmMatrixN1 + lineEdit_dirkinArmMatrixN2 + lineEdit_dirkinArmMatrixN3 + lineEdit_dirkinArmMatrixS1 + lineEdit_dirkinArmMatrixS2 + lineEdit_dirkinArmMatrixS3 + lineEdit_dirkinArmMatrixA1 + lineEdit_dirkinArmMatrixA2 + lineEdit_dirkinArmMatrixA3 + lineEdit_dirkinArmMatrixP1 + lineEdit_dirkinArmMatrixP2 + lineEdit_dirkinArmMatrixP3 + plainTextEdit_dirkinCommands + pushButton_dirkinGoToPos + lineEdit_invkinArmMatrixN1 + lineEdit_invkinArmMatrixN2 + lineEdit_invkinArmMatrixN3 + lineEdit_invkinArmMatrixS1 + lineEdit_invkinArmMatrixS2 + lineEdit_invkinArmMatrixS3 + lineEdit_invkinArmMatrixA1 + lineEdit_invkinArmMatrixA2 + lineEdit_invkinArmMatrixA3 + lineEdit_invkinArmMatrixP1 + lineEdit_invkinArmMatrixP2 + lineEdit_invkinArmMatrixP3 + doubleSpinBox_invkinTheta1F + doubleSpinBox_invkinTheta2E + doubleSpinBox_invkinTheta3D + doubleSpinBox_invkinTheta4C + doubleSpinBox_invkinTheta5B + plainTextEdit_invkinCommands + pushButton_invkinGoToPos + lineEdit_30 + lineEdit_14 + dial_dirkinTheta2E + lineEdit_15 + dial_invkinTheta4C + lineEdit_16 + dial_invkinTheta5B + dial_dirkinTheta4C + dial_dirkinTheta1F + plainTextEdit_terminalView + dial_invkinTheta2E + dial_dirkinTheta5B + lineEdit_27 + dial_invkinTheta3D + dial_invkinTheta1F + lineEdit_28 + dial_dirkinTheta3D + lineEdit_29 + lineEdit_13 + + + + + + + lineEdit_cmd + returnPressed() + pushButton_sendCmd + click() + + + 228 + 961 + + + 228 + 961 + + + + + MainWindow + destroyed() + MainWindow + quitApp() + + + 326 + 292 + + + 326 + 292 + + + + + actionQuit + triggered() + MainWindow + quitApp() + + + -1 + -1 + + + 326 + 292 + + + + + + quitApp() + +
diff --git a/matrix.cpp b/matrix.cpp new file mode 100644 index 0000000..73a2cad --- /dev/null +++ b/matrix.cpp @@ -0,0 +1,155 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "matrix.hpp" + +#include +using namespace std; + +Matrix::Matrix(uint rows, uint cols) +{ + _rows = rows; + _cols = cols; + + array = new real*[rows]; + for (uint i = 0; i < rows; i++) + { + array[i] = new real[cols]; + for (uint j = 0; j < cols; j++) + array[i][j] = 0; + } +} + +Matrix::~Matrix() +{ + for (uint i = 0; i < rows(); i++) + delete[] array[i]; + delete[] array; +} + +uint Matrix::rows() const +{ + return _rows; +} + +uint Matrix::cols() const +{ + return _cols; +} + +real Matrix::at(uint row, uint col) const +{ + if (row < 1 || row > rows() || col < 1 || col > cols()) + throw new OutOfRange(); + return array[row - 1][col - 1]; +} + +real & Matrix::at(uint row, uint col) +{ + if (row < 1 || row > rows() || col < 1 || col > cols()) + throw new OutOfRange(); + return array[row - 1][col - 1]; +} + +/* + * http://en.wikipedia.org/wiki/Assignment_operator_in_C%2B%2B + */ +Matrix & Matrix::operator=(const Matrix &matrix) +{ + if (this != &matrix) // protect against self-assignment + { + real **new_array = new real*[matrix.rows()]; + for (uint i = 0; i < matrix.rows(); i++) + { + new_array[i] = new real[matrix.cols()]; + for (uint j = 0; j < matrix.cols(); j++) + new_array[i][j] = matrix.at(i+1, j+1); + delete[] array[i]; + } + delete[] array; + array = new_array; + _rows = matrix.rows(); + _cols = matrix.cols(); + } + return *this; +} + +Matrix Matrix::operator+(const Matrix &matrix) const +{ + if (rows() != matrix.rows() || cols() != matrix.cols()) + throw new IncompatibleDimensions(); + + Matrix new_matrix(rows(), cols()); + for (uint i = 0; i < rows(); i++) + { + for (uint j = 0; j < cols(); j++) + new_matrix.at(i+1, j+1) = array[i][j] + matrix.at(i+1, j+1); + } + return new_matrix; +} + +Matrix Matrix::operator-(const Matrix &matrix) const +{ + if (rows() != matrix.rows() || cols() != matrix.cols()) + throw new IncompatibleDimensions(); + + Matrix new_matrix(rows(), cols()); + for (uint i = 0; i < rows(); i++) + { + for (uint j = 0; j < cols(); j++) + new_matrix.at(i+1, j+1) = array[i][j] - matrix.at(i+1, j+1); + } + return new_matrix; +} + +Matrix Matrix::operator*(const Matrix &matrix) const +{ + if (cols() != matrix.rows()) + throw new IncompatibleDimensions(); + + Matrix new_matrix(rows(), matrix.cols()); + for (uint i = 0; i < rows(); i++) + { + for (uint j = 0; j < matrix.cols(); j++) + { + for (uint k = 0; k < cols(); k++) + new_matrix.at(i+1, j+1) += array[i][k] * matrix.at(k+1, j+1); + } + } + return new_matrix; +} + +void Matrix::print() +{ + cout << endl; + for (uint i = 1; i <= rows(); i++) + { + for (uint j = 1; j <= cols(); j++) + cout << at(i, j) << "\t"; + cout << endl; + } + cout << endl; +} + +OutOfRange::OutOfRange() +{ + _description = "Index out of range"; + setMessage("Index out of range"); +} + +IncompatibleDimensions::IncompatibleDimensions() +{ + _description = "Incompatible dimensions"; + setMessage("Incompatible dimensions"); +} diff --git a/matrix.hpp b/matrix.hpp new file mode 100644 index 0000000..a6950a3 --- /dev/null +++ b/matrix.hpp @@ -0,0 +1,54 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MATRIX_HPP_8BSA1YFN +#define MATRIX_HPP_8BSA1YFN + +#include "exception.hpp" + +typedef unsigned int uint; +typedef long double real; + +class Matrix { + uint _rows; + uint _cols; + real **array; + +public: + Matrix(uint rows, uint cols); + ~Matrix(); + uint rows() const; + uint cols() const; + real at(uint row, uint col) const; + real & at(uint row, uint col); + Matrix & operator=(const Matrix &matrix); + Matrix operator+(const Matrix &matrix) const; + Matrix operator-(const Matrix &matrix) const; + Matrix operator*(const Matrix &matrix) const; + void print(); +}; + +class OutOfRange : Exception +{ +public: + OutOfRange(); +}; + +class IncompatibleDimensions : Exception +{ +public: + IncompatibleDimensions(); +}; + +#endif /* end of include guard: MATRIX_HPP_8BSA1YFN */ diff --git a/rhino_xr4.cpp b/rhino_xr4.cpp new file mode 100644 index 0000000..d2c5a28 --- /dev/null +++ b/rhino_xr4.cpp @@ -0,0 +1,408 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rhino_xr4.hpp" + +#include + +#include +using namespace std; + +real nullify(real num) +{ + if (abs(num) < TOL) + return 0.0; + else + return num; +} + +float truncate(float num) +{ + long x = 1000 * num; + float y = (float)x / (float)1000; + return y; +} + +real sign(real num) +{ + return (num < 0.0 ? -1 : 1); +} + +real deg2rad(real angle) +{ + return (PI*angle)/180; +} + +real rad2deg(real angle) +{ + return (angle*180)/PI; +} + +JointAngles::JointAngles(real t1, real t2, real t3, real t4, real t5) +{ + this->t1 = deg2rad(t1); + this->t2 = deg2rad(t2); + this->t3 = deg2rad(t3); + this->t4 = deg2rad(t4); + this->t5 = deg2rad(t5); +} + +Range::Range(real min, real max) +{ + this->min = min; + this->max = max; +} + +void JointAngles::print() +{ + cout << "t1 = " << rad2deg(t1) << " degrees" << endl; + cout << "t2 = " << rad2deg(t2) << " degrees" << endl; + cout << "t3 = " << rad2deg(t3) << " degrees" << endl; + cout << "t4 = " << rad2deg(t4) << " degrees" << endl; + cout << "t5 = " << rad2deg(t5) << " degrees" << endl; +} + +RhinoXR4::RhinoXR4() +{ + angles.t1 = 0; + angles.t2 = 0; + angles.t3 = 0; + angles.t4 = 0; + angles.t5 = 0; +} + +Matrix RhinoXR4::dirkin(JointAngles &angles) +{ + Matrix matrix(4, 4); + + real d1 = 260; + real a2 = 228.6; + real a3 = 228.6; + real a4 = 9.5; + real d5 = 165; + + real s1 = sin(angles.t1); + real c1 = cos(angles.t1); + real s2 = sin(angles.t2); + real c2 = cos(angles.t2); + real s5 = sin(angles.t5); + real c5 = cos(angles.t5); + real s23 = sin(angles.t2 + angles.t3); + real c23 = cos(angles.t2 + angles.t3); + real s234 = sin(angles.t2 + angles.t3 + angles.t4); + real c234 = cos(angles.t2 + angles.t3 + angles.t4); + + matrix.at(1, 1) = nullify(s1*s5 + c5*c1*c234); + matrix.at(1, 2) = nullify(c5*s1 - s5*c1*c234); + matrix.at(1, 3) = nullify(c1*s234); + matrix.at(1, 4) = nullify(c1*(d5*s234 + a2*c2 + a3*c23 + a4*c234)); + + matrix.at(2, 1) = nullify(c5*s1*c234 - c1*s5); + matrix.at(2, 2) = nullify(-c1*c5 - s5*s1*c234); + matrix.at(2, 3) = nullify(s1*s234); + matrix.at(2, 4) = nullify(s1*(d5*s234 + a2*c2 + a3*c23 + a4*c234)); + + matrix.at(3, 1) = nullify(c5*s234); + matrix.at(3, 2) = nullify(-s5*s234); + matrix.at(3, 3) = nullify(-c234); + matrix.at(3, 4) = nullify(d1 - d5*c234 + a2*s2 + a3*s23 + a4*s234); + + matrix.at(4, 1) = 0; + matrix.at(4, 2) = 0; + matrix.at(4, 3) = 0; + matrix.at(4, 4) = 1; + + return matrix; +} + +JointAngles RhinoXR4::invkin(Matrix &matrix) +{ + JointAngles angles; + real A, B, alph, sa, s1, c1, s3, c3; + + real d1 = 260; + real a2 = 228.6; + real a3 = 228.6; + real a4 = 9.5; + real d5 = 165; + + // row 1 + real r11 = matrix.at(1, 1); + real r12 = matrix.at(1, 2); + real r13 = matrix.at(1, 3); + qDebug("r11 = %f\tr12 = %f\tr13 = %f", (double)r11, (double)r12, (double)r13); + // row 2 + real r21 = matrix.at(2, 1); + real r22 = matrix.at(2, 2); + real r23 = matrix.at(2, 3); + qDebug("r21 = %f\tr22 = %f\tr23 = %f", (double)r21, (double)r22, (double)r23); + // row 3 + real r33 = matrix.at(3, 3); + // row 4 + real t1 = matrix.at(1, 4); + real t2 = matrix.at(2, 4); + real t3 = matrix.at(3, 4); + + angles.t1 = atan2(t2, t1); + qDebug("t1 = %f rad (%f deg)", (double)angles.t1, (double)rad2deg(angles.t1)); + qDebug("deg2rad(jointRangeDeg('F').min) = %f", (double)deg2rad(jointRangeDeg('F', false).min)); + qDebug("deg2rad(jointRangeDeg('F').max) = %f", (double)deg2rad(jointRangeDeg('F', false).max)); + if (angles.t1 < deg2rad(jointRangeDeg('F').min) || angles.t1 > deg2rad(jointRangeDeg('F').max)) + angles.t1 += -sign(angles.t1)*PI; // t1 + 180º + qDebug("t1 = %f rad (%f deg)", (double)angles.t1, (double)rad2deg(angles.t1)); + s1 = sin(angles.t1); + qDebug("s1 = %f", (double)s1); + c1 = cos(angles.t1); + qDebug("c1 = %f", (double)c1); + + angles.t5 = atan2(s1*r11 - c1*r21, s1*r12 - c1*r22); + qDebug("s1*r11 = %f", (double)(s1*r11)); + qDebug("c1*r21 = %f", (double)(c1*r21)); + qDebug("s1*r11 - c1*r21 = %f", (double)(s1*r11 - c1*r21)); + qDebug("s1*r12 = %f", (double)(s1*r12)); + qDebug("c1*r22 = %f", (double)(c1*r22)); + qDebug("s1*r12 - c1*r22 = %f", (double)(s1*r12 - c1*r22)); + qDebug("t5 = %f rad (%f deg)", (double)angles.t5, (double)rad2deg(angles.t5)); + + alph = atan2(c1*r13+s1*r23, -r33); + qDebug("alpha = %f (%f deg)", (double)alph, (double)rad2deg(alph)); + sa = sin(alph); + qDebug("sa = %f", (double)sa); + + // calculation of th3 + A = t3 - d1 - d5*r33 - a4*sa; + qDebug("A = %f", (double)A); + if (nullify(s1) == 0.0) + B = t1/c1 - d5*sa + a4*r33; + else + B = t2/s1 - d5*sa + a4*r33; + qDebug("B = %f", (double)B); + qDebug("(A*A + B*B - a2*a2 - a3*a3) = %f", (double)(A*A + B*B - a2*a2 - a3*a3)); + qDebug("(A*A + B*B - a2*a2 - a3*a3) / (2*a2*a3) = %f", (double)((A*A + B*B - a2*a2 - a3*a3) / (2*a2*a3))); + real tmp = (A*A + B*B - a2*a2 - a3*a3) / (2*a2*a3); + tmp = tmp > 1.0 ? 1.0 : tmp; + angles.t3 = -acos(truncate(tmp)); // elbow-up solution + qDebug("t3 = %f (%f deg)", (double)angles.t3, (double)rad2deg(angles.t3)); + s3 = sin(angles.t3); + qDebug("s3 = %f", (double)s3); + c3 = cos(angles.t3); + qDebug("c3 = %f", (double)c3); + + // calculation of th2 + qDebug("A*(a2+a3*c3) = %f", (double)(A*(a2+a3*c3))); + qDebug("B*a3*s3 = %f", (double)(B*a3*s3)); + qDebug("A*(a2+a3*c3)-B*a3*s3 = %f", (double)(A*(a2+a3*c3)-B*a3*s3)); + qDebug("B*(a2+a3*c3) = %f", (double)(B*(a2+a3*c3))); + qDebug("A*a3*s3 = %f", (double)(A*a3*s3)); + qDebug("B*(a2+a3*c3)+A*a3*s3 = %f", (double)(B*(a2+a3*c3)+A*a3*s3)); + qDebug("A*(a2+a3*c3)-B*a3*s3 / B*(a2+a3*c3)+A*a3*s3 = %f", (double)((A*(a2+a3*c3)-B*a3*s3) / (B*(a2+a3*c3)+A*a3*s3))); + angles.t2 = atan2(A*(a2+a3*c3)-B*a3*s3, B*(a2+a3*c3)+A*a3*s3); + qDebug("t2 = %f (%f deg)", (double)angles.t2, (double)rad2deg(angles.t2)); + + // calculation of th4 + angles.t4 = alph - angles.t2 - angles.t3; + + angles.t1 = nullify(angles.t1); + angles.t2 = nullify(angles.t2); + angles.t3 = nullify(angles.t3); + angles.t4 = nullify(angles.t4); + angles.t5 = nullify(angles.t5); + + return angles; +} + +JointAngles RhinoXR4::invkin2(Matrix &matrix) +{ + JointAngles angles; + real t234, s234, c234, A, B, s1, c1, s3, c3; + + real d1 = 260; + real a2 = 228.6; + real a3 = 228.6; + real a4 = 9.5; + real d5 = 165; + + // N + real nx = matrix.at(1, 1); + real nz = matrix.at(3, 1); + // S + real sx = matrix.at(1, 2); + real sz = matrix.at(3, 2); + // A + real r13 = matrix.at(1, 3); + real r23 = matrix.at(2, 3); + real az = matrix.at(3, 3); + real &r33 = az; + // P + real px = matrix.at(1, 4); + real py = matrix.at(2, 4); + real pz = matrix.at(3, 4); + + //qDebug("az = %f", (double)az); + //t234 = acos(-az); + //s234 = sin(t234); + //c234 = cos(t234); + + angles.t1 = atan2(py, px); + if (angles.t1 < deg2rad(jointRangeDeg('F', false).min) || angles.t1 > deg2rad(jointRangeDeg('F', false).max)) + angles.t1 += PI; // t1 + 180º + qDebug("t1 = %f (%f deg)", (double)angles.t1, (double)rad2deg(angles.t1)); + s1 = sin(angles.t1); + c1 = cos(angles.t1); + + t234 = atan2(c1*r13+s1*r23, -r33); + qDebug("t234 = %f (%f deg)", (double)t234, (double)rad2deg(t234)); + s234 = sin(t234); + c234 = cos(t234); + + if (nullify(s234) == 0.0) + { + if (c234 > 0) + angles.t5 = angles.t1 - atan2(sx, nx); + else + angles.t5 = -angles.t1 + atan2(sx, -nx); + } + else + angles.t5 = atan2(-sz, nz); + + A = pz - a4*s234 + d5*c234 - d1; + B = px*c1 + py*s1 - a4*c234 - d5*s234; + + real num = A*A + B*B - a2*a2 - a3*a3; + real den = 2*a2*a3; + qDebug("num / den = %f", (double)(num/den)); + angles.t3 = -acos(truncate(num / den)); + s3 = sin(angles.t3); + c3 = cos(angles.t3); + + num = A*(a2 + a3*c3) - B*a3*s3; + den = A*a3*s3 + B*(a2 + a3*c3); + angles.t2 = atan2(num, den); + + angles.t4 = t234 - angles.t2 - angles.t3; + + angles.t1 = nullify(angles.t1); + angles.t2 = nullify(angles.t2); + angles.t3 = nullify(angles.t3); + angles.t4 = nullify(angles.t4); + angles.t5 = nullify(angles.t5); + + return angles; +} + +real RhinoXR4::deg2steps(real deg, char motor, bool correct) +{ + switch (motor) + { + case 'B': + if (correct) + return (deg - 180)*12.8; + else + return deg*12.8; + case 'C': + return deg*35.2736; + case 'D': + if (correct) + return (deg + 90)*35.2736; + else + return deg*35.2736; + case 'E': + if (correct) + return (deg - 90)*35.2736; // Home de la cinemática: 1196 \simeq 1200 + else + return deg*35.2736; // Home de la cinemática: 1196 \simeq 1200 + case 'F': + if (correct) + return (deg - 90)*17.6368; + else + return deg*17.6368; + default: + throw new InvalidMotor(); + } +} + +real RhinoXR4::steps2deg(real steps, char motor, bool correct) +{ + switch (motor) + { + case 'B': + if (correct) + return steps*0.078125 + 180; + else + return steps*0.078125; + case 'C': + return steps*0.02834981402522; + case 'D': + if (correct) + return steps*0.02834981402522 - 90; + else + return steps*0.02834981402522; + case 'E': + if (correct) + return steps*0.02834981402522 + 90; // Home de la cinemática: 1196 \simeq 1200 + else + return steps*0.02834981402522; // Home de la cinemática: 1196 \simeq 1200 + case 'F': + if (correct) + return steps*0.05669962805044 + 90; + else + return steps*0.05669962805044; + default: + throw new InvalidMotor(); + } +} + +Range RhinoXR4::jointRangeDeg(char motor, bool correct) +{ + switch (motor) + { + case 'B': + return Range(steps2deg(-20000, 'B', true), steps2deg(20000, 'B', true)); + case 'C': + return Range(steps2deg(-2800, 'C', true), steps2deg(8200, 'C', true)); + case 'D': + return Range(steps2deg(-2200, 'D', true), steps2deg(5115, 'D', true)); + case 'E': + return Range(steps2deg(-550, 'E', true), steps2deg(4300, 'E', true)); + case 'F': + return Range(steps2deg(-3056, 'F', true), steps2deg(3056, 'F', correct)); + default: + throw new InvalidMotor(); + } +} + +Range RhinoXR4::jointRangeSteps(char motor) +{ + switch (motor) + { + case 'B': + return Range(-20000, 20000); + case 'C': + return Range(-2800, 8200); + case 'D': + return Range(-2200, 5115); + case 'E': + return Range(-550, 4300); + case 'F': + return Range(-3056, 3056); + default: + throw new InvalidMotor(); + } +} + +InvalidMotor::InvalidMotor() +{ + _description = QObject::tr("Invalid motor letter"); + setMessage(QObject::tr("Invalid mottor letter: motor letter must be between B and F")); +} diff --git a/rhino_xr4.hpp b/rhino_xr4.hpp new file mode 100644 index 0000000..db73606 --- /dev/null +++ b/rhino_xr4.hpp @@ -0,0 +1,67 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RHINO_XR4_H_53DOY91C +#define RHINO_XR4_H_53DOY91C + +#include "matrix.hpp" +#include "exception.hpp" + +#ifndef PI +#define PI 3.14159265 +#endif + +#ifndef TOL +#define TOL 0.0001 // tolerance +#endif + +real deg2rad(real angle); +real rad2deg(real angle); +real nullify(real num); +float truncate(float num); +real sign(real num); + +struct JointAngles { + real t1, t2, t3, t4, t5; + + JointAngles() {}; + JointAngles(real t1, real t2, real t3, real t4, real t5); + void print(); +}; + +struct Range { + real min, max; + Range(real min, real max); +}; + +struct RhinoXR4 { + JointAngles angles; +public: + RhinoXR4(); + Matrix dirkin(JointAngles &angles); + JointAngles invkin(Matrix &matrix); + JointAngles invkin2(Matrix &matrix); + real deg2steps(real deg, char motor, bool correct=true); + real steps2deg(real steps, char motor, bool correct=true); + Range jointRangeDeg(char motor, bool correct=false); + Range jointRangeSteps(char motor); +}; + +class InvalidMotor : Exception +{ +public: + InvalidMotor(); +}; + +#endif /* end of include guard: RHINO_XR4_H_53DOY91C */ diff --git a/rhinolang.cpp b/rhinolang.cpp new file mode 100644 index 0000000..eee9c72 --- /dev/null +++ b/rhinolang.cpp @@ -0,0 +1,60 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rhinolang.hpp" + +#include + +bool mustWaitResponseFromCmd(QString cmd) +{ + QSet matchingCmds; + + matchingCmds.insert("SE"); + matchingCmds.insert("SA"); + matchingCmds.insert("SC"); + matchingCmds.insert("SE"); + matchingCmds.insert("SM"); + matchingCmds.insert("SP"); + matchingCmds.insert("SS"); + matchingCmds.insert("SU"); + matchingCmds.insert("SV"); + matchingCmds.insert("SZ"); + matchingCmds.insert("AR"); + matchingCmds.insert("DR"); + matchingCmds.insert("GS"); + matchingCmds.insert("HR"); + matchingCmds.insert("PA"); + matchingCmds.insert("PW"); + matchingCmds.insert("PZ"); + matchingCmds.insert("RL"); + matchingCmds.insert("UA"); + matchingCmds.insert("UH"); + matchingCmds.insert("UO"); + matchingCmds.insert("UT"); + matchingCmds.insert("UY"); + matchingCmds.insert("VA"); + matchingCmds.insert("VR"); + matchingCmds.insert("VX"); + matchingCmds.insert("XR"); + matchingCmds.insert("FT"); + matchingCmds.insert("RA"); + matchingCmds.insert("RB"); + matchingCmds.insert("RC"); + matchingCmds.insert("IB"); + matchingCmds.insert("IP"); + matchingCmds.insert("IX"); + matchingCmds.insert("OR"); + + return matchingCmds.contains(cmd.toLower()) || matchingCmds.contains(cmd.toUpper()); +} diff --git a/rhinolang.hpp b/rhinolang.hpp new file mode 100644 index 0000000..6e3d1ab --- /dev/null +++ b/rhinolang.hpp @@ -0,0 +1,43 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RHINOLANG_H +#define RHINOLANG_H + +#include + +/******************************************************************************************************** + * SYNTAX FOR COMMANDS + *******************************************************************************************************/ + +#define ARGSEP "," // character that separates the command name from its arguments + +/******************************************************************************************************** + * SYNTAX FOR PROGRAM FILES + *******************************************************************************************************/ + +#define FILESTART "\x30\x30\x31\x31\x31\x31\x31\x31\x31\x31\x30" // start of file +//#define FILEEND "\x25\x1a\x1a" // end of file +#define FILEEND "\x25\x1a" // end of file +#define CMDSEP "\n" // command separator + +/******************************************************************************************************** + * SYNTAX FOR TERMINAL + *******************************************************************************************************/ + +#define CMDEND "\r" // command separator (end of command) + +bool mustWaitResponseFromCmd(QString cmd); + +#endif // RHINOLANG_H diff --git a/rhinoprog.cpp b/rhinoprog.cpp new file mode 100644 index 0000000..bb6fd1a --- /dev/null +++ b/rhinoprog.cpp @@ -0,0 +1,47 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rhinoprog.hpp" + +#include + +RhinoProg::RhinoProg(QByteArray newCode) +{ + if (!newCode.isEmpty()) + setCode(newCode); +} + +void RhinoProg::saveToPath(QString path) +{ + QFile outf(path); + outf.open(QFile::WriteOnly | QFile::Text); + outf.write(getCode()); + outf.close(); +} + +void RhinoProg::setCode(QByteArray newCode) +{ + code = newCode.trimmed(); + appendCode("\n"); +} + +void RhinoProg::appendCode(QByteArray newCode) +{ + code.append(newCode); +} + +QByteArray RhinoProg::getCode() +{ + return code; +} diff --git a/rhinoprog.hpp b/rhinoprog.hpp new file mode 100644 index 0000000..3b621c2 --- /dev/null +++ b/rhinoprog.hpp @@ -0,0 +1,31 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RHINOPROG_H +#define RHINOPROG_H + +#include "exception.hpp" + +class RhinoProg +{ + QByteArray code; // program code without file start and file end +public: + RhinoProg(QByteArray newCode=QByteArray()); + void saveToPath(QString path); + void setCode(QByteArray newCode); + void appendCode(QByteArray newCode); + QByteArray getCode(); +}; + +#endif // RHINOPROG_H diff --git a/terminal.cpp b/terminal.cpp new file mode 100644 index 0000000..23b1405 --- /dev/null +++ b/terminal.cpp @@ -0,0 +1,294 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "terminal.hpp" +#include "rhinolang.hpp" + +#include + +Terminal::Terminal() +{ + _serialPort = NULL; + + _waitTimer = new QTimer(this); + QObject::connect(_waitTimer, SIGNAL(timeout()), this, SLOT(abortWaitResponse())); + _pollTimer = new QTimer(this); + QObject::connect(_pollTimer, SIGNAL(timeout()), this, SLOT(pollController())); + + setPromptTxt(">> "); + + setInputTxtColor("rgb(186, 186, 186);"); // gray + setOutputTxtColor(""); + setBgColor("rgb(0, 0, 0);"); // black + setTxtFontFamily("Courier New"); +} + +Terminal::~Terminal() +{ + if (isConnected()) + disconnect(); + delete _pollTimer; + delete _waitTimer; +} + +void Terminal::setPort(QString comPort) +{ + if (comPort.isEmpty()) + throw new InvalidComPortError(); + if (isConnected()) + throw new PortChangeWhileConnectedError(); + _portId = comPort; +} + +void Terminal::connect() +{ + if (port().isEmpty()) + throw new InvalidComPortError(); + else + { + if (_serialPort == NULL) + { + _serialPort = new QextSerialPort(port()); + _serialPort->setBaudRate(BAUD9600); + _serialPort->setDataBits(DATA_7); + _serialPort->setParity(PAR_EVEN); // RoboTalk manual: even / Mark IV manual: odd + _serialPort->setStopBits(STOP_2); + _serialPort->setFlowControl(FLOW_HARDWARE); + } + if (!_serialPort->open(QIODevice::ReadWrite)) // has no effect if port is already open + throw new ErrorOpeningComPort(); + } +} + +void Terminal::disconnect() +{ + _serialPort->close(); // has no effect if port is already closed + delete _serialPort; + _serialPort = NULL; + _waitTimer->stop(); +} + +bool Terminal::isConnected() +{ + return _serialPort != NULL && _serialPort->isOpen(); +} + +QString Terminal::port() +{ + return _portId; +} + +QString Terminal::promptTxt() +{ + return _promptTxt; +} + +void Terminal::setPromptTxt(QString newPrompt) +{ + _promptTxt = newPrompt; +} + +bool Terminal::sendCmdAndTellMustWait(QString cmd) +{ + // send command to controller + QByteArray cmdBytes = cmd.toAscii(); + _serialPort->write(cmdBytes); + _serialPort->write(CMDEND); + + // get output from controller without blocking the GUI (using a QTimer) + // (only if controller shall produce a response for the sent command) + if (mustWaitResponseFromCmd(cmd.left(2))) + { + _pollTimer->start(POLL_INTERVAL); + _waitTimer->start(CMD_TIMEOUT); + } + else + return false; // tell must not wait + + return true; // tell must wait +} + +QString Terminal::sendCmdSynchronous(QString cmd) +{ + QByteArray cmdBytes = cmd.toAscii(); + _serialPort->write(cmdBytes); + _serialPort->write(CMDEND); + if (mustWaitResponseFromCmd(cmd.left(2))) + { + int indexOfCmdEnd; + time_t startTime = time(NULL); + + while ((_serialPort->bytesAvailable() == 0) && (time(NULL) - startTime < CMD_TIMEOUT/1000)); + + if (_serialPort->bytesAvailable() > 0) + { + _comBuffer.append(_serialPort->readAll()); + indexOfCmdEnd = _comBuffer.indexOf(CMDEND); // cmd separator for command line + if (indexOfCmdEnd != -1) + { + QByteArray responseBytes; + + responseBytes = _comBuffer.left(indexOfCmdEnd); + _comBuffer = _comBuffer.right(_comBuffer.size() - (indexOfCmdEnd + strlen(CMDEND))); + + QString response; + for (int i = 0; i < indexOfCmdEnd; i++) + response += responseBytes.at(i); + return response; + } + } + else + emit timeout(CMD_TIMEOUT); + } + return ""; +} + +QString Terminal::inputTxtColor() +{ + return _inputTxtColor; +} + +QString Terminal::outputTxtColor() +{ + return _outputTxtColor; +} + +QString Terminal::bgColor() +{ + return _bgColor; +} + +QString Terminal::txtFontFamily() +{ + return _txtFontFamily; +} + +QString Terminal::txtFontSize() +{ + return _txtFontSize; +} + +void Terminal::setInputTxtColor(QString color) +{ + _inputTxtColor = color; +} + +void Terminal::setOutputTxtColor(QString color) +{ + _outputTxtColor = color; +} + +void Terminal::setBgColor(QString color) +{ + _bgColor = color; +} + +void Terminal::setTxtFontFamily(QString fontFamily) +{ + _txtFontFamily = fontFamily; +} + +void Terminal::setTxtFontSize(QString fontSize) +{ + _txtFontSize = fontSize; +} + +void Terminal::pollController() +{ + int indexOfCmdEnd, indexOfFileEnd; + + if (_serialPort->bytesAvailable() > 0) + { + _pollTimer->stop(); + _waitTimer->stop(); + _comBuffer.append(_serialPort->readAll()); + indexOfCmdEnd = _comBuffer.indexOf(CMDEND); // cmd separator for command line + if (indexOfCmdEnd != -1) + { + QByteArray responseBytes; + + responseBytes = _comBuffer.left(indexOfCmdEnd); + _comBuffer = _comBuffer.right(_comBuffer.size() - (indexOfCmdEnd + strlen(CMDEND))); + + QString response; + for (int i = 0; i < indexOfCmdEnd; i++) + response += responseBytes.at(i); + emit receivedFullResponse(response); + } + indexOfFileEnd = _comBuffer.lastIndexOf(FILEEND); // cmd separator for program files + if (indexOfFileEnd != -1) + { + QByteArray responseBytes; + + responseBytes = _comBuffer.left(indexOfFileEnd); + _comBuffer = _comBuffer.right(_comBuffer.size() - (indexOfFileEnd + strlen(FILEEND))); + + RhinoProg *prog = new RhinoProg(responseBytes); + emit receivedProgram(prog); + } + if (indexOfCmdEnd == -1 && indexOfFileEnd == -1) + { + _pollTimer->start(POLL_INTERVAL); + _waitTimer->start(FILE_TIMEOUT); + } + } +} + +void Terminal::abortWaitResponse() +{ + _pollTimer->stop(); + _waitTimer->stop(); + emit timeout(_waitTimer->interval()); +} + +void Terminal::sendProgram(QByteArray code) +{ + _serialPort->write("FR"); + _serialPort->write(CMDEND); + // send program + _serialPort->write(code); + _serialPort->write(FILEEND); +} + +void Terminal::getProgram() +{ + _serialPort->write("FT"); + _serialPort->write(CMDEND); + + _pollTimer->start(POLL_INTERVAL); + _waitTimer->start(FILE_TIMEOUT); +} + +/************************************************************************************************************* + * EXCEPTIONS + ************************************************************************************************************/ + +InvalidComPortError::InvalidComPortError() +{ + _description = QObject::tr("Invalid port number"); + setMessage(QObject::tr("Invalid port number: port number must be non-negative")); +} + +ErrorOpeningComPort::ErrorOpeningComPort() +{ + _description = QObject::tr("Error opening serial port"); + setMessage(QObject::tr("Error opening serial port")); +} + +PortChangeWhileConnectedError::PortChangeWhileConnectedError() +{ + _description = QObject::tr("Port change while connection is open"); + setMessage(QObject::tr("Cannot change port number: connection is already " + "open, you should close it first")); +} diff --git a/terminal.hpp b/terminal.hpp new file mode 100644 index 0000000..460ffb5 --- /dev/null +++ b/terminal.hpp @@ -0,0 +1,105 @@ +// Copyright 2011 Jonán C. Martín +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TERMINAL_H +#define TERMINAL_H + +#include +#include +#include + +#include "exception.hpp" +#include "rhinoprog.hpp" + +#include + +#define POLL_INTERVAL 100 // poll serial port every 0.1 seconds +#define CMD_TIMEOUT 10000 // wait response from Mark IV for 10 seconds +#define FILE_TIMEOUT 20000 // wait response from Mark IV for 10 seconds + +class Terminal : public QObject +{ + Q_OBJECT + +private: + QString _portId; + QextSerialPort * _serialPort; + QTimer * _pollTimer; + QTimer * _waitTimer; + QByteArray _comBuffer; // communication buffer + QString _inputTxtColor; + QString _outputTxtColor; + QString _bgColor; + QString _txtFontFamily; + QString _txtFontSize; + QString _promptTxt; // text to use as prompt + +public: + Terminal(); + ~Terminal(); + void setPort(QString comPort); + void connect(); + void disconnect(); + bool isConnected(); + QString port(); + QString promptTxt(); + void setPromptTxt(QString newPrompt); + bool sendCmdAndTellMustWait(QString cmd); + QString sendCmdSynchronous(QString cmd); + void getProgram(); + void sendProgram(QByteArray execCode); + QString inputTxtColor(); + QString outputTxtColor(); + QString bgColor(); + QString txtFontFamily(); + QString txtFontSize(); + void setInputTxtColor(QString color); + void setOutputTxtColor(QString color); + void setBgColor(QString color); + void setTxtFontFamily(QString fontFamily); + void setTxtFontSize(QString fontSize); + +signals: + void receivedFullResponse(QString response); + void timeout(int time); + void receivedProgram(RhinoProg *prog); + +private slots: + void pollController(); + void abortWaitResponse(); +}; + +/************************************************************************************************************* + * EXCEPTIONS + ************************************************************************************************************/ + +class InvalidComPortError : Exception +{ +public: + InvalidComPortError(); +}; + +class ErrorOpeningComPort : Exception +{ +public: + ErrorOpeningComPort(); +}; + +class PortChangeWhileConnectedError : Exception +{ +public: + PortChangeWhileConnectedError(); +}; + +#endif // TERMINAL_H