robot_command_interface.h
Go to the documentation of this file.
1 #ifndef ROBOT_COMMAND_INTERFACE_H
2 #define ROBOT_COMMAND_INTERFACE_H
3 
4 #ifndef Q_MOC_RUN
5 #include <ros/ros.h>
6 #include <rviz/panel.h>
7 #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
8 # include <QtWidgets>
9 #else
10 # include <QtGui>
11 #endif
12 #include <jsk_rviz_plugins/EusCommand.h>
14 #endif
15 
16 namespace jsk_rviz_plugins
17 {
19  {
20  Q_OBJECT
21  public:
22  RobotCommandInterfaceAction( QWidget* parent = 0 );
23 
24  protected Q_SLOTS:
25  bool callRequestEusCommand(const std::string& command);
26  void buttonCallback(int i);
27  protected:
28  void popupDialog(const std::string& text);
29  // The ROS node handle.
31  QSignalMapper* signal_mapper_;
32  std::map<int, std::string> euscommand_mapping_;
33  std::map<int, std::string> emptyservice_mapping_;
34  //std::vector<QToolButton*> buttons_;
35  };
36 
37 }
38 
39 #endif // TELEOP_PANEL_H
jsk_rviz_plugins::RobotCommandInterfaceAction
Definition: robot_command_interface.h:18
panel.h
rviz::Panel
ros.h
command
ROSLIB_DECL std::string command(const std::string &cmd)
jsk_rviz_plugins::RobotCommandInterfaceAction::emptyservice_mapping_
std::map< int, std::string > emptyservice_mapping_
Definition: robot_command_interface.h:33
jsk_rviz_plugins::RobotCommandInterfaceAction::nh_
ros::NodeHandle nh_
Definition: robot_command_interface.h:30
overlay_sample.text
text
Definition: overlay_sample.py:21
jsk_rviz_plugins::RobotCommandInterfaceAction::signal_mapper_
QSignalMapper * signal_mapper_
Definition: robot_command_interface.h:31
jsk_rviz_plugins::RobotCommandInterfaceAction::callRequestEusCommand
bool callRequestEusCommand(const std::string &command)
Definition: robot_command_interface.cpp:129
jsk_rviz_plugins::RobotCommandInterfaceAction::RobotCommandInterfaceAction
RobotCommandInterfaceAction(QWidget *parent=0)
Definition: robot_command_interface.cpp:21
retriever.h
jsk_rviz_plugins::RobotCommandInterfaceAction::popupDialog
void popupDialog(const std::string &text)
Definition: robot_command_interface.cpp:155
jsk_rviz_plugins
Definition: __init__.py:1
jsk_rviz_plugins::RobotCommandInterfaceAction::buttonCallback
void buttonCallback(int i)
Definition: robot_command_interface.cpp:136
jsk_rviz_plugins::RobotCommandInterfaceAction::euscommand_mapping_
std::map< int, std::string > euscommand_mapping_
Definition: robot_command_interface.h:32
ros::NodeHandle


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Jan 22 2024 03:47:13