MainWindow.cpp
Go to the documentation of this file.
00001 #include "MainWindow.h"
00002 #include "ui_MainWindow.h"
00003 
00004 #include <QMessageBox>
00005 #include <QFileDialog>
00006 #include <QComboBox>
00007 #include <QtCore>
00008 
00009 #include <opencv2/core/core.hpp>
00010 #include <opencv2/opencv.hpp>
00011 
00012 #include <ros/package.h>
00013 #include "speech_rec_messages/SpeechRecCommandM.h"
00014 //#include "door_detection_messages/DetectDoorControl.h"
00015 //#include "door_detection_messages/DetectHandleControl.h"
00016 
00017 
00018 
00019 #include "rviz/visualization_manager.h"
00020 #include "rviz/render_panel.h"
00021 #include "rviz/display.h"
00022 #include "rviz/yaml_config_reader.h"
00023 #include "rviz/yaml_config_writer.h"
00024 
00025 using namespace std;
00026 
00027 
00028 bool MainWindow::eventFilter(QObject *object, QEvent *event)
00029  {
00030     if (object == this && event->type() == QEvent::KeyPress) {
00031         robot_platform::MoveRobot msgMove;
00032         robot_platform::TurnRobot msgTurn;
00033         QKeyEvent *keyEvent = static_cast<QKeyEvent *>(event);
00034         switch (keyEvent->key()) {
00035         case Qt::Key_W:
00036             msgMove.m_Distance = 0.1;
00037             msgMove.m_Speed = 0.05;
00038             msgMove.m_Permanent = false;
00039             move_robot_pub_.publish(msgMove);
00040             ROS_INFO_STREAM("MOVE FORWARD");
00041             //cout<<"Move Forward"<<endl;
00042             break;
00043         case Qt::Key_S:
00044             msgMove.m_Distance = -0.1;
00045             msgMove.m_Speed = 0.05;
00046             msgMove.m_Permanent = false;
00047             move_robot_pub_.publish(msgMove);
00048             ROS_INFO("Move Back");
00049             break;
00050         case Qt::Key_A:
00051             msgTurn.m_Theta = 15;
00052             msgTurn.m_Speed = 0.1;
00053             msgTurn.m_Permanent = false;
00054             turn_robot_pub_.publish(msgTurn);
00055             ROS_INFO("Turn Left");
00056             break;
00057 
00058         case Qt::Key_D:
00059             msgTurn.m_Theta = -15;
00060             msgTurn.m_Speed = 0.1;
00061             msgTurn.m_Permanent = false;
00062             turn_robot_pub_.publish(msgTurn);
00063             ROS_INFO("Turn Right");
00064             break;
00065         default:
00066             break;
00067         }
00068 //        if (keyEvent->            cout<<"Turn Left"<<endl;
00069 //key() == Qt::Key_Tab) {
00070 //            // Special tab handling
00071 //            std::cout<<"Hello Keys"<<std::endl;
00072 //            return true;
00073 //        } else
00074 //            return false;
00075     }
00076     return false;
00077  }
00078 
00079 
00080 MainWindow::MainWindow(QWidget *parent) :
00081     QMainWindow(parent),
00082     ui(new Ui::MainWindow),
00083     m_Talker(0)
00084 {
00085     ui->setupUi(this);
00086 
00087     qApp->installEventFilter(this);
00088 
00089 
00090 
00091 //      qtRosNode.getNodeHandle()
00092 
00093 
00094 
00095 }
00096 
00097 MainWindow::~MainWindow()
00098 {
00099     delete ui;
00100 }
00101 
00102 
00103 void MainWindow::setQtRosNode(QtRosNode& qtRosNode)
00104 {
00105     m_Talker = new Talker(*qtRosNode.getNodeHandle(),"chatter");
00106 
00107     m_ObjectRecognitionTab = new ObjectRecognitionTab ( qtRosNode.getNodeHandle(), ui->centralWidget);
00108     ui->mainTabs->addTab ( m_ObjectRecognitionTab, tr ( "&Object Recognition" ) );
00109 
00110     m_ObjectLearningTab = new ObjectLearningTab ( qtRosNode.getNodeHandle(), ui->centralWidget);
00111     ui->mainTabs->addTab ( m_ObjectLearningTab, tr ( "&Object Learning" ) );
00112 
00113 
00114     qRegisterMetaType<std::vector<map_messages::PointOfInterest> >("std::vector<map_messages::PointOfInterest>");
00115     qRegisterMetaType<std::vector<geometry_msgs::PoseStamped> >("std::vector<geometry_msgs::PoseStamped>");
00116     qRegisterMetaType<geometry_msgs::Pose>("geometry_msgs::Pose");
00117 
00118     connect(&qtRosNode, SIGNAL(learningStatus(std::vector<std::string>,std::string)), m_ObjectLearningTab, SLOT(processLearningStatus(std::vector<std::string>,std::string)));
00119     connect(&qtRosNode, SIGNAL(objectNames(std::vector<std::string>,std::vector<std::string>)), m_ObjectRecognitionTab, SLOT(processObjectNames(std::vector<std::string>,std::vector<std::string>)));
00120 
00121 
00122 
00123     connect(&qtRosNode, SIGNAL(rosShutdown()), this, SLOT(close()));
00124 
00125 
00126     move_robot_pub_ = qtRosNode.getNodeHandle()->advertise<robot_platform::MoveRobot>("/robot_platform/MoveRobot", 1);
00127     turn_robot_pub_ = qtRosNode.getNodeHandle()->advertise<robot_platform::TurnRobot>("/robot_platform/TurnRobot", 1);
00128     stop_robot_pub_ = qtRosNode.getNodeHandle()->advertise<robot_platform::StopRobot>("/robot_platform/StopRobot", 1);    stop_robot_pub_ = qtRosNode.getNodeHandle()->advertise<robot_platform::StopRobot>("/robot_platform/StopRobot", 1);
00129 
00130 
00131     start_game_pub_ = qtRosNode.getNodeHandle()->advertise<std_msgs::Empty>("/start_game", 1);
00132     speech_out_pub_ = qtRosNode.getNodeHandle()->advertise<std_msgs::String>("/robot_face/text_out", 1);
00133     fake_user_input_pub_ = qtRosNode.getNodeHandle()->advertise<std_msgs::String>("/robot_face/user_input", 1);
00134 
00135     set_pan_tilt_pub_ = qtRosNode.getNodeHandle()->advertise<ptu::SetPanTilt>("/ptu/set_pan_tilt", 1);
00136 
00137     //m_HandleDetectionPub = m_NodeHandle->advertise<door_detection_messages::DetectHandleControl>("/handle_detection/detect_handle_control", 10);
00138 
00139     //m_DoorDetectionPub = m_NodeHandle->advertise<door_detection_messages::DetectDoorControl>("/door_detection/detect_door_control", 10);
00140 
00141 
00142 
00143 
00144     render_panel_ = new rviz::RenderPanel();
00145 
00146     ui->frame->layout()->addWidget(render_panel_);
00147 
00148     // Next we initialize the main RViz classes.
00149     //
00150     // The VisualizationManager is the container for Display objects,
00151     // holds the main Ogre scene, holds the ViewController, etc. It is
00152     // very central and we will probably need one in every usage of
00153     // librviz.
00154     manager_ = new rviz::VisualizationManager( render_panel_ );
00155     //manager_->setFixedFrame("/map");
00156 
00157     rviz::YamlConfigReader reader;
00158     rviz::Config config;
00159     std::string filename = ros::package::getPath("homer_bringup")+"/homer_display_or_final.rviz" ;
00160     reader.readFile( config, QString::fromStdString( filename ));
00161     if( !reader.error() )
00162     {
00163         manager_->load( config.mapGetChild( "Visualization Manager" ));
00164     }
00165 
00166 
00167     render_panel_->initialize( manager_->getSceneManager(), manager_ );
00168     manager_->initialize();
00169     manager_->startUpdate();
00170 
00171     // Create a Grid display.
00172     //grid_ = manager_->createDisplay( "rviz/Grid", "adjustable grid", true );
00173     //laser_ = manager_->createDisplay( "rviz/Map", "sick laser data", true );
00174     //ROS_ASSERT( grid_ != NULL );
00175    // ROS_ASSERT( laser_ != NULL );
00176 
00177     // Configure the GridDisplay the way we like it.
00178     //grid_->subProp( "Line Style" )->setValue( "Billboards" );
00179     //grid_->subProp( "Color" )->setValue( Qt::yellow );
00180 
00181 
00182     //laser_->subProp( "Topic" )->setValue( "/map");
00183 }
00184 
00185 void MainWindow::on_butStartGame_clicked()
00186 {
00187     std_msgs::Empty msg;
00188     start_game_pub_.publish(msg);
00189 }
00190 
00191 void MainWindow::on_butFakeUserInput_clicked()
00192 {
00193 
00194 }
00195 
00196 void MainWindow::on_butSpeak_clicked()
00197 {
00198 
00199 }
00200 
00201 
00202 void MainWindow::on_pushButtonPanTiltAngle_clicked()
00203 {
00204 
00205 }


obj_rec_gui
Author(s): AGAS/agas@uni-koblenz.de
autogenerated on Mon Oct 6 2014 02:53:43