my_plugin.cpp
Go to the documentation of this file.
1 
3 #include <QStringList>
4 #include <rqt_gauges/my_plugin.h>
6 #include <stdlib.h>
7 #include <sstream>
8 
9 namespace rqt_gauges {
10 
11 // Callback to change the position of the needle
12 void MyPlugin::newDataCallback(const std_msgs::Float64& msg)
13 {
14  mSpeedNeedle_-> setCurrentValue(msg.data);
15 }
16 
17 // Constructor is called first before initPlugin function, needless to say.
19  : rqt_gui_cpp::Plugin()
20  , widget_(0)
21 {
22  // give QObjects reasonable names
23  setObjectName("Gauge");
24 }
25 
27 {
28  // access standalone command line arguments
29  //QStringList argv = context.argv();
30 
31  // create QWidget
33  widget_ = mSpeedGauge_; // This works because mSpeedGauge is inherited from a QWidget class, I guess
34  // extend the widget with all attributes and children from UI file
35  ui_.setupUi(widget_);
36 
37  // Window title
38  widget_->setWindowTitle("Gauge[*]");
39  if (context.serialNumber() != 1)
40  {
41  widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
42  }
43 
44  // Set default parameters for the gauge. To customize, these can be overwritten.
45  // See http://wiki.ros.org/Parameter%20Server
46  // The parameters are numbered so multiple gauges can be launched.
47 
48  std::string gaugeNum;
49  std::stringstream out;
50  out << context.serialNumber();
51  gaugeNum = out.str();
52 
53  // Set each parameter if it isn't defined already
54  if (!getNodeHandle().hasParam("topic"+gaugeNum))
55  getNodeHandle().setParam("topic"+gaugeNum, "/roll");
56  if (!getNodeHandle().hasParam("gauge_name"+gaugeNum))
57  getNodeHandle().setParam("gauge_name"+gaugeNum, "Roll");
58  if (!getNodeHandle().hasParam("minimum"+gaugeNum))
59  getNodeHandle().setParam("minimum"+gaugeNum, 0);
60  if (!getNodeHandle().hasParam("maximum"+gaugeNum))
61  getNodeHandle().setParam("maximum"+gaugeNum, 100);
62  if (!getNodeHandle().hasParam("danger_threshold"+gaugeNum))
63  getNodeHandle().setParam("danger_threshold"+gaugeNum, 50);
64  if (! getNodeHandle().hasParam("pixel_size"+gaugeNum))
65  getNodeHandle().setParam("pixel_size"+gaugeNum, 200); // width and height
66 
67  // Set up the gauge
68  int gauge_size = 150;
69  getNodeHandle().getParam("pixel_size"+gaugeNum, gauge_size);
70  mSpeedGauge_->setFixedHeight(gauge_size);
71  mSpeedGauge_->setFixedWidth(gauge_size);
74  bkg1->clearrColors();
75  bkg1->addColor(0.1,Qt::black);
76  bkg1->addColor(1.0,Qt::white);
77 
79  bkg2->clearrColors();
80  bkg2->addColor(0.1,Qt::gray);
81  bkg2->addColor(1.0,Qt::darkGray);
82 
83  // Gauge label
84  std::string gaugeName;
85  getNodeHandle().getParam("gauge_name"+gaugeNum, gaugeName);
86  mSpeedGauge_->addLabel(70)->setText(gaugeName.c_str());
87 
88  // Range of the indicator
89  int minimum = 0;
90  getNodeHandle().getParam("minimum"+gaugeNum, minimum);
91  int maximum = 100;
92  getNodeHandle().getParam("maximum"+gaugeNum, maximum);
93  //mSpeedGauge->addArc(55);
94  mSpeedGauge_->addDegrees(65)->setValueRange(minimum, maximum);
95  //mSpeedGauge->addColorBand(50);
96  mSpeedGauge_->addValues(80)->setValueRange(minimum, maximum);
97 
98  // The needle
99  QcLabelItem *lab = mSpeedGauge_->addLabel(40);
100  lab->setText("0");
102  mSpeedNeedle_->setLabel(lab);
103  mSpeedNeedle_->setColor(Qt::black);
104  mSpeedNeedle_->setValueRange(minimum,maximum);
106  mSpeedGauge_->addGlass(88);
107 
108  // Color band. Red starts at "danger_threshold"
109  double threshold = 0.;
110  getNodeHandle().getParam("danger_threshold"+gaugeNum, threshold);
111  mSpeedGauge_->addColorBand(threshold);
112 
113  // add widget to the user interface
114  context.addWidget(widget_);
115 
116  // Subscribe to new data
117  std::string topicName;
118  getNodeHandle().getParam("topic"+gaugeNum, topicName);
120 }
121 
123 {
125 }
126 
127 void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
128 {
129  // TODO save intrinsic configuration, usually using:
130  // instance_settings.setValue(k, v)
131 }
132 
133 void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
134 {
135  // TODO restore intrinsic configuration, usually using:
136  // v = instance_settings.value(k)
137 }
138 
139 /*bool hasConfiguration() const
140 {
141  return true;
142 }
143 
144 void triggerConfiguration()
145 {
146  // Usually used to open a dialog to offer the user a set of configuration
147 }*/
148 
149 } // namespace
virtual void initPlugin(qt_gui_cpp::PluginContext &context)
Definition: my_plugin.cpp:26
QcNeedleItem * mSpeedNeedle_
Definition: my_plugin.h:32
ros::Subscriber needleSub_
Definition: my_plugin.h:33
virtual void saveSettings(qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const
Definition: my_plugin.cpp:127
QcDegreesItem * addDegrees(float position)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void restoreSettings(const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings)
Definition: my_plugin.cpp:133
QcBackgroundItem * addBackground(float position)
QcGlassItem * addGlass(float position)
void setText(const QString &text, bool repaint=true)
void addWidget(QWidget *widget)
QWidget * widget_
Definition: my_plugin.h:30
QcNeedleItem * addNeedle(float position)
QcGaugeWidget * mSpeedGauge_
Definition: my_plugin.h:31
virtual void shutdownPlugin()
Definition: my_plugin.cpp:122
void setValueRange(float minValue, float maxValue)
QcColorBand * addColorBand(float position)
void setLabel(QcLabelItem *)
QcValuesItem * addValues(float position)
ros::NodeHandle & getNodeHandle() const
bool getParam(const std::string &key, std::string &s) const
void setColor(const QColor &color)
void newDataCallback(const std_msgs::Float64 &msg)
Definition: my_plugin.cpp:12
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
QcLabelItem * addLabel(float position)
void addColor(float position, const QColor &color)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const


gauges
Author(s):
autogenerated on Sat Apr 11 2020 03:54:59