Skip to content
Snippets Groups Projects
Commit 2f306d9a authored by Boulongne Corentin's avatar Boulongne Corentin
Browse files

Updated gnssMarker class and fixed multiple point tracking

parent eb227a8a
No related branches found
No related tags found
No related merge requests found
...@@ -33,6 +33,7 @@ set(rqt_gps_map_view_HDRS ...@@ -33,6 +33,7 @@ set(rqt_gps_map_view_HDRS
set(rqt_gps_map_view_moc_HDRS set(rqt_gps_map_view_moc_HDRS
include/rqt_gps_map_view/rqt_gps_map_view_widget.h include/rqt_gps_map_view/rqt_gps_map_view_widget.h
include/rqt_gps_map_view/gnssMarker.h
) )
set(rqt_gps_map_view_UIS set(rqt_gps_map_view_UIS
...@@ -198,6 +199,9 @@ include_directories( ...@@ -198,6 +199,9 @@ include_directories(
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
#set_target_properties(${PROJECT_NAME} PROPERTIES AUTOMOC TRUE)
## Add cmake target dependencies of the executable ## Add cmake target dependencies of the executable
## same as for the library above ## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
......
This diff is collapsed.
/*
Created on 04 April 2022
Author : Boulongne Corentin
Brief : class to subscribe to ROS GPS data and track markers with QML.
LICENCE : to define
*/
#ifndef GNSSMARKER_H #ifndef GNSSMARKER_H
#define GNSSMARKER_H #define GNSSMARKER_H
...@@ -6,34 +18,42 @@ ...@@ -6,34 +18,42 @@
#include <std_msgs/String.h> #include <std_msgs/String.h>
#include <ros/master.h> #include <ros/master.h>
#include <string> #include <string>
#include <boost/bind.hpp>
#include <qt5/QtCore/QList> #include <qt5/QtCore/QList>
#include <qt5/QtCore/QTimer> #include <qt5/QtCore/QTimer>
#include <QQuickItem>
#include <QString>
class gnssMarker class GnssMarker: public QObject
{ {
Q_OBJECT
public: public:
gnssMarker(); GnssMarker();
GnssMarker(std::string topicToSub);
void subScribeTo(std::string topicName); void subScribeTo(std::string topicName);
void getData(const sensor_msgs::NavSatFix& data); void getData(const sensor_msgs::NavSatFix& data);
void addTimerToList(); QString getName();
void sendObjects(QQuickItem* itm, QString markerName_);
double getLongitude(); double getLongitude();
double getLatitude(); double getLatitude();
~GnssMarker();
QTimer* getAvailableTimer(); public slots:
~gnssMarker(); void track();
private: private:
ros::NodeHandle nh_; ros::NodeHandle nh_;
ros::Subscriber subNavSatFix; ros::Subscriber subNavSatFix;
QQuickItem* item;
private slots: QString marker_name;
QTimer * timer;
void track();
...@@ -41,7 +61,6 @@ protected: ...@@ -41,7 +61,6 @@ protected:
double longitude; double longitude;
double latitude; double latitude;
QList<QTimer*> timerList;
}; };
......
/*
Created on 04 April 2022
Author : Boulongne Corentin
Brief : User Interface to display GPS sources on a map and track them.
LICENCE : to define
*/
#ifndef RQT_GPS_MAP_VIEW_WIDGET #ifndef RQT_GPS_MAP_VIEW_WIDGET
#define RQT_GPS_MAP_VIEW_WIDGET #define RQT_GPS_MAP_VIEW_WIDGET
...@@ -30,17 +42,15 @@ public: ...@@ -30,17 +42,15 @@ public:
~GpsMapViewWidget(); ~GpsMapViewWidget();
public slots: public slots:
void aller();
void poseublx();
void updateTopicList(); void updateTopicList();
void afficherPosition(QString latitude, QString longitude); void afficherPosition(QString latitude, QString longitude);
void afficherInformations(QString adresse, QString coordonnee); void afficherInformations(QString adresse, QString coordonnee);
void getNovatelData(const sensor_msgs::NavSatFix& novateldata);
void getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix>& event); void getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix>& event);
void getUbloxData(const sensor_msgs::NavSatFix& ubloxdata);
private slots: private slots:
void on_refreshButton_clicked(); void on_refreshButton_clicked();
...@@ -51,25 +61,16 @@ private slots: ...@@ -51,25 +61,16 @@ private slots:
void on_pushButton_2_clicked(); void on_pushButton_2_clicked();
void trackMarker();
private: private:
Ui::GpsMapViewWidget *ui; Ui::GpsMapViewWidget *ui;
gnssMarker * gnssMarkerObj; QList<GnssMarker *> gnssMarkerList;
QTimer *gpsDataTimer;
QVector<QCheckBox*> checkBoxes; QVector<QCheckBox*> checkBoxes;
QList<QTimer*> timerList;
ros::NodeHandle nh;
ros::Subscriber subNovatelData; int mID = -1;
ros::Subscriber subUbloxData;
ros::Subscriber subInfoData;
ros::Subscriber testSub;
int mID;
QString markerName_ = ""; QString markerName_ = "";
double longi = 0.0; double longi = 0.0;
...@@ -78,8 +79,6 @@ private: ...@@ -78,8 +79,6 @@ private:
double ulongi = 0.0; double ulongi = 0.0;
double ulati = 0.0; double ulati = 0.0;
}; };
#endif // RQT_GPS_MAP_VIEW_WIDGET #endif // RQT_GPS_MAP_VIEW_WIDGET
...@@ -10,13 +10,13 @@ Item { ...@@ -10,13 +10,13 @@ Item {
ListModel{ ListModel{
id: locationModel id: locationModel
objectName: "locationList" objectName: "locationList"
ListElement {mID: 0; Mname: "marker0"; lat: 36.688089; lon: 3.034564; color: "orange"; radius:600} //ListElement {mID: 0; Mname: "marker0"; lat: 36.688089; lon: 3.034564; color: "orange"; radius:600}
ListElement {mID: 1; Mname: "marker1"; lat: 36.692111; lon: 3.028278; color: "green"; radius:400} /*ListElement {mID: 1; Mname: "marker1"; lat: 36.692111; lon: 3.028278; color: "green"; radius:400}
ListElement {mID: 2; Mname: "marker2"; lat: 36.693239; lon: 3.029731; color: "orange"; radius:500} ListElement {mID: 2; Mname: "marker2"; lat: 36.693239; lon: 3.029731; color: "orange"; radius:500}
ListElement {mID: 3; Mname: "marker3"; lat: 36.693444; lon: 3.029972; color: "red"; radius:300} ListElement {mID: 3; Mname: "marker3"; lat: 36.693444; lon: 3.029972; color: "red"; radius:300}
ListElement {mID: 4; Mname: "marker4"; lat: 36.693472; lon: 3.042250; color: "green"; radius:200} ListElement {mID: 4; Mname: "marker4"; lat: 36.693472; lon: 3.042250; color: "green"; radius:200}
ListElement {mID: 5; Mname: "marker5"; lat: 36.691561; lon: 3.043039; color: "orange"; radius:450} ListElement {mID: 5; Mname: "marker5"; lat: 36.691561; lon: 3.043039; color: "orange"; radius:450}
ListElement {mID: 6; Mname: "marker6"; lat: 36.691250; lon: 3.042861; color: "red"; radius:200} ListElement {mID: 6; Mname: "marker6"; lat: 36.691250; lon: 3.042861; color: "red"; radius:200}*/
function addMarker(markerID, markerName, lati, longi) function addMarker(markerID, markerName, lati, longi)
{ {
...@@ -50,7 +50,7 @@ Item { ...@@ -50,7 +50,7 @@ Item {
minimumZoomLevel: 5 minimumZoomLevel: 5
zoomLevel: 15 zoomLevel: 15
gesture.enabled: true gesture.enabled: true
MapQuickItem /*MapQuickItem
{ {
id: indicateurPosition id: indicateurPosition
objectName: "indicateurPosition" objectName: "indicateurPosition"
...@@ -65,7 +65,7 @@ Item { ...@@ -65,7 +65,7 @@ Item {
map.addMapItem(indicateurPosition); map.addMapItem(indicateurPosition);
map.update(); map.update();
} }
} }*/
/*MapQuickItem /*MapQuickItem
{ {
......
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject> <!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 4.11.0, 2022-05-03T10:31:32. --> <!-- Written by QtCreator 4.11.0, 2022-05-05T17:23:21. -->
<qtcreator> <qtcreator>
<data> <data>
<variable>EnvironmentId</variable> <variable>EnvironmentId</variable>
......
/*
Created on 04 April 2022
Author : Boulongne Corentin
Brief : class to subscribe to ROS GPS data and track markers with QML.
LICENCE : to define
*/
#include "gnssMarker.h" #include "gnssMarker.h"
#include <iostream> #include <iostream>
gnssMarker::gnssMarker() GnssMarker::GnssMarker()
{
}
GnssMarker::GnssMarker(std::string topicToSub)
{ {
// ros::init(argc, argv, "GNSS-MARKER Node"); // ros::init(argc, argv, "GNSS-MARKER Node");
//subNavSatFix = nh_.subscribe("/ublox/fix", 100, &gnssMarker::getData, this); this->timer = new QTimer();
QTimer * timer = new QTimer(); timer->setInterval(20);
QTimer * timer2 = new QTimer(); // Timers ajoutés en durs pour TEST. timer->start();
subNavSatFix = nh_.subscribe(topicToSub, 100, &GnssMarker::getData, this);
ROS_INFO(" %s", topicToSub.c_str());
timerList << timer << timer2;
//ros::spin(); //ros::spin();
} }
void gnssMarker::subScribeTo(std::string topicName)
void GnssMarker::subScribeTo(std::string topicName)
{ {
subNavSatFix = nh_.subscribe(topicName, 100, &gnssMarker::getData, this); subNavSatFix = nh_.subscribe(topicName, 100, &GnssMarker::getData, this);
ROS_INFO(" %s", topicName.c_str()); ROS_INFO(" %s", topicName.c_str());
} }
void gnssMarker::getData(const sensor_msgs::NavSatFix& data) void GnssMarker::getData(const sensor_msgs::NavSatFix& data)
{ {
longitude = data.longitude; longitude = data.longitude;
latitude = data.latitude; latitude = data.latitude;
std::cout << data.header.frame_id << std::endl << data.longitude << std::endl << data.latitude << std::endl; // std::cout << data.header.frame_id << std::endl << data.longitude << std::endl << data.latitude << std::endl;
} }
double gnssMarker::getLatitude() double GnssMarker::getLatitude()
{ {
return latitude; return latitude;
} }
double gnssMarker::getLongitude() double GnssMarker::getLongitude()
{ {
return longitude; return longitude;
} }
QString GnssMarker::getName()
void gnssMarker::addTimerToList()
{ {
return marker_name;
}
QTimer * timer = new QTimer(); void GnssMarker::sendObjects(QQuickItem* itm, QString markerNames)
{
item = itm;
timerList << timer; marker_name = markerNames;
QTimer::connect(timer, SIGNAL(timeout()), this, SLOT(track()));
} }
QTimer* gnssMarker::getAvailableTimer()
void GnssMarker::track()
{ {
QObject *obj = item->findChild<QObject *>("locationList");
for(int i = 0; i < sizeof(timerList); i++) QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
{ auto test_2 = mapItem.at(0);
if(timerList.at(i)->isActive() == false) auto mapItemChild = test_2->childItems();
{
timerList.at(i)->setInterval(20);
timerList.at(i)->start();
return timerList.at(i);
}
int nb_markers = mapItemChild.count(); //return nb of markers
QStringList listOfMarkers;
for(int j = 0; j < nb_markers; j++)
{
listOfMarkers << mapItemChild.at(j)->objectName();
} }
int idx = listOfMarkers.indexOf(marker_name);
auto marker_id = mapItemChild.at(idx); // throw error if index is out of range -> app crash.
QVariant latitude_ = latitude;
QVariant longitude_ = longitude;
/* if(timerList.at(index)->isActive() == false){ if(marker_id != nullptr)
{
timerList.at(index)->setInterval(20); QMetaObject::invokeMethod(marker_id, "track", Q_ARG(QVariant, latitude_), Q_ARG(QVariant, longitude_));
timerList.at(index)->start(); // std::cout << "track function called!" << std::endl;
return timerList.at(index); }
}else{ }
return timerList.at(index+1); GnssMarker::~GnssMarker()
{
}*/ QTimer::disconnect(timer, SIGNAL(timeout()), this, SLOT(track()));
delete timer;
} }
\ No newline at end of file
// License
// Date
// Author
// Description
#include <rqt_gps_map_view/rqt_gps_map_view.h> #include <rqt_gps_map_view/rqt_gps_map_view.h>
#include <pluginlib/class_list_macros.h> #include <pluginlib/class_list_macros.h>
...@@ -6,6 +12,7 @@ ...@@ -6,6 +12,7 @@
namespace rqt_gps_map_view { namespace rqt_gps_map_view {
// constructor
GpsMapView::GpsMapView() : GpsMapView::GpsMapView() :
rqt_gui_cpp::Plugin() rqt_gui_cpp::Plugin()
{ {
......
/*
Created on 04 April 2022
Author : Boulongne Corentin
Brief : User Interface to display GPS sources on a map and track them.
LICENCE : to define
*/
#include <rqt_gps_map_view/rqt_gps_map_view_widget.h> #include <rqt_gps_map_view/rqt_gps_map_view_widget.h>
#include "ui_rqt_gps_map_view_widget.h" #include "ui_rqt_gps_map_view_widget.h"
...@@ -12,22 +24,14 @@ ...@@ -12,22 +24,14 @@
#include <QVector> #include <QVector>
GpsMapViewWidget::GpsMapViewWidget(QWidget *parent) : GpsMapViewWidget::GpsMapViewWidget(QWidget *parent) :
QWidget(parent), QWidget(parent),
ui(new Ui::GpsMapViewWidget) ui(new Ui::GpsMapViewWidget)
{ {
ui->setupUi(this); ui->setupUi(this);
this->gpsDataTimer = new QTimer(this);
gpsDataTimer->setInterval(20);
connect(ui->boutonAller, SIGNAL(clicked(bool)), this, SLOT(aller()));
QTimer::connect(gpsDataTimer, SIGNAL(timeout()), this, SLOT(aller()));
//QTimer::connect(gpsDataTimer, SIGNAL(timeout()), this, SLOT(poseublx()));
this->gnssMarkerObj = new gnssMarker();
gpsDataTimer->start();
QQuickItem *item = ui->quickWidget->rootObject(); QQuickItem *item = ui->quickWidget->rootObject();
QObject *objectMouseArea = item->findChild<QObject *>("mouseArea"); QObject *objectMouseArea = item->findChild<QObject *>("mouseArea");
...@@ -46,14 +50,21 @@ GpsMapViewWidget::GpsMapViewWidget(QWidget *parent) : ...@@ -46,14 +50,21 @@ GpsMapViewWidget::GpsMapViewWidget(QWidget *parent) :
updateTopicList(); updateTopicList();
subNovatelData = nh.subscribe("/gps/fix", 100, &GpsMapViewWidget::getNovatelData, this);
subInfoData = nh.subscribe("/gps/fix", 100, &GpsMapViewWidget::getInfo, this);
// subUbloxData = nh.subscribe("/ublox/fix", 100, &GpsMapViewWidget::getUbloxData, this); // topic a changer.
} }
GpsMapViewWidget::~GpsMapViewWidget() GpsMapViewWidget::~GpsMapViewWidget()
{ {
foreach(QCheckBox* cb, checkBoxes)
{
cb->setChecked(false);
}
for (int idx = 0 ; idx < gnssMarkerList.count(); ++idx)
{
delete gnssMarkerList.at(idx);
gnssMarkerList.removeAt(idx);
}
delete ui; delete ui;
} }
...@@ -88,7 +99,7 @@ void GpsMapViewWidget::updateTopicList() ...@@ -88,7 +99,7 @@ void GpsMapViewWidget::updateTopicList()
} }
QVBoxLayout *vbox = new QVBoxLayout; QVBoxLayout *vbox = new QVBoxLayout(this);
foreach(QString filt, topicsNames){ foreach(QString filt, topicsNames){
QCheckBox *checkbox = new QCheckBox(filt, this); QCheckBox *checkbox = new QCheckBox(filt, this);
...@@ -96,46 +107,45 @@ void GpsMapViewWidget::updateTopicList() ...@@ -96,46 +107,45 @@ void GpsMapViewWidget::updateTopicList()
checkbox->setChecked(false); checkbox->setChecked(false);
vbox->addWidget(checkbox); vbox->addWidget(checkbox);
connect(checkbox, &QCheckBox::stateChanged, this, &GpsMapViewWidget::on_checkBoxClicked); connect(checkbox, &QCheckBox::stateChanged, this, &GpsMapViewWidget::on_checkBoxClicked);
}
}
ui->dataSourcesGB->setLayout(vbox); ui->dataSourcesGB->setLayout(vbox);
} }
// slot
void GpsMapViewWidget::on_checkBoxClicked(int state) void GpsMapViewWidget::on_checkBoxClicked(int state)
{ {
auto cb = qobject_cast<QCheckBox*>(sender()); auto cb = qobject_cast<QCheckBox*>(sender());
QQuickItem *item = ui->quickWidget->rootObject(); QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList"); QObject *obj = item->findChild<QObject *>("locationList");
QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView"); /*QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
auto test_2 = mapItem.at(0); auto test_2 = mapItem.at(0);
auto mapItemChild = test_2->childItems(); // list of markers 0 to N -> name is markerX / X is the id auto mapItemChild = test_2->childItems(); // list of markers 0 to N -> name is markerX / X is the id
*/
int nb_markers = mapItemChild.count(); //return nb of markers // int nb_markers = mapItemChild.count(); //return nb of markers
QStringList list; QStringList list;
for(int j = 0; j < nb_markers; j++) for(int j = 0; j < gnssMarkerList.count(); j++)
{ {
list << mapItemChild.at(j)->objectName(); // list << mapItemChild.at(j)->objectName();
list << gnssMarkerList.at(j)->getName();
} }
if(state == 2) // -> checkbox is checked if(state == 2) // -> checkbox is checked
{ {
QString chboxName = cb->text(); QString chboxName = cb->text();
gnssMarkerObj->subScribeTo(chboxName.toStdString()); int mID = gnssMarkerList.count();
gnssMarkerList << new GnssMarker(chboxName.toStdString());
chboxName.replace(QString("/"), QString("_")); chboxName.replace(QString("/"), QString("_"));
...@@ -143,148 +153,38 @@ void GpsMapViewWidget::on_checkBoxClicked(int state) ...@@ -143,148 +153,38 @@ void GpsMapViewWidget::on_checkBoxClicked(int state)
QVariant longitude = ulongi; QVariant longitude = ulongi;
QVariant markerName = chboxName; QVariant markerName = chboxName;
mID = (nb_markers-1)+1; // id qui s'incremente
markerName_ = "marker"+chboxName; markerName_ = "marker"+chboxName;
//std::cout << markerName_.toStdString() << std::endl; //std::cout << markerName_.toStdString() << std::endl;
QMetaObject::invokeMethod(obj, "addMarker", Q_ARG(QVariant, mID), Q_ARG(QVariant, markerName), Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude)); QMetaObject::invokeMethod(obj, "addMarker", Q_ARG(QVariant, mID), Q_ARG(QVariant, markerName), Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude));
gnssMarkerList.at(mID)->sendObjects(item, markerName_);
// QTimer::connect(gpsDataTimer, SIGNAL(timeout()), this, SLOT(trackMarker() )) ;
QTimer::connect(gnssMarkerObj->getAvailableTimer(), SIGNAL(timeout()), this, SLOT(trackMarker() )) ;
// std::cout << "this checkbox (" << cb->text().toStdString() << ") checked." << std::endl; // std::cout << "this checkbox (" << cb->text().toStdString() << ") checked." << std::endl;
} }
else if(state != 2) else if(state != 2)
{ {
// std::cout << "marker" << mID << std::endl; // probleme, prend le dernier id créé au dessus
QString chboxName = cb->text(); QString chboxName = cb->text();
chboxName.replace(QString("/"), QString("_")); chboxName.replace(QString("/"), QString("_"));
int idx = list.indexOf("marker"+chboxName); int idx = list.indexOf("marker"+chboxName);
printf("index %d\n", idx);
QVariant indexToRemove = idx;
QVariant indexToRemove = idx; // change this -> find marker QMetaObject::invokeMethod(obj, "removeMarker", Q_ARG(QVariant, indexToRemove)); // removing correstponding marker with the topic name
delete gnssMarkerList.at(idx);
QMetaObject::invokeMethod(obj, "removeMarker", Q_ARG(QVariant, indexToRemove)); // will remove last marker gnssMarkerList.removeAt(idx);
// QTimer::disconnect(gpsDataTimer, nullptr, this , SLOT(trackMarker()) ); // disconnect timer to avoid crash due to out of index bounds
std::cout << "this checkbox (" << cb->text().toStdString() << ") unchecked." << std::endl; std::cout << "this checkbox (" << cb->text().toStdString() << ") unchecked." << std::endl;
}
//std::cout << "checkbox " << cb->text().toStdString() << " state is : " << state << std::endl;
}
void GpsMapViewWidget::aller()
{
QQuickItem *item = ui->quickWidget->rootObject();
QObject *object = item->findChild<QObject *>("indicateurPosition");
QVariant latitude = QString::number(lati);
QVariant longitude = QString::number(longi);
if(object != nullptr)
{
QMetaObject::invokeMethod(object, "aller", Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude));
}
GpsMapViewWidget::afficherPosition(QString::number(lati), QString::number(longi));
}
void GpsMapViewWidget::trackMarker()
{
QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList");
QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
auto test_2 = mapItem.at(0);
auto mapItemChild = test_2->childItems();
int nb_markers = mapItemChild.count(); //return nb of markers
QStringList listOfMarkers;
for(int j = 0; j < nb_markers; j++)
{
listOfMarkers << mapItemChild.at(j)->objectName();
}
int idx = listOfMarkers.indexOf(markerName_);
auto marker_id = mapItemChild.at(idx); // throw error if index is out of range -> app crash.
QVariant latitude = gnssMarkerObj->getLatitude();//QString::number(ulati);
QVariant longitude = gnssMarkerObj->getLongitude();//QString::number(ulongi);
if(marker_id != nullptr)
{
QMetaObject::invokeMethod(marker_id, "track", Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude));
// std::cout << "track function called!" << std::endl;
}
GpsMapViewWidget::afficherPosition(QString::number(lati), QString::number(longi));
} }
// function to delete -> replaced by trackMarker //std::cout << "checkbox " << cb->text().toStdString() << " state is : " << state << std::endl;
void GpsMapViewWidget::poseublx()
{
QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList");
QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
auto test_2 = mapItem.at(0);
auto mapItemChild = test_2->childItems();
auto marker_id = mapItemChild.at(7); // throw error if index is out of range -> app crash.
QVariant latitude = QString::number(ulati);
QVariant longitude = QString::number(ulongi);
if(marker_id != nullptr)
{
QMetaObject::invokeMethod(marker_id, "track", Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude));
// std::cout << "track function called!" << std::endl;
}
GpsMapViewWidget::afficherPosition(QString::number(lati), QString::number(longi));
} }
...@@ -293,8 +193,8 @@ void GpsMapViewWidget::afficherPosition(QString latitude, QString longitude) ...@@ -293,8 +193,8 @@ void GpsMapViewWidget::afficherPosition(QString latitude, QString longitude)
ui->positionLatitude->setText(QString::fromUtf8("%1").arg(latitude.toDouble(), 0, 'f', 5)); ui->positionLatitude->setText(QString::fromUtf8("%1").arg(latitude.toDouble(), 0, 'f', 5));
ui->positionLongitude->setText(QString::fromUtf8("%1").arg(longitude.toDouble(), 0, 'f', 5)); ui->positionLongitude->setText(QString::fromUtf8("%1").arg(longitude.toDouble(), 0, 'f', 5));
ui->editLatitude->setText(QString::fromUtf8("%1").arg(latitude.toDouble(), 0, 'f', 5)); //ui->editLatitude->setText(QString::fromUtf8("%1").arg(latitude.toDouble(), 0, 'f', 5));
ui->editLongitude->setText(QString::fromUtf8("%1").arg(longitude.toDouble(), 0, 'f', 5)); //ui->editLongitude->setText(QString::fromUtf8("%1").arg(longitude.toDouble(), 0, 'f', 5));
} }
void GpsMapViewWidget::afficherInformations(QString adresse, QString coordonnee) void GpsMapViewWidget::afficherInformations(QString adresse, QString coordonnee)
...@@ -302,13 +202,6 @@ void GpsMapViewWidget::afficherInformations(QString adresse, QString coordonnee) ...@@ -302,13 +202,6 @@ void GpsMapViewWidget::afficherInformations(QString adresse, QString coordonnee)
ui->labelInformations->setText("Informations : " + adresse); ui->labelInformations->setText("Informations : " + adresse);
} }
void GpsMapViewWidget::getNovatelData(const sensor_msgs::NavSatFix& novateldata)
{
longi = novateldata.longitude;
lati = novateldata.latitude;
}
void GpsMapViewWidget::getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix> &event) void GpsMapViewWidget::getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix> &event)
{ {
...@@ -322,108 +215,7 @@ void GpsMapViewWidget::getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix> & ...@@ -322,108 +215,7 @@ void GpsMapViewWidget::getInfo(const ros::MessageEvent<sensor_msgs::NavSatFix> &
} }
void GpsMapViewWidget::getUbloxData(const sensor_msgs::NavSatFix& ubloxdata)
{
ulongi = ubloxdata.longitude;
ulati = ubloxdata.latitude;
}
void GpsMapViewWidget::on_refreshButton_clicked() void GpsMapViewWidget::on_refreshButton_clicked()
{ {
updateTopicList(); updateTopicList();
} }
/*void GpsMapViewWidget::on_listWidget_itemDoubleClicked(QListWidgetItem *item)
{
QMessageBox msgBox;
msgBox.setWindowTitle("Adding a GPS source");
msgBox.setText("Do you want to add this GPS source to the map ?");
msgBox.setInformativeText(item->text());
QPushButton *connectButton = msgBox.addButton(tr("Yes"), QMessageBox::ActionRole);
QPushButton *abortButton = msgBox.addButton(tr("No"), QMessageBox::ActionRole);
msgBox.exec();
if (msgBox.clickedButton() == connectButton)
{
//ui->label->setText("Yes clicked!");
QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList");
QVariant latitude = ulati;
QVariant longitude = ulongi;
QVariant markerName = "marker";
QVariant mID = ui->doubleSpinBox_2->value();
QMetaObject::invokeMethod(obj, "addMarker", Q_ARG(QVariant, mID), Q_ARG(QVariant, markerName), Q_ARG(QVariant, latitude), Q_ARG(QVariant, longitude));
}
else if (msgBox.clickedButton() == abortButton)
{
//ui->label->setText("No clicked!");
}
}*/
void GpsMapViewWidget::on_pushButton_clicked()
{
QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList");
QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
auto test_2 = mapItem.at(0);
auto mapItemChild = test_2->childItems(); // list of markers 0 to N -> name is markerX / X is the id
auto nb_markers = mapItemChild.count(); //return nb of markers
auto marker_id = mapItemChild.at(1);
if(marker_id != nullptr)
{
QMetaObject::invokeMethod(marker_id, "track", Q_ARG(QVariant, ui->doubleSpinBox->value()), Q_ARG(QVariant, ui->doubleSpinBox_2->value()));
std::cout << "track function called!" << std::endl;
}
std::cout << "[DEBUG] Marker object address : " << marker_id << " object name : " << marker_id->objectName().toStdString() << std::endl;
}
void GpsMapViewWidget::on_pushButton_2_clicked()
{
QQuickItem *item = ui->quickWidget->rootObject();
QObject *obj = item->findChild<QObject *>("locationList");
QList<QQuickItem*> mapItem = item->findChildren<QQuickItem*>("mapItemView");
auto test_2 = mapItem.at(0);
auto mapItemChild = test_2->childItems(); // list of markers 0 to N -> name is markerX / X is the id
int nb_markers = mapItemChild.count(); //return nb of markers
QStringList list;
for(int j = 0; j < nb_markers; j++)
{
list << mapItemChild.at(j)->objectName();
}
//list.indexOf("marker"+ui->doubleSpinBox->value());
int idx = list.indexOf("marker"+QString::number(ui->doubleSpinBox->value()));
QVariant indexToRemove = idx; // change this -> find marker
QMetaObject::invokeMethod(obj, "removeMarker", Q_ARG(QVariant, indexToRemove)); // will remove last marker
QTimer::disconnect(gpsDataTimer, nullptr, this ,SLOT(poseublx())); // disconnect timer to avoid crash due to out of index bounds
}
...@@ -52,59 +52,6 @@ ...@@ -52,59 +52,6 @@
<property name="spacing"> <property name="spacing">
<number>4</number> <number>4</number>
</property> </property>
<item>
<widget class="QLabel" name="labelLatitude">
<property name="text">
<string>Latitude :</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="editLatitude"/>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="labelLongitude">
<property name="text">
<string>Longitude :</string>
</property>
</widget>
</item>
<item>
<widget class="QLineEdit" name="editLongitude"/>
</item>
<item>
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="boutonAller">
<property name="text">
<string>Aller !</string>
</property>
</widget>
</item>
</layout> </layout>
</item> </item>
<item> <item>
...@@ -243,52 +190,6 @@ ...@@ -243,52 +190,6 @@
<bool>true</bool> <bool>true</bool>
</property> </property>
</widget> </widget>
<widget class="QDoubleSpinBox" name="doubleSpinBox">
<property name="geometry">
<rect>
<x>1420</x>
<y>950</y>
<width>69</width>
<height>27</height>
</rect>
</property>
</widget>
<widget class="QDoubleSpinBox" name="doubleSpinBox_2">
<property name="geometry">
<rect>
<x>1420</x>
<y>1000</y>
<width>69</width>
<height>27</height>
</rect>
</property>
</widget>
<widget class="QPushButton" name="pushButton">
<property name="geometry">
<rect>
<x>1520</x>
<y>1030</y>
<width>99</width>
<height>27</height>
</rect>
</property>
<property name="text">
<string>find objects</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_2">
<property name="geometry">
<rect>
<x>1520</x>
<y>990</y>
<width>99</width>
<height>27</height>
</rect>
</property>
<property name="text">
<string>remove point</string>
</property>
</widget>
</widget> </widget>
<layoutdefault spacing="6" margin="11"/> <layoutdefault spacing="6" margin="11"/>
<customwidgets> <customwidgets>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment