00001 #ifndef ROBOT_COMMAND_INTERFACE_H 00002 #define ROBOT_COMMAND_INTERFACE_H 00003 00004 #ifndef Q_MOC_RUN 00005 #include <ros/ros.h> 00006 #include <rviz/panel.h> 00007 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) 00008 # include <QtWidgets> 00009 #else 00010 # include <QtGui> 00011 #endif 00012 #include <jsk_rviz_plugins/EusCommand.h> 00013 #include <resource_retriever/retriever.h> 00014 #endif 00015 00016 namespace jsk_rviz_plugins 00017 { 00018 class RobotCommandInterfaceAction: public rviz::Panel 00019 { 00020 Q_OBJECT 00021 public: 00022 RobotCommandInterfaceAction( QWidget* parent = 0 ); 00023 00024 protected Q_SLOTS: 00025 bool callRequestEusCommand(const std::string& command); 00026 void buttonCallback(int i); 00027 protected: 00028 void popupDialog(const std::string& text); 00029 // The ROS node handle. 00030 ros::NodeHandle nh_; 00031 QSignalMapper* signal_mapper_; 00032 std::map<int, std::string> euscommand_mapping_; 00033 std::map<int, std::string> emptyservice_mapping_; 00034 //std::vector<QToolButton*> buttons_; 00035 }; 00036 00037 } 00038 00039 #endif // TELEOP_PANEL_H