Go to the documentation of this file.00001
00018 #include "VisualisationUtils/laserscanwidget.h"
00019 #include <iostream>
00020
00021 #include <QtGui/QApplication>
00022 #include <QtConcurrentRun>
00023
00024 #include <qapplication.h>
00025 #ifndef Q_MOC_RUN
00026 #include <sensor_msgs/LaserScan.h>
00027 #include <ros/ros.h>
00028 #include <ros/init.h>
00029 #include <qwt_series_data.h>
00030 #include <qwt_symbol.h>
00031 #endif
00032 #include <QLayout>
00033
00034 using namespace std;
00035 LaserScanWidget::LaserScanWidget(QWidget *parent, int appearance, unsigned int showData, LaserScanThread *currentThread) :
00036 QWidget(parent)
00037 {
00038 this->currentThread = currentThread;
00039 connect(currentThread, SIGNAL(valueChanged()),this, SLOT(replot()));
00040
00041 plot_flat = 0;
00042 this->appearance = -1;
00043 setGraph(appearance, showData);
00044 }
00045
00046 void LaserScanWidget::setGraph(int appearance, unsigned int showData)
00047 {
00048 QPen pen1(Qt::gray, 1, Qt::SolidLine);
00049 QPen pen2(Qt::red, 1, Qt::SolidLine);
00050 QPen pen3(Qt::green, 1, Qt::SolidLine);
00051 QPen pen4(Qt::red, 3, Qt::SolidLine);
00052 QPen pen5(Qt::red, 3, Qt::SolidLine);
00053
00054 if (this->appearance != appearance)
00055 {
00056
00057
00058
00059
00060
00061
00062
00063 if (plot_flat != 0)
00064 {
00065 plot_flat->setVisible(false);
00066
00067 delete plot_flat;
00068 plot_flat = 0;
00069 }
00070
00071 this->appearance = appearance;
00072
00073 if (appearance == APPEARENCE_POLAR)
00074 {
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116 }
00117 else if (appearance == APPEARENCE_FLAT)
00118 {
00119 plot_flat = new QwtPlot(this);
00120 plot_flat->setAxisScale(QwtPlot::yLeft, 0,6);
00121 plot_flat->setAxisScale(QwtPlot::xBottom, currentThread->starting_angle,currentThread->starting_angle + currentThread->angle_spread,30.0);
00122
00123 curve_roh_flat = new QwtPlotCurve();
00124 curve_roh_flat->setPen(pen1);
00125 curve_roh_flat->setRawSamples(currentThread->dx, currentThread->data_raw, currentThread->data_field_size);
00126
00127 curve_gemittelt_flat = new QwtPlotCurve();
00128 curve_gemittelt_flat->setPen(pen2);
00129 curve_gemittelt_flat->setRawSamples(currentThread->dx, currentThread->data_avg, currentThread->data_field_size);
00130
00131 curve_gauss_flat = new QwtPlotCurve();
00132 curve_gauss_flat->setPen(pen3);
00133 curve_gauss_flat->setRawSamples(currentThread->dx, currentThread->data_filtered, currentThread->data_field_size);
00134
00135 curve_erkannt_flat = new QwtPlotCurve();
00136 curve_erkannt_flat->setPen(pen4);
00137 curve_erkannt_flat->setRawSamples(currentThread->dx, currentThread->data_segments, currentThread->data_field_size);
00138
00139 curve_ecke_flat = new QwtPlotCurve();
00140 curve_ecke_flat->setPen(pen5);
00141 curve_ecke_flat->setRawSamples(currentThread->dx, currentThread->data_edges, currentThread->data_field_size);
00142
00143 plot_flat->setAutoReplot(true);
00144 plot_flat->show();
00145 plot_flat->resize(this->width(),this->height());
00146 }
00147 setCurves(showData);
00148 }
00149 }
00150
00151 void LaserScanWidget::replot()
00152 {
00153 if (this->appearance == APPEARENCE_POLAR)
00154 {
00155
00156
00157
00158
00159
00160
00161 }
00162 else if (appearance == APPEARENCE_FLAT)
00163 {
00164 plot_flat->replot();
00165 }
00166 }
00167
00168
00169 void LaserScanWidget::setCurves(unsigned int showData)
00170 {
00171 if (this->appearance == APPEARENCE_POLAR)
00172 {
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219 }
00220 else if (appearance == APPEARENCE_FLAT)
00221 {
00222 if ((showData & 1) != 0)
00223 {
00224 curve_roh_flat->attach(plot_flat);
00225 curve_roh_flat->show();
00226 }
00227 else
00228 {
00229 curve_roh_flat->detach();
00230 }
00231 if ((showData & 2) != 0)
00232 {
00233 curve_gemittelt_flat->attach(plot_flat);
00234 curve_gemittelt_flat->show();
00235 }
00236 else
00237 {
00238 curve_gemittelt_flat->detach();
00239 }
00240 if ((showData & 4) != 0)
00241 {
00242 curve_gauss_flat->attach(plot_flat);
00243 curve_gauss_flat->show();
00244 }
00245 else
00246 {
00247 curve_gauss_flat->detach();
00248 }
00249 if ((showData & 8) != 0)
00250 {
00251 curve_erkannt_flat->attach(plot_flat);
00252 curve_erkannt_flat->show();
00253 }
00254 else
00255 {
00256 curve_erkannt_flat->detach();
00257 }
00258 if ((showData & 16) != 0)
00259 {
00260 curve_ecke_flat->attach(plot_flat);
00261 curve_ecke_flat->show();
00262 }
00263 else
00264 {
00265 curve_ecke_flat->detach();
00266 }
00267 plot_flat->replot();
00268 }
00269 }
00270
00271 void LaserScanWidget::resizeEvent(QResizeEvent * event)
00272 {
00273 if (this->appearance == APPEARENCE_POLAR)
00274 {
00275
00276 }
00277 else
00278 {
00279 plot_flat->resize(this->width(),this->height());
00280 }
00281 QWidget::resizeEvent(event);
00282 }
00283
00284
00285