Commit f22025af authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'experimental' of git://github.com/tecnosapiens/qgroundcontrol into experimental

parents 414a947c f8a90520
......@@ -140,7 +140,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsVideoCamControl.ui
src/ui/SlugsVideoCamControl.ui \
src/ui/SlugsPadCameraControl.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -243,7 +244,8 @@ HEADERS += src/MG.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -326,7 +328,8 @@ SOURCES += src/main.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp
RESOURCES = mavground.qrc
......
......@@ -153,6 +153,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
current_partner_compid = 0;
protocol_timer.stop();
emit readGlobalWPFromUAS(false);
emit updateStatusString("done.");
qDebug() << "got all waypoints from ID " << systemId;
......@@ -294,6 +295,7 @@ void UASWaypointManager::localAddWaypoint(Waypoint *wp)
{
wp->setId(waypoints.size());
waypoints.insert(waypoints.size(), wp);
emit waypointListChanged();
}
}
......@@ -417,6 +419,7 @@ void UASWaypointManager::clearWaypointList()
void UASWaypointManager::readWaypoints()
{
emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE)
{
while(waypoints.size()>0)
......@@ -424,6 +427,7 @@ void UASWaypointManager::readWaypoints()
Waypoint *t = waypoints.back();
delete t;
waypoints.pop_back();
}
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
......@@ -435,6 +439,7 @@ void UASWaypointManager::readWaypoints()
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointRequestList();
}
}
......@@ -569,6 +574,8 @@ void UASWaypointManager::sendWaypointRequestList()
MG::SLEEP::usleep(PROTOCOL_DELAY_MS * 1000);
qDebug() << "sent waypoint list request to ID " << wprl.target_system;
}
void UASWaypointManager::sendWaypointRequest(quint16 seq)
......
......@@ -122,6 +122,7 @@ signals:
void updateStatusString(const QString &); ///< emits the current status string
void loadWPFile(); ///< emits signal that a file wp has been load
void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
private:
UAS &uas; ///< Reference to the corresponding UAS
......
......@@ -225,6 +225,9 @@ void MainWindow::connectWidgets()
connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
// it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView
connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
connect(slugsCamControlWidget->widget(),SIGNAL(viewCamBorderAtMap(bool)),mapWidget,SLOT(drawBorderCamAtMap(bool)));
connect(slugsCamControlWidget->widget(),SIGNAL(changeCamPosition(double,double,QString)),mapWidget,SLOT(updateCameraPosition(double,double, QString)));
}
if (slugsHilSimWidget && slugsHilSimWidget->widget()){
......@@ -570,7 +573,8 @@ void MainWindow::UASCreated(UASInterface* uas)
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2) {
dataWidget->addUAS(uas);
loadSlugsView();
//loadSlugsView();
loadGlobalOperatorView();
}
}
}
......
......@@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <QComboBox>
#include <QGridLayout>
#include "MapWidget.h"
#include "ui_MapWidget.h"
#include "UASInterface.h"
......@@ -42,6 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "MG.h"
MapWidget::MapWidget(QWidget *parent) :
QWidget(parent),
zoomLevel(0),
......@@ -84,6 +86,8 @@ MapWidget::MapWidget(QWidget *parent) :
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
//
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
......@@ -218,6 +222,19 @@ MapWidget::MapWidget(QWidget *parent) :
path = new qmapcontrol::LineString (wps, "UAV Path", pointPen);
mc->layer("Waypoints")->addGeometry(path);
//Camera Control
// CAMERA INDICATOR LAYER
// create a layer with the mapadapter and type GeometryLayer (for camera indicator)
camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter);
mc->addLayer(camLayer);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
drawCamBorder = false;
radioCamera = 10;
this->setVisible(false);
}
......@@ -393,6 +410,7 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
......@@ -414,8 +432,9 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
qDebug()<<"Funcion createWaypointGraphAtMap WP= "<<str<<" -> x= "<<tempPoint->latitude()<<" y= "<<tempPoint->longitude();
// Refresh the screen
// Refresh the screen
mc->updateRequestNew();
//// // emit signal mouse was clicked
......@@ -602,6 +621,10 @@ void MapWidget::wheelEvent(QWheelEvent *event)
// Detail zoom level is the number of steps zoomed in further
// after the bounding has taken effect
detailZoom = qAbs(qMin(0, mc->currentZoom()-newZoom));
// visual field of camera
updateCameraPosition(20*newZoom,0,"no");
}
void MapWidget::keyPressEvent(QKeyEvent *event)
......@@ -691,3 +714,68 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa
}
void MapWidget::updateCameraPosition(double radio, double bearing, QString dir)
{
//camPoints.clear();
QPointF currentPos = mc->currentCoordinate();
// QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance);
// qmapcontrol::Point* tempPoint1 = new qmapcontrol::Point(currentPos.x(), currentPos.y(),"inicial",qmapcontrol::Point::Middle);
// qmapcontrol::Point* tempPoint2 = new qmapcontrol::Point(actualPos.x(), actualPos.y(),"final",qmapcontrol::Point::Middle);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camLine->setPoints(camPoints);
QPen* camBorderPen = new QPen(QColor(255,0,0));
camBorderPen->setWidth(2);
//radio = mc->currentZoom()
if(drawCamBorder)
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
//create a camera borders
qmapcontrol::CirclePoint* camBorder = new qmapcontrol::CirclePoint(currentPos.x(), currentPos.y(), radio, "camBorder", qmapcontrol::Point::Middle, camBorderPen);
//camBorder->setCoordinate(currentPos);
mc->layer("Camera")->addGeometry(camBorder);
// mc->layer("Camera")->addGeometry(camLine);
mc->updateRequestNew();
}
else
{
//clear camera borders
mc->layer("Camera")->clearGeometries();
mc->updateRequestNew();
}
}
void MapWidget::drawBorderCamAtMap(bool status)
{
drawCamBorder = status;
updateCameraPosition(20,0,"no");
}
QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double bearing, double distance)
{
QPointF temp;
double rad = M_PI/180;
bearing = bearing*rad;
temp.setX((lon1 + ((distance/60) * (sin(bearing)))));
temp.setY((lat1 + ((distance/60) * (cos(bearing)))));
return temp;
}
......@@ -37,6 +37,11 @@ This file is part of the QGROUNDCONTROL project
#include <QMap>
#include "qmapcontrol.h"
#include "UASInterface.h"
#include "QPointF"
#include <qmath.h>
class QMenu;
......@@ -63,10 +68,13 @@ public slots:
void activeUASSet(UASInterface* uas);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
void updateCameraPosition(double distance, double bearing, QString dir);
QPointF getPointxBearing_Range(double lat1, double lon1, double bearing, double distance);
//ROCA
void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
void drawBorderCamAtMap(bool status);
protected:
void changeEvent(QEvent* e);
......@@ -93,6 +101,10 @@ protected:
qmapcontrol::Layer* l; ///< Current map layer (background)
qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
//only for experiment
qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
int zoomLevel;
int detailZoom; ///< Steps zoomed in further than qMapControl allows
static const int scrollStep = 40; ///< Scroll n pixels per keypress
......@@ -132,7 +144,16 @@ private:
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
bool waypointIsDrag;
qmapcontrol::LineString* camLine;
QList<qmapcontrol::Point*> camPoints;
QPointF lastCamBorderPos;
bool drawCamBorder;
int radioCamera;
};
#endif // MAPWIDGET_H
......@@ -489,32 +489,32 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal
qDebug() << "\nACTUALIZANDO GUI = " << pidValues.idx;
switch(pidValues.idx)
{
case 1:
case 0:
ui->dT_P_get->setText(QString::number(pidValues.pVal));
ui->dT_I_get->setText(QString::number(pidValues.iVal));
ui->dT_D_get->setText(QString::number(pidValues.dVal));
break;
case 2:
case 1:
ui->HELPComm_P_get->setText(QString::number(pidValues.pVal));
ui->HELPComm_I_get->setText(QString::number(pidValues.iVal));
ui->HELPComm_FF_get->setText(QString::number(pidValues.dVal));
break;
case 3:
case 2:
ui->dE_P_get->setText(QString::number(pidValues.pVal));
ui->dE_I_get->setText(QString::number(pidValues.iVal));
ui->dE_D_get->setText(QString::number(pidValues.dVal));
break;
case 4:
case 3:
ui->dR_P_get->setText(QString::number(pidValues.pVal));
ui->dR_I_get->setText(QString::number(pidValues.iVal));
ui->dR_D_get->setText(QString::number(pidValues.dVal));
break;
case 5:
case 4:
ui->dA_P_get->setText(QString::number(pidValues.pVal));
ui->dA_I_get->setText(QString::number(pidValues.iVal));
ui->dA_D_get->setText(QString::number(pidValues.dVal));
break;
case 9:
case 8:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
......
......@@ -977,6 +977,52 @@
</item>
</layout>
</widget>
<tabstops>
<tabstop>dT_P_set</tabstop>
<tabstop>dT_I_set</tabstop>
<tabstop>dT_D_set</tabstop>
<tabstop>dT_PID_set_pushButton</tabstop>
<tabstop>dT_PID_get_pushButton</tabstop>
<tabstop>HELPComm_P_set</tabstop>
<tabstop>HELPComm_I_set</tabstop>
<tabstop>HELPComm_FF_set</tabstop>
<tabstop>HELPComm_PDI_set_pushButton</tabstop>
<tabstop>HELPComm_PDI_get_pushButton</tabstop>
<tabstop>dE_P_set</tabstop>
<tabstop>dE_I_set</tabstop>
<tabstop>dE_D_set</tabstop>
<tabstop>dE_PID_set_pushButton</tabstop>
<tabstop>dE_PID_get_pushButton</tabstop>
<tabstop>dR_P_set</tabstop>
<tabstop>dR_I_set</tabstop>
<tabstop>dR_D_set</tabstop>
<tabstop>dR_PDI_set_pushButton</tabstop>
<tabstop>dR_PDI_get_pushButton</tabstop>
<tabstop>dA_P_set</tabstop>
<tabstop>dA_I_set</tabstop>
<tabstop>dA_D_set</tabstop>
<tabstop>dA_PID_set_pushButton</tabstop>
<tabstop>dA_PID_get_pushButton</tabstop>
<tabstop>P2dT_FF_set</tabstop>
<tabstop>Pitch2dT_PDI_set_pushButton</tabstop>
<tabstop>Pitch2dT_PDI_get_pushButton</tabstop>
<tabstop>dT_P_get</tabstop>
<tabstop>dT_I_get</tabstop>
<tabstop>dT_D_get</tabstop>
<tabstop>HELPComm_P_get</tabstop>
<tabstop>HELPComm_I_get</tabstop>
<tabstop>HELPComm_FF_get</tabstop>
<tabstop>dE_P_get</tabstop>
<tabstop>dE_I_get</tabstop>
<tabstop>dE_D_get</tabstop>
<tabstop>dR_P_get</tabstop>
<tabstop>dR_I_get</tabstop>
<tabstop>dR_D_get</tabstop>
<tabstop>dA_P_get</tabstop>
<tabstop>dA_I_get</tabstop>
<tabstop>dA_D_get</tabstop>
<tabstop>P2dT_FF_get</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>
This diff is collapsed.
......@@ -6,6 +6,10 @@
#include <QGraphicsView>
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#include "SlugsPadCameraControl.h"
#define DELTA 1000
namespace Ui {
class SlugsVideoCamControl;
......@@ -20,14 +24,36 @@ public:
explicit SlugsVideoCamControl(QWidget *parent = 0);
~SlugsVideoCamControl();
public slots:
void changeViewCamBorderAtMapStatus(bool status);
void getDeltaPositionPad(int x, int y);
double getDistPixel(int x1, int y1, int x2, int y2);
QPointF ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2);
signals:
void changeCamPosition(double dist, double dir, QString textDir);
void viewCamBorderAtMap(bool status);
protected:
virtual void mousePressEvent(QMouseEvent* event);
virtual void mouseReleaseEvent(QMouseEvent* event);
void mouseMoveEvent(QMouseEvent* event);
//virtual void paintEvent(QPaintEvent *pe);
void paintEvent(QPaintEvent *pe);
private:
Ui::SlugsVideoCamControl *ui;
bool dragging;
int x1;
int y1;
QPoint tL;
QPoint bR;
SlugsPadCameraControl* padCamera;
};
#endif // SLUGSVIDEOCAMCONTROL_H
......@@ -6,46 +6,83 @@
<rect>
<x>0</x>
<y>0</y>
<width>443</width>
<height>351</height>
<width>165</width>
<height>191</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QWidget" name="widget" native="true">
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QFrame" name="padCamContro_frame">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="mouseTracking">
<bool>true</bool>
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgb(255, 193, 76);</string>
<string notr="true">background-color: rgba(255, 170, 0,0%);
</string>
</property>
<property name="frameShape">
<enum>QFrame::WinPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Sunken</enum>
</property>
</widget>
</item>
<item>
<item row="1" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="label_y">
<widget class="QLabel" name="label_x">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<string>TextLabel</string>
<string>Coord_X</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_x">
<widget class="QLabel" name="label_y">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<string>TextLabel</string>
<string>Coord_Y</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_dir">
<property name="text">
<string>Camera Pos</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QCheckBox" name="viewCamBordeatMap_checkBox">
<property name="text">
<string>Camera at Map</string>
</property>
</widget>
</item>
......
......@@ -92,6 +92,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
isGlobalWP = false;
isLocalWP = false;
loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
......@@ -133,6 +134,8 @@ void WaypointList::setUAS(UASInterface* uas)
connect(&uas->getWaypointManager(), SIGNAL(waypointListChanged(void)), this, SLOT(waypointListChanged(void)));
connect(&uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(&uas->getWaypointManager(),SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
connect(&uas->getWaypointManager(),SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
......@@ -250,6 +253,8 @@ void WaypointList::addCurrentPositonWaypoint()
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
......@@ -341,7 +346,7 @@ void WaypointList::waypointListChanged()
WaypointGlobalView *wpgv = wpGlobalViews.value(wp);
wpgv->updateValues();
listLayout->addWidget(wpgv);
if(loadFileGlobalWP)
if(loadFileGlobalWP || readGlobalWP)
{
emit createWaypointAtMap(QPointF(wp->getX(),wp->getY()));
qDebug()<<"Emitiendo Pos: "<<wp->getX()<<" - "<<wp->getY();
......@@ -475,11 +480,12 @@ void WaypointList::changeEvent(QEvent *e)
void WaypointList::on_clearWPListButton_clicked()
{
if (uas)
{
if(isGlobalWP)
{
emit clearPathclicked();
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
......@@ -516,6 +522,13 @@ void WaypointList::on_clearWPListButton_clicked()
}
}
else
{
if(isGlobalWP)
{
emit clearPathclicked();
}
}
}
/** @brief Add a waypoint by mouse click over the map */
......@@ -638,3 +651,8 @@ void WaypointList::setIsLoadFileWP()
{
loadFileGlobalWP = true;
}
void WaypointList::setIsReadGlobalWP(bool value)
{
readGlobalWP = value;
}
......@@ -103,6 +103,7 @@ public slots:
void removeWaypoint(Waypoint* wp);
void setIsLoadFileWP();
void setIsReadGlobalWP(bool value);
......@@ -131,6 +132,7 @@ protected:
bool isLocalWP;
QPointF centerMapCoordinate;
bool loadFileGlobalWP;
bool readGlobalWP;
private:
Ui::WaypointList *m_ui;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment