├── CMakeLists.txt ├── README.md ├── package.xml ├── qt_resources ├── arrows.qrc └── images │ ├── down.xpm │ ├── left.xpm │ ├── right.xpm │ └── up.xpm └── src ├── ControlWindow.cpp ├── ControlWindow.h ├── RobotThread.cpp ├── RobotThread.h └── main.cpp /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.9) 2 | project(ros_qt_controller) 3 | find_package(catkin REQUIRED COMPONENTS roscpp) 4 | find_package(Qt5Widgets REQUIRED) 5 | find_package(Qt5Core REQUIRED) 6 | 7 | catkin_package( 8 | CATKIN_DEPENDS roscpp geometry_msgs 9 | DEPENDS system-lib 10 | ) 11 | 12 | qt5_add_resources(QT_RESOURCES_CPP qt_resources/arrows.qrc) 13 | qt5_wrap_cpp(QT_MOC_HPP src/ControlWindow.h 14 | src/RobotThread.h) 15 | 16 | include_directories(src ${catkin_INCLUDE_DIRS}) 17 | include_directories(${Qt5Widgets_INCLUDE_DIRS}) 18 | 19 | add_executable(qt_ros_ctrl src/ControlWindow.cpp 20 | src/RobotThread.cpp 21 | src/main.cpp 22 | ${QT_RESOURCES_CPP} 23 | ${QT_MOC_HPP}) 24 | 25 | target_link_libraries(qt_ros_ctrl ${QT_LIBRARIES} 26 | ${catkin_LIBRARIES} Qt5::Widgets) 27 | 28 | install(TARGETS qt_ros_ctrl 29 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 30 | ) -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Description 2 | =========== 3 | This is a simple controller built with ROS and Qt5 libraries. This is implemented here as a part of the ROS Complete Handbook. -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ros_qt_controller 4 | 0.0.1 5 | Simple Robot Controller. 6 | BSD 7 | Hunter Allen 8 | Hunter Allen 9 | 10 | catkin 11 | 12 | geometry_msgs 13 | roscpp 14 | 15 | geometry_msgs 16 | roscpp 17 | -------------------------------------------------------------------------------- /qt_resources/arrows.qrc: -------------------------------------------------------------------------------- 1 | 2 | 3 | images/down.xpm 4 | images/left.xpm 5 | images/right.xpm 6 | images/up.xpm 7 | 8 | -------------------------------------------------------------------------------- /qt_resources/images/down.xpm: -------------------------------------------------------------------------------- 1 | /* XPM */ 2 | static char * down_xpm[] = { 3 | "50 50 42 1", 4 | " c #CDCDCD", 5 | ". c #FFFFFF", 6 | "+ c #C7C7C7", 7 | "@ c #AAAAAA", 8 | "# c #959595", 9 | "$ c #8F8F8F", 10 | "% c #C1C1C1", 11 | "& c #FDFDFD", 12 | "* c #353535", 13 | "= c #949494", 14 | "- c #393939", 15 | "; c #BBBBBB", 16 | "> c #010101", 17 | ", c #929292", 18 | "' c #B2B2B2", 19 | ") c #989898", 20 | "! c #383838", 21 | "~ c #000000", 22 | "{ c #AFAFAF", 23 | "] c #ACACAC", 24 | "^ c #181818", 25 | "/ c #ECECEC", 26 | "( c #F0F0F0", 27 | "_ c #161616", 28 | ": c #555555", 29 | "< c #666666", 30 | "[ c #2C2C2C", 31 | "} c #B7B7B7", 32 | "| c #1D1D1D", 33 | "1 c #363636", 34 | "2 c #424242", 35 | "3 c #C2C2C2", 36 | "4 c #373737", 37 | "5 c #3F3F3F", 38 | "6 c #3A3A3A", 39 | "7 c #C3C3C3", 40 | "8 c #404040", 41 | "9 c #414141", 42 | "0 c #F2F2F2", 43 | "a c #686868", 44 | "b c #3B3B3B", 45 | "c c #434343", 46 | " ................................................+", 47 | "@#..............................................$%", 48 | "&*=............................................$-.", 49 | ".;>,..........................................$>'.", 50 | "..*>)........................................$>!..", 51 | "..;~>{......................................]>~'..", 52 | "...*~^/....................................(_~!...", 53 | "...;~~:....................................<~~'...", 54 | "....[~~{..................................}>~!....", 55 | "....@~~^/................................(|~~'....", 56 | "....&1~~:................................<~~2.....", 57 | ".....;~~~{..............................}>~~3.....", 58 | "......1~~^/............................(|~~-......", 59 | "......;~~~:............................<~~~'......", 60 | ".......1~~~{..........................}>~~-.......", 61 | ".......;~~~^/........................(|~~~'.......", 62 | "........4~~~:........................<~~~-........", 63 | "........;~~~~{......................}>~~~'........", 64 | ".........4~~~^/....................(|~~~-.........", 65 | ".........;~~~~:....................<~~~~'.........", 66 | "..........4~~~~{..................}>~~~-..........", 67 | "..........;~~~~^/................(|~~~~'..........", 68 | "...........5~~~~:................<~~~~6...........", 69 | "...........7~~~~~{..............}>~~~~'...........", 70 | "............8~~~~^/............(|~~~~6............", 71 | "............7~~~~~:............<~~~~~'............", 72 | ".............8~~~~~{..........}>~~~~6.............", 73 | ".............7~~~~~^/........(|~~~~~'.............", 74 | "..............8~~~~~:........<~~~~~6..............", 75 | "..............7~~~~~~{......}>~~~~~'..............", 76 | "...............9~~~~~^/....(|~~~~~6...............", 77 | "...............7~~~~~~:....<~~~~~~'...............", 78 | "................9~~~~~~{..}>~~~~~6................", 79 | "................7~~~~~~^0(|~~~~~~'................", 80 | ".................9~~~~~~a<~~~~~~6.................", 81 | ".................7~~~~~~>>~~~~~~'.................", 82 | "..................2~~~~~~~~~~~~b..................", 83 | "..................7~~~~~~~~~~~~'..................", 84 | "...................2~~~~~~~~~~b...................", 85 | "...................7~~~~~~~~~~'...................", 86 | "....................2~~~~~~~~b....................", 87 | "....................7~~~~~~~~'....................", 88 | ".....................c~~~~~~b.....................", 89 | ".....................7~~~~~~'.....................", 90 | "......................c~~~~b......................", 91 | "......................7~~~~'......................", 92 | ".......................c~~b.......................", 93 | ".......................7~~;.......................", 94 | "........................4b........................", 95 | "........................};........................"}; 96 | -------------------------------------------------------------------------------- /qt_resources/images/left.xpm: -------------------------------------------------------------------------------- 1 | /* XPM */ 2 | static char * left_xpm[] = { 3 | "50 50 42 1", 4 | " c #FFFFFF", 5 | ". c #C1C1C1", 6 | "+ c #C7C7C7", 7 | "@ c #B2B2B2", 8 | "# c #393939", 9 | "$ c #8F8F8F", 10 | "% c #383838", 11 | "& c #010101", 12 | "* c #000000", 13 | "= c #C2C2C2", 14 | "- c #424242", 15 | "; c #161616", 16 | "> c #ACACAC", 17 | ", c #666666", 18 | "' c #F0F0F0", 19 | ") c #1D1D1D", 20 | "! c #B7B7B7", 21 | "~ c #3A3A3A", 22 | "{ c #3B3B3B", 23 | "] c #BBBBBB", 24 | "^ c #373737", 25 | "/ c #686868", 26 | "( c #F2F2F2", 27 | "_ c #C3C3C3", 28 | ": c #434343", 29 | "< c #181818", 30 | "[ c #AFAFAF", 31 | "} c #555555", 32 | "| c #ECECEC", 33 | "1 c #414141", 34 | "2 c #404040", 35 | "3 c #3F3F3F", 36 | "4 c #363636", 37 | "5 c #FDFDFD", 38 | "6 c #AAAAAA", 39 | "7 c #2C2C2C", 40 | "8 c #989898", 41 | "9 c #353535", 42 | "0 c #929292", 43 | "a c #949494", 44 | "b c #959595", 45 | "c c #CDCDCD", 46 | " .+", 47 | " @#$ ", 48 | " @%&$ ", 49 | " @%*&$ ", 50 | " @%**&$ ", 51 | " =-***;> ", 52 | " @#***&,' ", 53 | " @#****)! ", 54 | " @#****&,' ", 55 | " @#*****)! ", 56 | " @#*****&,' ", 57 | " @~******)! ", 58 | " @~******&,' ", 59 | " @~*******)! ", 60 | " @~*******&,' ", 61 | " @~********)! ", 62 | " @~********&,' ", 63 | " @~*********)! ", 64 | " @{*********&,' ", 65 | " @{**********)! ", 66 | " @{**********&,' ", 67 | " @{***********)! ", 68 | " @{***********&,' ", 69 | " ]{************)! ", 70 | "]{************&,' ", 71 | "!^************&/( ", 72 | " _:************<[ ", 73 | " _:************}| ", 74 | " _:***********<[ ", 75 | " _-***********}| ", 76 | " _-**********<[ ", 77 | " _-**********}| ", 78 | " _1*********<[ ", 79 | " _1*********}| ", 80 | " _1********<[ ", 81 | " _2********}| ", 82 | " _2*******<[ ", 83 | " _2*******}| ", 84 | " _3******<[ ", 85 | " ]^******}| ", 86 | " ]^*****<[ ", 87 | " ]^*****}| ", 88 | " ]4****<[ ", 89 | " ]4****}| ", 90 | " ]4***<[ ", 91 | " 567**&8 ", 92 | " ]9*&0 ", 93 | " ]9&a ", 94 | " ]9b ", 95 | " 56c"}; 96 | -------------------------------------------------------------------------------- /qt_resources/images/right.xpm: -------------------------------------------------------------------------------- 1 | /* XPM */ 2 | static char * right_xpm[] = { 3 | "50 50 42 1", 4 | " c #C7C7C7", 5 | ". c #C1C1C1", 6 | "+ c #FFFFFF", 7 | "@ c #8F8F8F", 8 | "# c #393939", 9 | "$ c #B2B2B2", 10 | "% c #010101", 11 | "& c #383838", 12 | "* c #000000", 13 | "= c #ACACAC", 14 | "- c #161616", 15 | "; c #424242", 16 | "> c #C2C2C2", 17 | ", c #F0F0F0", 18 | "' c #666666", 19 | ") c #B7B7B7", 20 | "! c #1D1D1D", 21 | "~ c #3A3A3A", 22 | "{ c #3B3B3B", 23 | "] c #BBBBBB", 24 | "^ c #F2F2F2", 25 | "/ c #686868", 26 | "( c #373737", 27 | "_ c #AFAFAF", 28 | ": c #181818", 29 | "< c #434343", 30 | "[ c #C3C3C3", 31 | "} c #ECECEC", 32 | "| c #555555", 33 | "1 c #414141", 34 | "2 c #404040", 35 | "3 c #3F3F3F", 36 | "4 c #363636", 37 | "5 c #989898", 38 | "6 c #2C2C2C", 39 | "7 c #AAAAAA", 40 | "8 c #FDFDFD", 41 | "9 c #929292", 42 | "0 c #353535", 43 | "a c #949494", 44 | "b c #959595", 45 | "c c #CDCDCD", 46 | " .++++++++++++++++++++++++++++++++++++++++++++++++", 47 | "+@#$++++++++++++++++++++++++++++++++++++++++++++++", 48 | "++@%&$++++++++++++++++++++++++++++++++++++++++++++", 49 | "+++@%*&$++++++++++++++++++++++++++++++++++++++++++", 50 | "++++@%**&$++++++++++++++++++++++++++++++++++++++++", 51 | "+++++=-***;>++++++++++++++++++++++++++++++++++++++", 52 | "++++++,'%***#$++++++++++++++++++++++++++++++++++++", 53 | "++++++++)!****#$++++++++++++++++++++++++++++++++++", 54 | "+++++++++,'%****#$++++++++++++++++++++++++++++++++", 55 | "+++++++++++)!*****#$++++++++++++++++++++++++++++++", 56 | "++++++++++++,'%*****#$++++++++++++++++++++++++++++", 57 | "++++++++++++++)!******~$++++++++++++++++++++++++++", 58 | "+++++++++++++++,'%******~$++++++++++++++++++++++++", 59 | "+++++++++++++++++)!*******~$++++++++++++++++++++++", 60 | "++++++++++++++++++,'%*******~$++++++++++++++++++++", 61 | "++++++++++++++++++++)!********~$++++++++++++++++++", 62 | "+++++++++++++++++++++,'%********~$++++++++++++++++", 63 | "+++++++++++++++++++++++)!*********~$++++++++++++++", 64 | "++++++++++++++++++++++++,'%*********{$++++++++++++", 65 | "++++++++++++++++++++++++++)!**********{$++++++++++", 66 | "+++++++++++++++++++++++++++,'%**********{$++++++++", 67 | "+++++++++++++++++++++++++++++)!***********{$++++++", 68 | "++++++++++++++++++++++++++++++,'%***********{$++++", 69 | "++++++++++++++++++++++++++++++++)!************{]++", 70 | "+++++++++++++++++++++++++++++++++,'%************{]", 71 | "+++++++++++++++++++++++++++++++++^/%************()", 72 | "++++++++++++++++++++++++++++++++_:************<[++", 73 | "++++++++++++++++++++++++++++++}|************<[++++", 74 | "+++++++++++++++++++++++++++++_:***********<[++++++", 75 | "+++++++++++++++++++++++++++}|***********;[++++++++", 76 | "++++++++++++++++++++++++++_:**********;[++++++++++", 77 | "++++++++++++++++++++++++}|**********;[++++++++++++", 78 | "+++++++++++++++++++++++_:*********1[++++++++++++++", 79 | "+++++++++++++++++++++}|*********1[++++++++++++++++", 80 | "++++++++++++++++++++_:********1[++++++++++++++++++", 81 | "++++++++++++++++++}|********2[++++++++++++++++++++", 82 | "+++++++++++++++++_:*******2[++++++++++++++++++++++", 83 | "+++++++++++++++}|*******2[++++++++++++++++++++++++", 84 | "++++++++++++++_:******3[++++++++++++++++++++++++++", 85 | "++++++++++++}|******(]++++++++++++++++++++++++++++", 86 | "+++++++++++_:*****(]++++++++++++++++++++++++++++++", 87 | "+++++++++}|*****(]++++++++++++++++++++++++++++++++", 88 | "++++++++_:****4]++++++++++++++++++++++++++++++++++", 89 | "++++++}|****4]++++++++++++++++++++++++++++++++++++", 90 | "+++++_:***4]++++++++++++++++++++++++++++++++++++++", 91 | "++++5%**678+++++++++++++++++++++++++++++++++++++++", 92 | "+++9%*0]++++++++++++++++++++++++++++++++++++++++++", 93 | "++a%0]++++++++++++++++++++++++++++++++++++++++++++", 94 | "+b0]++++++++++++++++++++++++++++++++++++++++++++++", 95 | "c78+++++++++++++++++++++++++++++++++++++++++++++++"}; 96 | -------------------------------------------------------------------------------- /qt_resources/images/up.xpm: -------------------------------------------------------------------------------- 1 | /* XPM */ 2 | static char * up_xpm[] = { 3 | "50 50 42 1", 4 | " c #FFFFFF", 5 | ". c #B7B7B7", 6 | "+ c #BBBBBB", 7 | "@ c #373737", 8 | "# c #3B3B3B", 9 | "$ c #C3C3C3", 10 | "% c #000000", 11 | "& c #434343", 12 | "* c #B2B2B2", 13 | "= c #424242", 14 | "- c #010101", 15 | "; c #414141", 16 | "> c #686868", 17 | ", c #666666", 18 | "' c #3A3A3A", 19 | ") c #181818", 20 | "! c #F2F2F2", 21 | "~ c #F0F0F0", 22 | "{ c #1D1D1D", 23 | "] c #AFAFAF", 24 | "^ c #555555", 25 | "/ c #ECECEC", 26 | "( c #404040", 27 | "_ c #3F3F3F", 28 | ": c #393939", 29 | "< c #363636", 30 | "[ c #C2C2C2", 31 | "} c #FDFDFD", 32 | "| c #AAAAAA", 33 | "1 c #2C2C2C", 34 | "2 c #383838", 35 | "3 c #353535", 36 | "4 c #161616", 37 | "5 c #ACACAC", 38 | "6 c #989898", 39 | "7 c #8F8F8F", 40 | "8 c #929292", 41 | "9 c #949494", 42 | "0 c #959595", 43 | "a c #C1C1C1", 44 | "b c #CDCDCD", 45 | "c c #C7C7C7", 46 | " .+ ", 47 | " @# ", 48 | " $%%+ ", 49 | " &%%# ", 50 | " $%%%%* ", 51 | " &%%%%# ", 52 | " $%%%%%%* ", 53 | " &%%%%%%# ", 54 | " $%%%%%%%%* ", 55 | " =%%%%%%%%# ", 56 | " $%%%%%%%%%%* ", 57 | " =%%%%%%%%%%# ", 58 | " $%%%%%%%%%%%%* ", 59 | " =%%%%%%%%%%%%# ", 60 | " $%%%%%%--%%%%%%* ", 61 | " ;%%%%%%>,%%%%%%' ", 62 | " $%%%%%%)!~{%%%%%%* ", 63 | " ;%%%%%%] .-%%%%%' ", 64 | " $%%%%%%^ ,%%%%%%* ", 65 | " ;%%%%%)/ ~{%%%%%' ", 66 | " $%%%%%%] .-%%%%%* ", 67 | " (%%%%%^ ,%%%%%' ", 68 | " $%%%%%)/ ~{%%%%%* ", 69 | " (%%%%%] .-%%%%' ", 70 | " $%%%%%^ ,%%%%%* ", 71 | " (%%%%)/ ~{%%%%' ", 72 | " $%%%%%] .-%%%%* ", 73 | " _%%%%^ ,%%%%' ", 74 | " +%%%%)/ ~{%%%%* ", 75 | " @%%%%] .-%%%: ", 76 | " +%%%%^ ,%%%%* ", 77 | " @%%%)/ ~{%%%: ", 78 | " +%%%%] .-%%%* ", 79 | " @%%%^ ,%%%: ", 80 | " +%%%)/ ~{%%%* ", 81 | " <%%%] .-%%: ", 82 | " +%%%^ ,%%%* ", 83 | " <%%)/ ~{%%: ", 84 | " +%%%] .-%%[ ", 85 | " }<%%^ ,%%= ", 86 | " |%%)/ ~{%%* ", 87 | " 1%%] .-%2 ", 88 | " +%%^ ,%%* ", 89 | " 3%)/ ~4%2 ", 90 | " +%-] 5-%* ", 91 | " 3-6 7-2 ", 92 | " +-8 7-* ", 93 | "}39 7: ", 94 | "|0 7a", 95 | "b c"}; 96 | -------------------------------------------------------------------------------- /src/ControlWindow.cpp: -------------------------------------------------------------------------------- 1 | #include "ControlWindow.h" 2 | 3 | namespace server{ 4 | ControlWindow::ControlWindow(int argc, char **argv, QWidget *parent) 5 | : QWidget(parent), 6 | m_RobotThread(argc, argv) 7 | { 8 | /** Set up the Controls **/ 9 | p_upButton = new QPushButton(); 10 | p_downButton = new QPushButton(); 11 | p_leftButton = new QPushButton(); 12 | p_rightButton = new QPushButton(); 13 | p_stopButton = new QPushButton(tr("&Stop")); 14 | p_quitButton = new QPushButton(tr("&Quit")); 15 | 16 | QPalette palette = p_rightButton->palette(); 17 | palette.setColor(QPalette::Button,QColor(255,255,255)); 18 | p_rightButton->setAutoFillBackground(true); 19 | p_rightButton->setFlat(true); 20 | p_rightButton->setPalette(palette); 21 | p_rightButton->setIcon(QIcon(":/images/right.xpm")); 22 | p_rightButton->setIconSize(QSize(50, 50)); 23 | 24 | palette = p_leftButton->palette(); 25 | palette.setColor(QPalette::Button,QColor(255,255,255)); 26 | p_leftButton->setAutoFillBackground(true); 27 | p_leftButton->setFlat(true); 28 | p_leftButton->setPalette(palette); 29 | p_leftButton->setIcon(QIcon(":/images/left.xpm")); 30 | p_leftButton->setIconSize(QSize(50, 50)); 31 | 32 | palette = p_upButton->palette(); 33 | palette.setColor(QPalette::Button,QColor(255,255,255)); 34 | p_upButton->setAutoFillBackground(true); 35 | p_upButton->setFlat(true); 36 | p_upButton->setPalette(palette); 37 | p_upButton->setIcon(QIcon(":/images/up.xpm")); 38 | p_upButton->setIconSize(QSize(50, 50)); 39 | 40 | palette = p_downButton->palette(); 41 | palette.setColor(QPalette::Button,QColor(255,255,255)); 42 | p_downButton->setAutoFillBackground(true); 43 | p_downButton->setFlat(true); 44 | p_downButton->setPalette(palette); 45 | p_downButton->setIcon(QIcon(":/images/down.xpm")); 46 | p_downButton->setIconSize(QSize(50, 50)); 47 | 48 | /** Set up the Position Display **/ 49 | leftLayout = new QVBoxLayout(); 50 | p_xLayout = new QHBoxLayout(); 51 | p_yLayout = new QHBoxLayout(); 52 | p_aLayout = new QHBoxLayout(); 53 | 54 | p_xLabel = new QLabel(); 55 | p_xLabel->setText(tr("X:")); 56 | p_xDisplay = new QLineEdit(); 57 | p_xDisplay->setText(tr("0.0")); 58 | 59 | p_yLabel = new QLabel(); 60 | p_yLabel->setText(tr("Y:")); 61 | p_yDisplay = new QLineEdit(); 62 | p_yDisplay->setText(tr("0.0")); 63 | 64 | p_aLabel = new QLabel(); 65 | p_aLabel->setText(tr("Theta: ")); 66 | p_aDisplay = new QLineEdit(); 67 | p_aDisplay->setText(tr("0.0")); 68 | 69 | p_xLayout->addWidget(p_xLabel); 70 | p_xLayout->addWidget(p_xDisplay); 71 | p_yLayout->addWidget(p_yLabel); 72 | p_yLayout->addWidget(p_yDisplay); 73 | p_aLayout->addWidget(p_aLabel); 74 | p_aLayout->addWidget(p_aDisplay); 75 | 76 | leftLayout->addLayout(p_xLayout); 77 | leftLayout->addLayout(p_yLayout); 78 | leftLayout->addLayout(p_aLayout); 79 | 80 | /** Set up the Layouts **/ 81 | rightLayout = new QVBoxLayout(); 82 | layout = new QHBoxLayout(); 83 | layout2 = new QHBoxLayout(); 84 | layout3 = new QHBoxLayout(); 85 | layout4 = new QHBoxLayout(); 86 | 87 | mainLayout = new QHBoxLayout(); 88 | 89 | layout->addWidget(p_upButton); 90 | layout2->addWidget(p_leftButton); 91 | layout2->addWidget(p_stopButton); 92 | layout2->addWidget(p_rightButton); 93 | layout3->addWidget(p_downButton); 94 | layout4->addWidget(p_quitButton, 6); 95 | 96 | rightLayout->addLayout(layout); 97 | rightLayout->addLayout(layout2); 98 | rightLayout->addLayout(layout3); 99 | rightLayout->addLayout(layout4); 100 | 101 | mainLayout->addLayout(leftLayout); 102 | mainLayout->addLayout(rightLayout); 103 | setLayout(mainLayout); 104 | 105 | show(); 106 | 107 | setWindowTitle(tr("Control Window")); 108 | 109 | connect(p_quitButton, &QPushButton::clicked, this, &ControlWindow::close); 110 | connect(p_upButton, &QPushButton::clicked, this, &ControlWindow::goForward); 111 | connect(p_leftButton, &QPushButton::clicked, this, &ControlWindow::goLeft); 112 | connect(p_rightButton, &QPushButton::clicked, this, &ControlWindow::goRight); 113 | connect(p_downButton, &QPushButton::clicked, this, &ControlWindow::goBackward); 114 | connect(p_stopButton, &QPushButton::clicked, this, &ControlWindow::halt); 115 | 116 | connect(&m_RobotThread, &RobotThread::newPose, this, &ControlWindow::updatePoseDisplay); 117 | m_RobotThread.init(); 118 | }//end constructor 119 | 120 | void ControlWindow::goForward(){m_RobotThread.SetSpeed(0.25, 0);} 121 | void ControlWindow::goBackward(){m_RobotThread.SetSpeed(-0.25, 0);} 122 | void ControlWindow::goRight(){m_RobotThread.SetSpeed(0, -PI / 6.0);} 123 | void ControlWindow::goLeft(){m_RobotThread.SetSpeed(0, PI / 6.0);} 124 | void ControlWindow::halt(){ m_RobotThread.SetSpeed(0, 0); } 125 | 126 | void ControlWindow::updatePoseDisplay(double x, double y, double theta) 127 | { 128 | QString xPose, yPose, aPose; 129 | xPose.setNum(x); 130 | yPose.setNum(y); 131 | aPose.setNum(theta); 132 | 133 | p_xDisplay->setText(xPose); 134 | p_yDisplay->setText(yPose); 135 | p_aDisplay->setText(aPose); 136 | }//update the display. 137 | }//end namespace 138 | 139 | -------------------------------------------------------------------------------- /src/ControlWindow.h: -------------------------------------------------------------------------------- 1 | #ifndef CONTROL_WINDOW_H 2 | #define CONTROL_WINDOW_H 3 | #include 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | #include 12 | #include 13 | #include "RobotThread.h" 14 | 15 | namespace server{ 16 | #define PI 3.14159265359 17 | 18 | class ControlWindow : public QWidget 19 | { 20 | Q_OBJECT 21 | 22 | public: 23 | ControlWindow(int argc, char** argv, QWidget * parent = 0); 24 | 25 | Q_SLOT void updatePoseDisplay(double x, double y, double theta); 26 | private: 27 | Q_SLOT void goForward(); 28 | Q_SLOT void goBackward(); 29 | Q_SLOT void goLeft(); 30 | Q_SLOT void goRight(); 31 | Q_SLOT void halt(); 32 | 33 | QPushButton *p_upButton; 34 | QPushButton *p_downButton; 35 | QPushButton *p_leftButton; 36 | QPushButton *p_rightButton; 37 | QPushButton *p_stopButton; 38 | QPushButton *p_quitButton; 39 | 40 | QVBoxLayout *rightLayout; 41 | QHBoxLayout *layout; 42 | QHBoxLayout *layout2; 43 | QHBoxLayout *layout3; 44 | QHBoxLayout *layout4; 45 | 46 | QVBoxLayout *leftLayout; 47 | QHBoxLayout *p_xLayout; 48 | QHBoxLayout *p_yLayout; 49 | QHBoxLayout *p_aLayout; 50 | 51 | QLabel *p_xLabel; 52 | QLabel *p_yLabel; 53 | QLabel *p_aLabel; 54 | QLabel *p_scanLabel; 55 | 56 | QLineEdit *p_xDisplay; 57 | QLineEdit *p_yDisplay; 58 | QLineEdit *p_aDisplay; 59 | 60 | QHBoxLayout *mainLayout; 61 | QPushButton *closeButton; 62 | 63 | RobotThread m_RobotThread; 64 | };//end class ControlWindow 65 | }//end namespace 66 | #endif 67 | 68 | -------------------------------------------------------------------------------- /src/RobotThread.cpp: -------------------------------------------------------------------------------- 1 | #include "RobotThread.h" 2 | 3 | RobotThread::RobotThread(int argc, char** pArgv, const char * topic) 4 | : m_Init_argc(argc), 5 | m_pInit_argv(pArgv), 6 | m_topic(topic) 7 | {/** Constructor for the robot thread **/} 8 | 9 | RobotThread::~RobotThread() 10 | { 11 | if (ros::isStarted()) 12 | { 13 | ros::shutdown(); 14 | ros::waitForShutdown(); 15 | }//end if 16 | 17 | m_pThread->wait(); 18 | }//end destructor 19 | 20 | bool RobotThread::init() 21 | { 22 | m_pThread = new QThread(); 23 | this->moveToThread(m_pThread); 24 | 25 | connect(m_pThread, &QThread::started, this, &RobotThread::run); 26 | ros::init(m_Init_argc, m_pInit_argv, "gui_command"); 27 | 28 | if (!ros::master::check()) 29 | return false;//do not start without ros. 30 | 31 | ros::start(); 32 | ros::Time::init(); 33 | ros::NodeHandle nh; 34 | sim_velocity = nh.advertise("/cmd_vel", 100); 35 | pose_listener = nh.subscribe(m_topic, 10, &RobotThread::poseCallback, this); 36 | 37 | m_pThread->start(); 38 | return true; 39 | }//set up the thread 40 | 41 | void RobotThread::poseCallback(const nav_msgs::Odometry & msg) 42 | { 43 | QMutex * pMutex = new QMutex(); 44 | 45 | pMutex->lock(); 46 | m_xPos = msg.pose.pose.position.x; 47 | m_yPos = msg.pose.pose.position.y; 48 | m_aPos = msg.pose.pose.orientation.w; 49 | pMutex->unlock(); 50 | 51 | delete pMutex; 52 | Q_EMIT newPose(m_xPos, m_yPos, m_aPos); 53 | }//callback method to update the robot's position. 54 | 55 | void RobotThread::run() 56 | { 57 | ros::Rate loop_rate(100); 58 | QMutex * pMutex; 59 | while (ros::ok()) 60 | { 61 | pMutex = new QMutex(); 62 | 63 | geometry_msgs::Twist cmd_msg; 64 | pMutex->lock(); 65 | cmd_msg.linear.x = m_speed; 66 | cmd_msg.angular.z = m_angle; 67 | pMutex->unlock(); 68 | 69 | sim_velocity.publish(cmd_msg); 70 | ros::spinOnce(); 71 | loop_rate.sleep(); 72 | delete pMutex; 73 | }//do ros things. 74 | } 75 | 76 | void RobotThread::SetSpeed(double speed, double angle) 77 | { 78 | QMutex * pMutex = new QMutex(); 79 | pMutex->lock(); 80 | m_speed = speed; 81 | m_angle = angle; 82 | pMutex->unlock(); 83 | 84 | delete pMutex; 85 | }//set the speed of the robot. 86 | 87 | double RobotThread::getXSpeed(){ return m_speed; } 88 | double RobotThread::getASpeed(){ return m_angle; } 89 | 90 | double RobotThread::getXPos(){ return m_xPos; } 91 | double RobotThread::getYPos(){ return m_yPos; } 92 | double RobotThread::getAPos(){ return m_aPos; } 93 | 94 | -------------------------------------------------------------------------------- /src/RobotThread.h: -------------------------------------------------------------------------------- 1 | #ifndef ___ROBOTTHREAD_H___ 2 | #define ___ROBOTTHREAD_H___ 3 | 4 | #include 5 | #include 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include "assert.h" 11 | 12 | #include 13 | #include 14 | #include 15 | #include 16 | 17 | class RobotThread : public QObject { 18 | Q_OBJECT 19 | public: 20 | RobotThread(int argc, char **pArgv, const char * topic = "/odom"); 21 | virtual ~RobotThread(); 22 | 23 | double getXPos(); 24 | double getXSpeed(); 25 | double getASpeed(); 26 | double getYPos(); 27 | double getAPos(); 28 | 29 | bool init(); 30 | 31 | void poseCallback(const nav_msgs::Odometry & msg); 32 | 33 | void SetSpeed(double speed, double angle); 34 | void setPose(QList to_set); 35 | 36 | Q_SLOT void run(); 37 | 38 | Q_SIGNAL void newPose(double,double,double); 39 | private: 40 | int m_Init_argc; 41 | char** m_pInit_argv; 42 | const char * m_topic; 43 | 44 | double m_speed; 45 | double m_angle; 46 | 47 | double m_xPos; 48 | double m_yPos; 49 | double m_aPos; 50 | 51 | double m_maxRange; 52 | double m_minRange; 53 | 54 | QThread * m_pThread; 55 | 56 | ros::Subscriber pose_listener; 57 | ros::Publisher sim_velocity; 58 | }; 59 | #endif 60 | 61 | -------------------------------------------------------------------------------- /src/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "ControlWindow.h" 3 | 4 | using namespace server; 5 | 6 | int main(int argc, char** argv) { 7 | QApplication app(argc, argv); 8 | 9 | ControlWindow s(argc, argv); 10 | 11 | return app.exec(); 12 | } 13 | 14 | --------------------------------------------------------------------------------