my_plugin.cpp
Go to the documentation of this file.
00001 
00002 #include <pluginlib/class_list_macros.h>
00003 #include <QStringList>
00004 #include <rqt_gauges/my_plugin.h>
00005 #include <rqt_gauges/qcgaugewidget.h>
00006 #include <stdlib.h>
00007 #include <sstream>
00008 
00009 namespace rqt_gauges {
00010 
00011 // Callback to change the position of the needle
00012 void MyPlugin::newDataCallback(const std_msgs::Float64& msg)
00013 {
00014   mSpeedNeedle_-> setCurrentValue(msg.data);
00015 }
00016 
00017 // Constructor is called first before initPlugin function, needless to say.
00018 MyPlugin::MyPlugin()
00019   : rqt_gui_cpp::Plugin()
00020   , widget_(0)
00021 {
00022   // give QObjects reasonable names
00023   setObjectName("Gauge");
00024 }
00025 
00026 void MyPlugin::initPlugin(qt_gui_cpp::PluginContext& context)
00027 {
00028   // access standalone command line arguments
00029   //QStringList argv = context.argv();
00030 
00031   // create QWidget
00032   mSpeedGauge_ = new QcGaugeWidget();
00033   widget_ = mSpeedGauge_; // This works because mSpeedGauge is inherited from a QWidget class, I guess
00034   // extend the widget with all attributes and children from UI file
00035   ui_.setupUi(widget_);
00036 
00037   // Window title
00038   widget_->setWindowTitle("Gauge[*]");
00039   if (context.serialNumber() != 1)
00040   {
00041     widget_->setWindowTitle(widget_->windowTitle() + " (" + QString::number(context.serialNumber()) + ")");
00042   }
00043 
00044   // Set default parameters for the gauge. To customize, these can be overwritten.
00045   // See http://wiki.ros.org/Parameter%20Server
00046   // The parameters are numbered so multiple gauges can be launched.
00047 
00048   std::string gaugeNum;
00049   std::stringstream out;
00050   out << context.serialNumber();
00051   gaugeNum = out.str();
00052 
00053   // Set each parameter if it isn't defined already
00054   if (!getNodeHandle().hasParam("topic"+gaugeNum))
00055     getNodeHandle().setParam("topic"+gaugeNum, "/roll");
00056   if (!getNodeHandle().hasParam("gauge_name"+gaugeNum))
00057     getNodeHandle().setParam("gauge_name"+gaugeNum, "Roll");
00058   if (!getNodeHandle().hasParam("minimum"+gaugeNum))
00059     getNodeHandle().setParam("minimum"+gaugeNum, 0);
00060   if (!getNodeHandle().hasParam("maximum"+gaugeNum))
00061     getNodeHandle().setParam("maximum"+gaugeNum, 100);
00062   if (!getNodeHandle().hasParam("danger_threshold"+gaugeNum))
00063     getNodeHandle().setParam("danger_threshold"+gaugeNum, 50);
00064   if (! getNodeHandle().hasParam("pixel_size"+gaugeNum))
00065     getNodeHandle().setParam("pixel_size"+gaugeNum, 200); // width and height
00066 
00067   // Set up the gauge
00068   int gauge_size = 150;
00069   getNodeHandle().getParam("pixel_size"+gaugeNum, gauge_size);
00070   mSpeedGauge_->setFixedHeight(gauge_size);
00071   mSpeedGauge_->setFixedWidth(gauge_size);
00072   mSpeedGauge_->addBackground(99);
00073   QcBackgroundItem *bkg1 = mSpeedGauge_->addBackground(92);
00074   bkg1->clearrColors();
00075   bkg1->addColor(0.1,Qt::black);
00076   bkg1->addColor(1.0,Qt::white);
00077 
00078   QcBackgroundItem *bkg2 = mSpeedGauge_->addBackground(88);
00079   bkg2->clearrColors();
00080   bkg2->addColor(0.1,Qt::gray);
00081   bkg2->addColor(1.0,Qt::darkGray);
00082 
00083   // Gauge label
00084   std::string gaugeName;
00085   getNodeHandle().getParam("gauge_name"+gaugeNum, gaugeName);
00086   mSpeedGauge_->addLabel(70)->setText(gaugeName.c_str());
00087 
00088   // Range of the indicator
00089   int minimum = 0;
00090   getNodeHandle().getParam("minimum"+gaugeNum, minimum);
00091   int maximum = 100;
00092   getNodeHandle().getParam("maximum"+gaugeNum, maximum);
00093   //mSpeedGauge->addArc(55);
00094   mSpeedGauge_->addDegrees(65)->setValueRange(minimum, maximum);
00095   //mSpeedGauge->addColorBand(50);
00096   mSpeedGauge_->addValues(80)->setValueRange(minimum, maximum);
00097 
00098   // The needle
00099   QcLabelItem *lab = mSpeedGauge_->addLabel(40);
00100   lab->setText("0");
00101   mSpeedNeedle_ = mSpeedGauge_->addNeedle(60);
00102   mSpeedNeedle_->setLabel(lab);
00103   mSpeedNeedle_->setColor(Qt::black);
00104   mSpeedNeedle_->setValueRange(minimum,maximum);
00105   mSpeedGauge_->addBackground(7);
00106   mSpeedGauge_->addGlass(88);
00107 
00108   // Color band. Red starts at "danger_threshold"
00109   double threshold = 0.;
00110   getNodeHandle().getParam("danger_threshold"+gaugeNum, threshold);
00111   mSpeedGauge_->addColorBand(threshold);
00112 
00113   // add widget to the user interface
00114   context.addWidget(widget_);
00115 
00116   // Subscribe to new data
00117   std::string topicName;
00118   getNodeHandle().getParam("topic"+gaugeNum, topicName);
00119   needleSub_ = getNodeHandle().subscribe (topicName, 1, &rqt_gauges::MyPlugin::newDataCallback, this);
00120 }
00121 
00122 void MyPlugin::shutdownPlugin()
00123 {
00124   needleSub_.shutdown();
00125 }
00126 
00127 void MyPlugin::saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const
00128 {
00129   // TODO save intrinsic configuration, usually using:
00130   // instance_settings.setValue(k, v)
00131 }
00132 
00133 void MyPlugin::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings)
00134 {
00135   // TODO restore intrinsic configuration, usually using:
00136   // v = instance_settings.value(k)
00137 }
00138 
00139 /*bool hasConfiguration() const
00140 {
00141   return true;
00142 }
00143 
00144 void triggerConfiguration()
00145 {
00146   // Usually used to open a dialog to offer the user a set of configuration
00147 }*/
00148 
00149 } // namespace
00150 PLUGINLIB_EXPORT_CLASS(rqt_gauges::MyPlugin, rqt_gui_cpp::Plugin)


gauges
Author(s):
autogenerated on Sat Jun 8 2019 19:36:19