aubopanel.h
Go to the documentation of this file.
00001 #ifndef AUBO_PANEL_H
00002 #define AUBO_PANEL_H
00003 
00004 #include  <ros/ros.h>
00005 #include  <rviz/panel.h>
00006 #include  <sensor_msgs/JointState.h>
00007 #include  <std_msgs/Float32MultiArray.h>
00008 #include  <aubo_msgs/IOState.h>
00009 #include  <aubo_msgs/GoalPoint.h>
00010 #include  <QWidget>
00011 #include  <QTimer>
00012 
00013 
00014 namespace Ui {
00015     class AuboPanel;
00016 }
00017 
00018 
00019 namespace aubo_panel
00020 {
00021     class AuboPanel : public rviz::Panel
00022     {
00023         Q_OBJECT
00024 
00025     public:
00026         explicit AuboPanel(QWidget *parent = 0);
00027         ~AuboPanel();
00028 
00029     public:
00030         void initROS();
00031 
00032     private Q_SLOTS:
00033         void on_pbn_joint1Left_pressed();
00034         void on_pbn_joint1Right_pressed();
00035         void on_pbn_joint2Left_pressed();
00036         void on_pbn_joint2Right_pressed();
00037         void on_pbn_joint3Left_pressed();
00038         void on_pbn_joint3Right_pressed();
00039         void on_pbn_joint4Left_pressed();
00040         void on_pbn_joint4Right_pressed();
00041         void on_pbn_joint5Left_pressed();
00042         void on_pbn_joint5Right_pressed();
00043         void on_pbn_joint6Left_pressed();
00044         void on_pbn_joint6Right_pressed();
00045 
00046         void on_pbn_zero_clicked();
00047         void on_pbn_classicPos1_clicked();
00048         void on_pbn_classicPos2_clicked();
00049         void on_pbn_sendGoal_clicked();
00050 
00051         void on_rbx_pcan_clicked();
00052         void on_rbx_tcp_clicked();
00053 
00054         void on_rbx_continuous_clicked();
00055         void on_rbx_goal_clicked();
00056         void on_rbx_moveit_clicked();
00057         void on_rbx_sync_clicked();
00058 
00059         void on_pbn_setIO_clicked();
00060 
00061     protected Q_SLOTS:
00062         void sendCommand();
00063 
00064     protected:
00065         QTimer* m_timer;
00066 
00067         // The ROS publisher/subscriber
00068         ros::Publisher cmd1_publisher_;
00069         ros::Publisher cmd2_publisher_;
00070         ros::Publisher cmd3_publisher_;
00071         ros::Publisher goal_publisher_;
00072         ros::Publisher io_publisher_;
00073 
00074         sensor_msgs::JointState jointMsg;
00075         std_msgs::Float32MultiArray joints;
00076         aubo_msgs::IOState iostate;
00077         aubo_msgs::GoalPoint goalPoint;
00078 
00079         ros::Subscriber subJointState_;
00080         void jointStateCallback(const sensor_msgs::JointState::ConstPtr& msg);
00081         int pointCompare(void);
00082 
00083         // The ROS node handle.
00084         ros::NodeHandle nh_;
00085 
00086         float jointVelocities[6];
00087         float jointPosition[6];
00088         float lastJointPosition[6];
00089 
00090     private:
00091         Ui::AuboPanel *ui;
00092         float m_step;
00093         float m_speed;
00094 
00095         int m_jointStateSync;
00096         int m_controMode;
00097         int m_busInterface;
00098     };
00099 }//end of aubo_rviz_plugin
00100 
00101 #endif // AUBO_PANEL_H


aubo_panel
Author(s): liuxin
autogenerated on Wed Sep 6 2017 03:06:50