00001 #ifndef UOS_ROTUNIT_TELEOP__RVIZ_SCAN_TOOL_H_ 00002 #define UOS_ROTUNIT_TELEOP__RVIZ_SCAN_TOOL_H_ 00003 00004 #include <ros/ros.h> 00005 #include <rviz/tool.h> 00006 #include <geometry_msgs/Twist.h> 00007 #include <actionlib/client/simple_action_client.h> 00008 #include <actionlib/client/terminal_state.h> 00009 #include <actionlib/client/simple_client_goal_state.h> 00010 #include <uos_rotunit_snapshotter/RotunitSnapshotAction.h> 00011 #include <uos_rotunit_driver/RotVelSrv.h> 00012 00013 00014 #ifndef Q_MOC_RUN // See: https://bugreports.qt-project.org/browse/QTBUG-22829 00015 #include <QObject> 00016 #include <QCursor> 00017 #endif 00018 00019 namespace uos_rotunit_teleop{ 00020 class RvizScanTool: public rviz::Tool 00021 { 00022 Q_OBJECT 00023 public: 00024 RvizScanTool(); 00025 ~RvizScanTool(); 00026 00027 virtual void onInitialize(); 00028 00029 virtual void activate(); 00030 virtual void deactivate(); 00031 00032 virtual int processMouseEvent( rviz::ViewportMouseEvent& event ); 00033 00034 void doneCb( 00035 const actionlib::SimpleClientGoalState& state, 00036 const uos_rotunit_snapshotter::RotunitSnapshotResultConstPtr& result); 00037 00038 private: 00039 ros::ServiceClient rot_vel_client_; 00040 double timeout_; 00041 actionlib::SimpleActionClient<uos_rotunit_snapshotter::RotunitSnapshotAction> ac_; 00042 int flags_; 00043 }; 00044 } /* namespace uos_rotunit_teleop */ 00045 00046 #endif /* rviz_scan_tool.h */