qt_ros_slider.h
Go to the documentation of this file.
00001 /****************************************************************************
00002 **
00003 ** Copyright (C) 2005-2007 Trolltech ASA. All rights reserved.
00004 **
00005 ** This file is part of the example classes of the Qt Toolkit.
00006 **
00007 ** This file may be used under the terms of the GNU General Public
00008 ** License version 2.0 as published by the Free Software Foundation
00009 ** and appearing in the file LICENSE.GPL included in the packaging of
00010 ** this file.  Please review the following information to ensure GNU
00011 ** General Public Licensing requirements will be met:
00012 ** http://www.trolltech.com/products/qt/opensource.html
00013 **
00014 ** If you are unsure which license is appropriate for your use, please
00015 ** review the following information:
00016 ** http://www.trolltech.com/products/qt/licensing.html or contact the
00017 ** sales department at sales@trolltech.com.
00018 **
00019 ** This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
00020 ** WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
00021 **
00022 ****************************************************************************/
00023 
00024 #ifndef LCDRANGE_H
00025 #define LCDRANGE_H
00026 
00027 #include <ros/ros.h>
00028 #include <QLCDNumber>
00029 #include <QWidget>
00030 #include <geometry_msgs/Twist.h>
00031 
00032 // for torso
00033 #include <actionlib/client/simple_action_client.h>
00034 #include <actionlib/client/terminal_state.h>
00035 #include <pr2_controllers_msgs/SingleJointPositionAction.h>
00036 
00037 // for gripper
00038 #include <pr2_controllers_msgs/Pr2GripperCommand.h>
00039 
00040 class QLabel;
00041 class QSlider;
00042 
00043 class QtRosSlider : public QWidget
00044 {
00045     Q_OBJECT
00046 
00047 public:
00048     QtRosSlider(const QString &text, QWidget *_parent = 0);
00049 
00050     int value() const;
00051     QString text() const;
00052 
00053     void setCallback(actionlib::SimpleActionClient<pr2_controllers_msgs::SingleJointPositionAction> *_ac);
00054     void addGripperPublisher(ros::Publisher _pub);
00055 
00056     int min_int;
00057     int max_int;
00058     double min_value;
00059     double max_value;
00060 public slots:
00061     void setValue(double value);
00062     void setRange(int minValue, int maxValue);
00063     void setText(const QString &text);
00064     void conversion(int value);
00065     double convert(int value);
00066     void onValueChange(int value);
00067 
00068 signals:
00069     void valueChanged(int newValue);
00070 
00071 private:
00072     void initTorsoCommander();
00073     void initGripperCommander();
00074     QLCDNumber *lcd;
00075     QSlider *slider;
00076     QLabel *label;
00077     actionlib::SimpleActionClient<pr2_controllers_msgs::SingleJointPositionAction> *ac;
00078     std::vector<ros::Publisher> gripper_publishers;
00079     std::vector<ros::Publisher> base_publishers;
00080 };
00081 
00082 #endif


pr2_gazebo
Author(s): John Hsu
autogenerated on Thu Apr 24 2014 15:48:38