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