From 1794ce50c0fdfd3f5e716cd43be0aaa5701d2d28 Mon Sep 17 00:00:00 2001 From: pip Date: Wed, 30 Jun 2010 20:22:18 +0000 Subject: [PATCH] Changed function names on various slots in the OPMap plug-in to stop warning messages. git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@953 ebee16cc-31ac-478f-84a7-5cbb03baadba --- .../plugins/opmap/images/waypoint_marker1.png | Bin 0 -> 4359 bytes .../plugins/opmap/images/waypoint_marker2.png | Bin 0 -> 4385 bytes ground/src/plugins/opmap/opmap.qrc | 2 + .../opmap/opmap_waypointeditor_dialog.cpp | 33 +++++--- .../opmap/opmap_waypointeditor_dialog.h | 13 ++- .../src/plugins/opmap/opmapgadgetwidget.cpp | 76 +++++++++--------- ground/src/plugins/opmap/opmapgadgetwidget.h | 36 ++++----- 7 files changed, 92 insertions(+), 68 deletions(-) create mode 100644 ground/src/plugins/opmap/images/waypoint_marker1.png create mode 100644 ground/src/plugins/opmap/images/waypoint_marker2.png diff --git a/ground/src/plugins/opmap/images/waypoint_marker1.png b/ground/src/plugins/opmap/images/waypoint_marker1.png new file mode 100644 index 0000000000000000000000000000000000000000..179be20075e5c973c890e292034df9d521820aae GIT binary patch literal 4359 zcmV+i5%}(jP)KLZ*U+IBfRsybQWXdwQbLP>6pAqfylh#{fb6;Z(vMMVS~$e@S=j*ftg6;Uhf59&ghTmgWD0l;*T zI709Y^p6lP1rIRMx#05C~cW=H_Aw*bJ-5DT&Z2n+x)QHX^p z00esgV8|mQcmRZ%02D^@S3L16t`O%c004NIvOKvYIYoh62rY33S640`D9%Y2D-rV&neh&#Q1i z007~1e$oCcFS8neI|hJl{-P!B1ZZ9hpmq0)X0i`JwE&>$+E?>%_LC6RbVIkUx0b+_+BaR3cnT7Zv!AJxW zizFb)h!jyGOOZ85F;a?DAXP{m@;!0_IfqH8(HlgRxt7s3}k3K`kFu>>-2Q$QMFfPW!La{h336o>X zu_CMttHv6zR;&ZNiS=X8v3CR#fknUxHUxJ0uoBa_M6WNWeqIg~6QE69c9o#eyhGvpiOA@W-aonk<7r1(?fC{oI5N*U!4 zfg=2N-7=cNnjjOr{yriy6mMFgG#l znCF=fnQv8CDz++o6_Lscl}eQ+l^ZHARH>?_s@|##Rr6KLRFA1%Q+=*RRWnoLsR`7U zt5vFIcfW3@?wFpwUVxrVZ>QdQz32KIeJ}k~{cZZE^+ya? z2D1z#2HOnI7(B%_ac?{wFUQ;QQA1tBKtrWrm0_3Rgps+?Jfqb{jYbcQX~taRB;#$y zZN{S}1|}gUOHJxc?wV3fxuz+mJ4`!F$IZ;mqRrNsHJd##*D~ju=bP7?-?v~|cv>vB zsJ6IeNwVZxrdjT`yl#bBIa#GxRa#xMMy;K#CDyyGyQdMSxlWT#tDe?p!?5wT$+oGt z8L;Kp2HUQ-ZMJ=3XJQv;x5ci*?vuTfeY$;({XGW_huIFR9a(?@3)XSs8O^N5RyOM=TTmp(3=8^+zpz2r)C z^>JO{deZfso3oq3?Wo(Y?l$ge?uXo;%ru`Vo>?<<(8I_>;8Eq#KMS9gFl*neeosSB zfoHYnBQIkwkyowPu(zdms`p{<7e4kra-ZWq<2*OsGTvEV%s0Td$hXT+!*8Bnh2KMe zBmZRodjHV?r+_5^X9J0WL4jKW`}lf%A-|44I@@LTvf1rHjG(ze6+w@Jt%Bvjts!X0 z?2xS?_ve_-kiKB_KiJlZ$9G`c^=E@oNG)mWWaNo-3TIW8)$Hg0Ub-~8?KhvJ>$ z3*&nim@mj(aCxE5!t{lw7O5^0EIO7zOo&c6l<+|iDySBWCGrz@C5{St!X3hAA}`T4 z(TLbXTq+(;@<=L8dXnssyft|w#WSTW<++3>sgS%(4NTpeI-VAqb|7ssJvzNHgOZVu zaYCvgO_R1~>SyL=cFU|~g|hy|Zi}}s9+d~lYqOB71z9Z$wnC=pR9Yz4DhIM>Wmjgu z&56o6maCpC&F##y%G;1PobR9i?GnNg;gYtchD%p19a!eQtZF&3JaKv33gZ<8D~47E ztUS1iwkmDaPpj=$m#%)jCVEY4fnLGNg2A-`YwHVD3gv};>)hAvT~AmqS>Lr``i7kw zJ{5_It`yrBmlc25DBO7E8;5VoznR>Ww5hAaxn$2~(q`%A-YuS64wkBy=9dm`4cXeX z4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC-q*U}&`cyXV(%rRT*Z6MH?i+i& z_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-Nmiuj8txj!m?Z*Ss1N{dh4z}01 z)YTo*JycSU)+_5r4#yw9{+;i4Ee$peRgIj+;v;ZGdF1K$3E%e~4LaI(jC-u%2h$&R z9cLXcYC@Xwnns&bn)_Q~Te?roKGD|d-g^8;+aC{{G(1^(O7m37Y1-+6)01cN&y1aw zoqc{T`P^XJqPBbIW6s}d4{z_f5Om?vMgNQEJG?v2T=KYd^0M3I6IZxbny)%vZR&LD zJpPl@Psh8QyPB@KTx+@RdcC!KX7}kEo;S|j^u2lU7XQ}Oo;f|;z4Ll+_r>@1-xl3| zawq-H%e&ckC+@AhPrP6BKT#_XdT7&;F71j}Joy zkC~6lh7E@6o;W@^IpRNZ{ptLtL(gQ-CY~4mqW;US7Zxvm_|@yz&e53Bp_lTPlfP|z zrTyx_>lv@x#=^!PzR7qqF<$gm`|ZJZ+;<)Cqu&ot2z=00004XF*Lt006O$eEU(80000WV@Og>004R=004l4008;_004mL004C` z008P>0026e000+nl3&F}000IeNkl7-k6~}+~zIh)rwx8|9&&E!mm_%un z29Xp|Dm4qBNZG)mfwDtLpdztDAb}8+k43v;SBXVn5d?xJ4XP+rR6rFxpP=d5}CA3=-JHX>No#$?*E)~)#1a3*|TR4b8~Z)%VmNfpxJD) zwzl@b>gwv}uU)(LiPhEBDtUOo0`NCr89+qX8rI&udzqh~XJllAD2fQf(9v3dzf>xH zYy0?kZEn}cIJm7!==Qu~BAw(g>F_;t-=wgwIQjBC7wXqSN{oLa`Ha9a3yr`6_0%!oG)c3}0 z`@sI4J46=>5C+g~LwgfC&0Jv+fH4%breYNs)f&gL`1YqCk(y&a1Uv(vMPwHE#z)4- zC>9EeFoaGEHXG1tLBF5>V3;5xXr(A>jcr-jN;5HHt1s-H2l$#&YTkgqob5F17Qe*ex70&aOCU)KmF&McP#O@!tK+#*=%;N-@JLN_#tEllm?~v%0s)~1$yeiU5E&2CL|^!Hijq};>IyR z-)b}(|K3UALs^GcUWP%P$ZmAV6qjbV@^w8D^99JA5)#kY*6cv5Qw!H;z|sO&+u{hBQq* z;P6YAm)F1gyFVzB7_`oTr7~!Z5g|$qZXB~2gfzmKUoTu#7h0Vb@T7=z?(}k{QUSOO zeDU{}uJ)h(>)$~a@|4RtaA-2TWJoKBXe0@Ly1dNUMl%8qi^#%l7ibY-baWKQaRA-| zzWL+RXLw`fI+RN}P-&9P(2HX>*(u-`cl%U_VTgz@IXTIW9XptrnW0*(K6AC# zcTZfpqOdH;46!k|X~r8j*SXqt0eCh_tIuzSv3I7vro<|c04tpy zE4jMo->=7Ynx=$di065T2-Rwpsi`R@CMN2YO6BE0U#lY`7_Io%+6I!Z(Z9Se5Fkks zJkKMFB1)wa6B83mPEO)D&WQ`{9^HYDWEtn0ZGe~WHH9n@!5Bjj1o*y>Qi{>hQ7p?s zDfL>X({bP4Y>jKBxH<3uPTmuEd;2Fzg75pJX-c_V#q$z`?QlPJ{{y_8b`(VzV-OLtEW;SHdZX8)+vx#Z`oDny!{LxH3`vrNLZLtq z1h}r-TD-Z2Ne#e_4+Pxm$uv#rcDpp2%|Vz9<<^4he<0v(`?#)45Ck+D4eIr}3k1Lj z(EdO`5yA63TCEl$LcLyReSO^p)&U!6-VgZS0RS0jkiDfM6OaG^002ovPDHLkV1mo@ BB#Qt5 literal 0 HcmV?d00001 diff --git a/ground/src/plugins/opmap/images/waypoint_marker2.png b/ground/src/plugins/opmap/images/waypoint_marker2.png new file mode 100644 index 0000000000000000000000000000000000000000..7834aa5435a3297aff43f2df126b28a9040608c2 GIT binary patch literal 4385 zcmV++5#H{JP)KLZ*U+IBfRsybQWXdwQbLP>6pAqfylh#{fb6;Z(vMMVS~$e@S=j*ftg6;Uhf59&ghTmgWD0l;*T zI709Y^p6lP1rIRMx#05C~cW=H_Aw*bJ-5DT&Z2n+x)QHX^p z00esgV8|mQcmRZ%02D^@S3L16t`O%c004NIvOKvYIYoh62rY33S640`D9%Y2D-rV&neh&#Q1i z007~1e$oCcFS8neI|hJl{-P!B1ZZ9hpmq0)X0i`JwE&>$+E?>%_LC6RbVIkUx0b+_+BaR3cnT7Zv!AJxW zizFb)h!jyGOOZ85F;a?DAXP{m@;!0_IfqH8(HlgRxt7s3}k3K`kFu>>-2Q$QMFfPW!La{h336o>X zu_CMttHv6zR;&ZNiS=X8v3CR#fknUxHUxJ0uoBa_M6WNWeqIg~6QE69c9o#eyhGvpiOA@W-aonk<7r1(?fC{oI5N*U!4 zfg=2N-7=cNnjjOr{yriy6mMFgG#l znCF=fnQv8CDz++o6_Lscl}eQ+l^ZHARH>?_s@|##Rr6KLRFA1%Q+=*RRWnoLsR`7U zt5vFIcfW3@?wFpwUVxrVZ>QdQz32KIeJ}k~{cZZE^+ya? z2D1z#2HOnI7(B%_ac?{wFUQ;QQA1tBKtrWrm0_3Rgps+?Jfqb{jYbcQX~taRB;#$y zZN{S}1|}gUOHJxc?wV3fxuz+mJ4`!F$IZ;mqRrNsHJd##*D~ju=bP7?-?v~|cv>vB zsJ6IeNwVZxrdjT`yl#bBIa#GxRa#xMMy;K#CDyyGyQdMSxlWT#tDe?p!?5wT$+oGt z8L;Kp2HUQ-ZMJ=3XJQv;x5ci*?vuTfeY$;({XGW_huIFR9a(?@3)XSs8O^N5RyOM=TTmp(3=8^+zpz2r)C z^>JO{deZfso3oq3?Wo(Y?l$ge?uXo;%ru`Vo>?<<(8I_>;8Eq#KMS9gFl*neeosSB zfoHYnBQIkwkyowPu(zdms`p{<7e4kra-ZWq<2*OsGTvEV%s0Td$hXT+!*8Bnh2KMe zBmZRodjHV?r+_5^X9J0WL4jKW`}lf%A-|44I@@LTvf1rHjG(ze6+w@Jt%Bvjts!X0 z?2xS?_ve_-kiKB_KiJlZ$9G`c^=E@oNG)mWWaNo-3TIW8)$Hg0Ub-~8?KhvJ>$ z3*&nim@mj(aCxE5!t{lw7O5^0EIO7zOo&c6l<+|iDySBWCGrz@C5{St!X3hAA}`T4 z(TLbXTq+(;@<=L8dXnssyft|w#WSTW<++3>sgS%(4NTpeI-VAqb|7ssJvzNHgOZVu zaYCvgO_R1~>SyL=cFU|~g|hy|Zi}}s9+d~lYqOB71z9Z$wnC=pR9Yz4DhIM>Wmjgu z&56o6maCpC&F##y%G;1PobR9i?GnNg;gYtchD%p19a!eQtZF&3JaKv33gZ<8D~47E ztUS1iwkmDaPpj=$m#%)jCVEY4fnLGNg2A-`YwHVD3gv};>)hAvT~AmqS>Lr``i7kw zJ{5_It`yrBmlc25DBO7E8;5VoznR>Ww5hAaxn$2~(q`%A-YuS64wkBy=9dm`4cXeX z4c}I@?e+FW+b@^RDBHV(wnMq2zdX3SWv9u`%{xC-q*U}&`cyXV(%rRT*Z6MH?i+i& z_B8C(+grT%{XWUQ+f@NoP1R=AW&26{v-dx)iK^-Nmiuj8txj!m?Z*Ss1N{dh4z}01 z)YTo*JycSU)+_5r4#yw9{+;i4Ee$peRgIj+;v;ZGdF1K$3E%e~4LaI(jC-u%2h$&R z9cLXcYC@Xwnns&bn)_Q~Te?roKGD|d-g^8;+aC{{G(1^(O7m37Y1-+6)01cN&y1aw zoqc{T`P^XJqPBbIW6s}d4{z_f5Om?vMgNQEJG?v2T=KYd^0M3I6IZxbny)%vZR&LD zJpPl@Psh8QyPB@KTx+@RdcC!KX7}kEo;S|j^u2lU7XQ}Oo;f|;z4Ll+_r>@1-xl3| zawq-H%e&ckC+@AhPrP6BKT#_XdT7&;F71j}Joy zkC~6lh7E@6o;W@^IpRNZ{ptLtL(gQ-CY~4mqW;US7Zxvm_|@yz&e53Bp_lTPlfP|z zrTyx_>lv@x#=^!PzR7qqF<$gm`|ZJZ+;<)Cqu&ot2z=00004XF*Lt006O$eEU(80000WV@Og>004R=004l4008;_004mL004C` z008P>0026e000+nl3&F}000I&Nkl1JR`E+qF7f-;l|@($IrM&}j?in|N(cUzuCs(D51Z%Og`XI_`Pkb6V?*H-WF|QyAn3@V5u} zCkBz@53orWNCdQj7C08v+oVfvoH(Hqr_5EC`OfnboIF=+0uO1e&jH9HCK6dRFb-{H z95_754}Nv>W+Z+%+X7(!lY7W!1UVx^2I%iEh|vutsP1=&`*!(Wxd;nkY^QV@2Rablm`8HCvy#{*T5vMdz+@Diqg% zMiz`LPd&OD;BA+ZC`Aw^I9`k$#I!oDZnRwioXa*YE&auAuGWs-IW+d!Pw$2_Tmu$z zjBOrZ{}X%I|D^|d#{`uq{77MY5ti-K2@_6FH$)Js72t%l7FVvow4cCZ##escQcr3+7d<)Bb? zOA{-|8&J$cJ_k~uQ%$T=Tt8u@>(j72mMveuc=Up>oS@p9JV+HQk}z?AeJ@X3s(s;W zzZG}^WF(jcF!PX+s5B*r6kRu<+3~1%Lw^10lsG@zY5||oTDNcZa-qKnFatdDyJOR< z&;0Z#WHL}Rpj3dYBu-KsFQR4n)V+}3Ps}hm(+GflTI;DBDUdqV^lj|Ntdsyw17H6B z&rk5isjE=RLtg=eBuW$=C#2~{OikDIA5K*PzNxi-{nl8?!1gH)m<+#ng#O_&LW&oq zk@?Mce|Cb%jWoF|070baxB)H8QOYBg zr!UvK-NS#L7UZ*_6k(ju4O8BjTHx|x2jF|})IrkgxCFM3Q7{<3bA-`d<80VEe62WO z9(dvSMM5Xi#ELLf*j~WITk`;~0)Kl)VCV!mEt|-TFb7MF>=2A*qn1Lx$K zd7<+eBA~ipQC)NQ+`IL-Oriw8>*1`dqEk(Iq{7B+o2ZNpEfmVdBY%AJ8amaejNr|) zHT2pV{nNVw0U|%dY1ss}PtMFy85?A9dIy-gcS5`ER)R}2q|7~&#!dPTy73XDOhaU0I#hJ1kkA_@*~`~LlP$B`|@P-SyGj@ z{H}lYpI4Um4463*mDYPN2i83@KoZ7ymP_P^WOD|^vWZzKVOC0$SK1!uW|slZ_9pTA z4gpe?64*YW69SMka}@du6v~D3H7~(iZ1KO`{RdE|n#hX?Y#$XTXstimages/hold.png images/go.png images/combobox_down_arrow.png + images/waypoint_marker2.png + images/waypoint_marker1.png diff --git a/ground/src/plugins/opmap/opmap_waypointeditor_dialog.cpp b/ground/src/plugins/opmap/opmap_waypointeditor_dialog.cpp index 25313b158..2832ae9d3 100644 --- a/ground/src/plugins/opmap/opmap_waypointeditor_dialog.cpp +++ b/ground/src/plugins/opmap/opmap_waypointeditor_dialog.cpp @@ -48,26 +48,37 @@ WaypointItem::WaypointItem(QString name, double latitude, double longitude, doub setFlag(QGraphicsItem::ItemIsMovable, true); setFlag(QGraphicsItem::ItemIsSelectable, true); setFlag(QGraphicsItem::ItemSendsScenePositionChanges, true); + + pixmap.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); } QRectF WaypointItem::boundingRect() const { - return QRectF(-6, -10, 12, 20); +// return QRectF(-6, -10, 12, 20); + return QRectF(-pixmap.width() / 2, -pixmap.height(), pixmap.width(), pixmap.height()); } - +/* QPainterPath WaypointItem::shape() const { QPainterPath path; - path.addEllipse(QPointF(0, 0), 6, 10); +// path.addEllipse(QPointF(0, 0), 6, 10); + path.addRect(pixmap.rect()); return path; } - +*/ void WaypointItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *, QWidget *) { - painter->setPen(Qt::black); - painter->setBrush(QColor(255, 0, 0, 128)); - painter->drawEllipse(QPointF(0, 0), 6, 10); - } +// painter->setPen(Qt::black); +// painter->setBrush(QColor(255, 0, 0, 128)); +// painter->drawEllipse(QPointF(0, 0), 6, 10); + + painter->drawPixmap(-pixmap.width() / 2, -pixmap.height(), pixmap); +} + +void WaypointItem::setPixmap(QPixmap pixmap) +{ + this->pixmap = pixmap.copy(pixmap.rect()); +} // *************************************************************** // Scene object @@ -119,9 +130,12 @@ opmap_waypointeditor_dialog::opmap_waypointeditor_dialog(QWidget *parent) : view = ui->graphicsViewWaypointHeightAndTimeline; scene = new OurScene(); - scene->setSceneRect(QRect(0, 0, 1800, 500)); + scene->setSceneRect(QRect(0, 0, 500, 500)); view->setScene(scene); + waypoint_pixmap1.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + waypoint_pixmap2.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + undoStack = new QUndoStack(); connect(scene, SIGNAL(itemMoved(WaypointItem *, const QPointF &)), this, SLOT(itemMoved(WaypointItem *, const QPointF &))); @@ -138,6 +152,7 @@ opmap_waypointeditor_dialog::opmap_waypointeditor_dialog(QWidget *parent) : scene->addItem(waypoint2); WaypointItem *waypoint3 = new WaypointItem(tr("Waypoint 3"), 0, 0, 100, 8, 5); + waypoint3->setPixmap(waypoint_pixmap2); waypoint3->setPos(scene->width() / 2 + 60, scene->height() / 2); scene->addItem(waypoint3); diff --git a/ground/src/plugins/opmap/opmap_waypointeditor_dialog.h b/ground/src/plugins/opmap/opmap_waypointeditor_dialog.h index cd39a1633..f8d1151dc 100644 --- a/ground/src/plugins/opmap/opmap_waypointeditor_dialog.h +++ b/ground/src/plugins/opmap/opmap_waypointeditor_dialog.h @@ -34,6 +34,7 @@ #include #include #include +#include #include #include "uavobjects/uavobjectmanager.h" @@ -54,6 +55,8 @@ class WaypointItem : public QObject, public QGraphicsItem public: WaypointItem(QString name = "", double latitude = 0, double longitude = 0, double height_feet = 0, int time_seconds = 0, int hold_seconds = 0); + void setPixmap(QPixmap pixmap); + QString waypoint_name; double latitude_degress; double longitude_degress; @@ -61,11 +64,12 @@ class WaypointItem : public QObject, public QGraphicsItem int time_seconds; int hold_seconds; - QRectF boundingRect() const; - QPainterPath shape() const; - void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); + QPixmap pixmap; protected: + QRectF boundingRect() const; +// QPainterPath shape() const; + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); // void timerEvent(QTimerEvent *event); private: @@ -110,6 +114,9 @@ protected: void changeEvent(QEvent *e); private: + QPixmap waypoint_pixmap1; + QPixmap waypoint_pixmap2; + QGraphicsView *view; QGraphicsScene *scene; diff --git a/ground/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/src/plugins/opmap/opmapgadgetwidget.cpp index 9914cf5e5..6c7a62b00 100644 --- a/ground/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/src/plugins/opmap/opmapgadgetwidget.cpp @@ -146,7 +146,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) */ m_widget->comboBoxFindPlace->setAutoCompletion(true); - connect( m_widget->comboBoxFindPlace->lineEdit(), SIGNAL(returnPressed()), this, SLOT(on_comboBoxFindPlace_returnPressed())); + connect( m_widget->comboBoxFindPlace->lineEdit(), SIGNAL(returnPressed()), this, SLOT(comboBoxFindPlace_returnPressed())); // ************** // map stuff @@ -269,7 +269,7 @@ OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) OPMapGadgetWidget::~OPMapGadgetWidget() { - on_clearWayPointsAct_triggered(); + clearWayPointsAct_triggered(); if (wayPoint_treeView_model) delete wayPoint_treeView_model; if (m_map_overlay_widget) delete m_map_overlay_widget; @@ -609,7 +609,7 @@ void OPMapGadgetWidget::WPDeleted(int const &number) // ************************************************************************************* // user control signals -void OPMapGadgetWidget::on_comboBoxFindPlace_returnPressed() +void OPMapGadgetWidget::comboBoxFindPlace_returnPressed() { QString place = m_widget->comboBoxFindPlace->currentText().simplified(); if (place.isNull() || place.isEmpty()) return; @@ -645,7 +645,7 @@ void OPMapGadgetWidget::on_comboBoxFindPlace_returnPressed() void OPMapGadgetWidget::on_toolButtonFindPlace_clicked() { m_widget->comboBoxFindPlace->setFocus(); - on_comboBoxFindPlace_returnPressed(); + comboBoxFindPlace_returnPressed(); } void OPMapGadgetWidget::on_toolButtonZoomP_clicked() @@ -862,91 +862,91 @@ void OPMapGadgetWidget::createActions() reloadAct = new QAction(tr("&Reload map"), this); reloadAct->setShortcut(tr("F5")); reloadAct->setStatusTip(tr("Reload the map tiles")); - connect(reloadAct, SIGNAL(triggered()), this, SLOT(on_reloadAct_triggered())); + connect(reloadAct, SIGNAL(triggered()), this, SLOT(reloadAct_triggered())); findPlaceAct = new QAction(tr("&Find place"), this); findPlaceAct->setShortcut(tr("Ctrl+F")); findPlaceAct->setStatusTip(tr("Find a location")); - connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(on_findPlaceAct_triggered())); + connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(findPlaceAct_triggered())); showCompassAct = new QAction(tr("Show compass"), this); // showCompassAct->setShortcut(tr("Ctrl+M")); showCompassAct->setStatusTip(tr("Show/Hide the map compass")); showCompassAct->setCheckable(true); showCompassAct->setChecked(true); - connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(on_showCompassAct_toggled(bool))); + connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(showCompassAct_toggled(bool))); zoomInAct = new QAction(tr("Zoom &In"), this); zoomInAct->setShortcut(Qt::Key_PageUp); zoomInAct->setStatusTip(tr("Zoom the map in")); - connect(zoomInAct, SIGNAL(triggered()), this, SLOT(on_goZoomInAct_triggered())); + connect(zoomInAct, SIGNAL(triggered()), this, SLOT(goZoomInAct_triggered())); zoomOutAct = new QAction(tr("Zoom &Out"), this); zoomOutAct->setShortcut(Qt::Key_PageDown); zoomOutAct->setStatusTip(tr("Zoom the map out")); - connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(on_goZoomOutAct_triggered())); + connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(goZoomOutAct_triggered())); goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this); goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse")); - connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(on_goMouseClickAct_triggered())); + connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(goMouseClickAct_triggered())); goHomeAct = new QAction(tr("Go to &Home location"), this); goHomeAct->setShortcut(tr("Ctrl+H")); goHomeAct->setStatusTip(tr("Center the map onto the home location")); - connect(goHomeAct, SIGNAL(triggered()), this, SLOT(on_goHomeAct_triggered())); + connect(goHomeAct, SIGNAL(triggered()), this, SLOT(goHomeAct_triggered())); goUAVAct = new QAction(tr("Go to &UAV location"), this); goUAVAct->setShortcut(tr("Ctrl+U")); goUAVAct->setStatusTip(tr("Center the map onto the UAV location")); - connect(goUAVAct, SIGNAL(triggered()), this, SLOT(on_goUAVAct_triggered())); + connect(goUAVAct, SIGNAL(triggered()), this, SLOT(goUAVAct_triggered())); followUAVpositionAct = new QAction(tr("Follow UAV position"), this); followUAVpositionAct->setShortcut(tr("Ctrl+F")); followUAVpositionAct->setStatusTip(tr("Keep the map centered onto the UAV")); followUAVpositionAct->setCheckable(true); followUAVpositionAct->setChecked(false); - connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(on_followUAVpositionAct_toggled(bool))); + connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(followUAVpositionAct_toggled(bool))); followUAVheadingAct = new QAction(tr("Follow UAV heading"), this); followUAVheadingAct->setShortcut(tr("Ctrl+F")); followUAVheadingAct->setStatusTip(tr("Keep the map rotation to the UAV heading")); followUAVheadingAct->setCheckable(true); followUAVheadingAct->setChecked(true); - connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(on_followUAVheadingAct_toggled(bool))); + connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(followUAVheadingAct_toggled(bool))); wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); wayPointEditorAct->setShortcut(tr("Ctrl+W")); wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); - connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(on_openWayPointEditorAct_triggered())); + connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(openWayPointEditorAct_triggered())); addWayPointAct = new QAction(tr("&Add waypoint"), this); addWayPointAct->setShortcut(tr("Ctrl+A")); addWayPointAct->setStatusTip(tr("Add waypoint")); - connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(on_addWayPointAct_triggered())); + connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(addWayPointAct_triggered())); editWayPointAct = new QAction(tr("&Edit waypoint"), this); editWayPointAct->setShortcut(tr("Ctrl+E")); editWayPointAct->setStatusTip(tr("Edit waypoint")); - connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(on_editWayPointAct_triggered())); + connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(editWayPointAct_triggered())); lockWayPointAct = new QAction(tr("&Lock waypoint"), this); lockWayPointAct->setStatusTip(tr("Lock/Unlock a waypoint")); lockWayPointAct->setCheckable(true); lockWayPointAct->setChecked(false); - connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(on_lockWayPointAct_triggered())); + connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(lockWayPointAct_triggered())); deleteWayPointAct = new QAction(tr("&Delete waypoint"), this); deleteWayPointAct->setShortcut(tr("Ctrl+D")); deleteWayPointAct->setStatusTip(tr("Delete waypoint")); - connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(on_deleteWayPointAct_triggered())); + connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(deleteWayPointAct_triggered())); clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); clearWayPointsAct->setShortcut(tr("Ctrl+C")); clearWayPointsAct->setStatusTip(tr("Clear waypoints")); - connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(on_clearWayPointsAct_triggered())); + connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(clearWayPointsAct_triggered())); zoomActGroup = new QActionGroup(this); - connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(on_zoomActGroup_triggered(QAction *))); + connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(zoomActGroup_triggered(QAction *))); zoomAct.clear(); for (int i = 2; i <= 19; i++) { @@ -959,13 +959,13 @@ void OPMapGadgetWidget::createActions() // *********************** } -void OPMapGadgetWidget::on_reloadAct_triggered() +void OPMapGadgetWidget::reloadAct_triggered() { if (m_map) m_map->ReloadMap(); } -void OPMapGadgetWidget::on_findPlaceAct_triggered() +void OPMapGadgetWidget::findPlaceAct_triggered() { m_widget->comboBoxFindPlace->setFocus(); // move focus to the 'find place' text box @@ -989,25 +989,25 @@ void OPMapGadgetWidget::on_findPlaceAct_triggered() */ } -void OPMapGadgetWidget::on_showCompassAct_toggled(bool show_compass) +void OPMapGadgetWidget::showCompassAct_toggled(bool show_compass) { if (m_map) m_map->SetShowCompass(show_compass); } -void OPMapGadgetWidget::on_goZoomInAct_triggered() +void OPMapGadgetWidget::goZoomInAct_triggered() { if (m_map) setZoom(m_map->Zoom() + 1); } -void OPMapGadgetWidget::on_goZoomOutAct_triggered() +void OPMapGadgetWidget::goZoomOutAct_triggered() { if (m_map) setZoom(m_map->Zoom() - 1); } -void OPMapGadgetWidget::on_zoomActGroup_triggered(QAction *action) +void OPMapGadgetWidget::zoomActGroup_triggered(QAction *action) { if (!action) return; @@ -1017,18 +1017,18 @@ void OPMapGadgetWidget::on_zoomActGroup_triggered(QAction *action) setZoom(zoom); } -void OPMapGadgetWidget::on_goMouseClickAct_triggered() +void OPMapGadgetWidget::goMouseClickAct_triggered() { if (m_map) m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position } -void OPMapGadgetWidget::on_goHomeAct_triggered() +void OPMapGadgetWidget::goHomeAct_triggered() { followUAVpositionAct->setChecked(false); } -void OPMapGadgetWidget::on_goUAVAct_triggered() +void OPMapGadgetWidget::goUAVAct_triggered() { PositionActual::DataFields data = m_positionActual->getData(); // get current UAV data @@ -1040,7 +1040,7 @@ void OPMapGadgetWidget::on_goUAVAct_triggered() } } -void OPMapGadgetWidget::on_followUAVpositionAct_toggled(bool checked) +void OPMapGadgetWidget::followUAVpositionAct_toggled(bool checked) { if (m_widget) { @@ -1052,18 +1052,18 @@ void OPMapGadgetWidget::on_followUAVpositionAct_toggled(bool checked) } } -void OPMapGadgetWidget::on_followUAVheadingAct_toggled(bool checked) +void OPMapGadgetWidget::followUAVheadingAct_toggled(bool checked) { if (!checked && m_map) m_map->SetRotate(0); // reset the rotation to '0' } -void OPMapGadgetWidget::on_openWayPointEditorAct_triggered() +void OPMapGadgetWidget::openWayPointEditorAct_triggered() { waypoint_editor_dialog.show(); } -void OPMapGadgetWidget::on_addWayPointAct_triggered() +void OPMapGadgetWidget::addWayPointAct_triggered() { if (!m_map) return; @@ -1081,7 +1081,7 @@ void OPMapGadgetWidget::on_addWayPointAct_triggered() m_waypoint_list_mutex.unlock(); } -void OPMapGadgetWidget::on_editWayPointAct_triggered() +void OPMapGadgetWidget::editWayPointAct_triggered() { if (!m_mouse_waypoint) return; @@ -1092,7 +1092,7 @@ void OPMapGadgetWidget::on_editWayPointAct_triggered() m_mouse_waypoint = NULL; } -void OPMapGadgetWidget::on_lockWayPointAct_triggered() +void OPMapGadgetWidget::lockWayPointAct_triggered() { if (!m_mouse_waypoint) return; @@ -1102,7 +1102,7 @@ void OPMapGadgetWidget::on_lockWayPointAct_triggered() m_mouse_waypoint = NULL; } -void OPMapGadgetWidget::on_deleteWayPointAct_triggered() +void OPMapGadgetWidget::deleteWayPointAct_triggered() { if (!m_mouse_waypoint) return; @@ -1131,7 +1131,7 @@ void OPMapGadgetWidget::on_deleteWayPointAct_triggered() m_mouse_waypoint = NULL; } -void OPMapGadgetWidget::on_clearWayPointsAct_triggered() +void OPMapGadgetWidget::clearWayPointsAct_triggered() { m_waypoint_list_mutex.lock(); if (m_map) m_map->WPDeleteAll(); diff --git a/ground/src/plugins/opmap/opmapgadgetwidget.h b/ground/src/plugins/opmap/opmapgadgetwidget.h index 0cdb321df..62d08b5ae 100644 --- a/ground/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/src/plugins/opmap/opmapgadgetwidget.h @@ -109,7 +109,7 @@ private slots: * * @param */ - void on_comboBoxFindPlace_returnPressed(); + void comboBoxFindPlace_returnPressed(); void on_toolButtonFindPlace_clicked(); void on_toolButtonZoomM_clicked(); void on_toolButtonZoomP_clicked(); @@ -151,23 +151,23 @@ private slots: * * @param */ - void on_reloadAct_triggered(); - void on_findPlaceAct_triggered(); - void on_showCompassAct_toggled(bool show_compass); - void on_goZoomInAct_triggered(); - void on_goZoomOutAct_triggered(); - void on_goMouseClickAct_triggered(); - void on_goHomeAct_triggered(); - void on_goUAVAct_triggered(); - void on_followUAVpositionAct_toggled(bool checked); - void on_followUAVheadingAct_toggled(bool checked); - void on_openWayPointEditorAct_triggered(); - void on_addWayPointAct_triggered(); - void on_editWayPointAct_triggered(); - void on_lockWayPointAct_triggered(); - void on_deleteWayPointAct_triggered(); - void on_clearWayPointsAct_triggered(); - void on_zoomActGroup_triggered(QAction *action); + void reloadAct_triggered(); + void findPlaceAct_triggered(); + void showCompassAct_toggled(bool show_compass); + void goZoomInAct_triggered(); + void goZoomOutAct_triggered(); + void goMouseClickAct_triggered(); + void goHomeAct_triggered(); + void goUAVAct_triggered(); + void followUAVpositionAct_toggled(bool checked); + void followUAVheadingAct_toggled(bool checked); + void openWayPointEditorAct_triggered(); + void addWayPointAct_triggered(); + void editWayPointAct_triggered(); + void lockWayPointAct_triggered(); + void deleteWayPointAct_triggered(); + void clearWayPointsAct_triggered(); + void zoomActGroup_triggered(QAction *action); private: double m_heading; // uav heading