Commit b800a8c0 authored by tecnosapiens's avatar tecnosapiens

add and test camera control widget

parent 5a8a8b2b
......@@ -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()){
......
......@@ -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);
}
......@@ -602,6 +619,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 +712,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>
......@@ -8,6 +8,7 @@
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
......@@ -16,6 +17,11 @@ SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
dragging(0)
{
ui->setupUi(this);
x1= 0;
y1 = 0;
connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
// QGraphicsScene *scene = new QGraphicsScene(ui->CamControlPanel_graphicsView);
// scene->setItemIndexMethod(QGraphicsScene::NoIndex);
......@@ -39,14 +45,16 @@ SlugsVideoCamControl::~SlugsVideoCamControl()
void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
{
QPoint tL = ui->widget->frameGeometry().topLeft();
QPoint bR = ui->widget->frameGeometry().bottomRight();
// ui->label_dir->setText("Camera Pos = " + QString::number(event->x()) + " - " + QString::number(event->y()));
// QPoint tL = ui->padCamContro_frame->frameGeometry().topLeft();
// QPoint bR = ui->padCamContro_frame->frameGeometry().bottomRight();
// if (!(event->x() > bR.x() || event->x() < tL.x() ||
// event->y() > bR.y() || event->y() < tL.y() ) && dragging){
// }
if (!(event->x() > bR.x() || event->x() < tL.x() ||
event->y() > bR.y() || event->y() < tL.y() ) && dragging){
ui->label_x->setText(QString::number(event->x()));
ui->label_y->setText(QString::number(event->y()));
}
}
......@@ -55,15 +63,269 @@ void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
{
Q_UNUSED(evnt);
x1 = evnt->x();
y1 = evnt->y();
dragging = true;
}
void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
{
dragging = false;
Q_UNUSED(evnt);
dragging = false;
getDeltaPositionPad(evnt->x(), evnt->y());
}
void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
{
emit viewCamBorderAtMap(status);
}
//void SlugsVideoCamControl::mouseDoubleClickEvent(QMouseEvent *evnt)
//{
void SlugsVideoCamControl::getDeltaPositionPad(int x2, int y2)
{
//double dist = getDistPixel(x1,y1,x2,y2);
QString dir = "nd";
QPointF localMeasures = ObtenerMarcacionDistanciaPixel(y1,x1,y2,x2);
double bearing = localMeasures.x();
double dist = localMeasures.y();
bearing = bearing +90;
if(bearing>= 360) bearing = bearing - 360;
if(((bearing > 330)&&(bearing < 360)) || ((bearing >= 0)&&(bearing <= 30)))
{
ui->label_dir->setText("up");
//bearing = 315;
dir = "up";
}
else
{
if((bearing > 30)&&(bearing <= 60) )
{
ui->label_dir->setText("right up");
//bearing = 315;
dir = "riht up";
}
else
{
if((bearing > 60)&&(bearing <= 105) )
{
ui->label_dir->setText("right");
//bearing = 315;
dir = "riht";
}
else
{
if((bearing > 105)&&(bearing <= 150) )
{
ui->label_dir->setText("right down");
//bearing = 315;
dir = "riht down";
}
else
{
if((bearing > 150)&&(bearing <= 195) )
{
ui->label_dir->setText("down");
//bearing = 315;
dir = "down";
}
else
{
if((bearing > 195)&&(bearing <= 240) )
{
ui->label_dir->setText("left down");
//bearing = 315;
dir = "left down";
}
else
{
if((bearing > 240)&&(bearing <= 300) )
{
ui->label_dir->setText("left");
//bearing = 315;
dir = "left";
}
else
{
if((bearing > 300)&&(bearing <= 330) )
{
ui->label_dir->setText("left up");
//bearing = 315;
dir = "left up";
}
}
}
}
}
}
}
}
ui->label_x->setText("Distancia= " + QString::number(dist) + " - x =" + QString::number(x1) );
ui->label_y->setText("Bearing= " + QString::number(bearing) + " - y = " + QString::number(y1));
emit changeCamPosition(20, bearing, dir);
// if((x2<x1)&&(y2<y1)) // left up
// {
// ui->label_dir->setText("left Up");
//// bearing = 315;
// dir = "left up";
// }
// else
// {
// if((x2<x1)&&(y2>y1)) // left down
// {
// ui->label_dir->setText("left down");
//// bearing = 225;
// dir = "left down";
// }
// else
// {
// if((x2<x1)&&(y2==y1))// left
// {
// ui->label_dir->setText("left");
//// bearing = 270;
// dir = "left";
// }
// else
// {
// if((x2==x1)&&(y2<y1)) // up
// {
// ui->label_dir->setText("Up");
//// bearing = 0;
// dir = "up";
// }
// else
// {
// if((x2==x1)&&(y2>y1)) // down
// {
// ui->label_dir->setText("down");
//// bearing = 180;
// dir = "down";
// }
// else
// {
// if((x2>x1)&&(y2==y1)) // right
// {
// ui->label_dir->setText("right");
//// bearing = 90;
// dir = "right";
// }
// else
// {
// if((x2>x1)&&(y2<y1))// right up
// {
// ui->label_dir->setText("right Up");
//// bearing = 45;
// dir = "right up";
// }
// else
// {
// if((x2>x1)&&(y2>y1))//right down
// {
// ui->label_dir->setText("right down");
//// bearing = 135;
// dir = "right down";
// }
// }
// }
// }
// }
// }
// }
// }
}
double SlugsVideoCamControl::getDistPixel(int x1, int y1, int x2, int y2)
{
double cateto_opuesto,cateto_adyacente;
//latitud y longitud del primer punto
cateto_opuesto = abs((x1-x2)); //diferencia de latitudes entre PCR1 y PCR2
cateto_adyacente = abs((y1-y2));//diferencia de longitudes entre PCR1 y PCR2
return sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
// distancia = (float) hipotenusa;
}
/**
* Esta funcin xxxxxxxxx
* @param double lat1 -->
* @param double lon1 -->
* @param double lat2 -->
* @param double lon2 -->
* @param ref double rumbo -->
* @param ref double distancia -->
*/
QPointF SlugsVideoCamControl::ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2)
{
double cateto_opuesto,cateto_adyacente, hipotenusa, distancia, marcacion;
//latitude and longitude first point
if(lat1<0) lat1= lat1*(-1);
if(lat2<0) lat2= lat2*(-1);
if(lon1<0) lon1= lon1*(-1);
if(lon2<0) lon1= lon1*(-1);
cateto_opuesto = abs((lat1-lat2));
cateto_adyacente = abs((lon1-lon2));
hipotenusa = sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
distancia = hipotenusa*60;
if ((lat1 < lat2) && (lon1 > lon2)) //primer cuadrante
marcacion = 360 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
else if ((lat1 < lat2) && (lon1 < lon2)) //segundo cuadrante
marcacion = (asin(cateto_adyacente/hipotenusa))/ 0.017453292;
else if((lat1 > lat2) && (lon1 < lon2)) //tercer cuadrante
marcacion = 180 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
else if((lat1 > lat2) && (lon1 > lon2)) //cuarto cuadrante
marcacion = 180 +((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
else if((lat1 < lat2) && (lon1 == lon2)) //360
marcacion = 360;
else if((lat1 == lat2) && (lon1 > lon2)) //270
marcacion = 270;
else if((lat1 > lat2) && (lon1 == lon2)) //180
marcacion = 180;
else if((lat1 == lat2) && (lon1 < lon2)) //90
marcacion =90;
else if((lat1 == lat2) && (lon1 == lon2)) //0
marcacion = 0.0;
return QPointF(marcacion,distancia);
}
//}
......@@ -7,6 +7,8 @@
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#define DELTA 1000
namespace Ui {
class SlugsVideoCamControl;
}
......@@ -20,14 +22,30 @@ 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);
private:
Ui::SlugsVideoCamControl *ui;
bool dragging;
int x1;
int y1;
};
#endif // SLUGSVIDEOCAMCONTROL_H
......@@ -6,46 +6,82 @@
<rect>
<x>0</x>
<y>0</y>
<width>443</width>
<height>351</height>
<width>153</width>
<height>200</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>153</width>
<height>176</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>131</width>
<height>91</height>
</size>
</property>
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgb(255, 193, 76);</string>
<string notr="true">background-color: rgb(255, 170, 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>
......
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