Commit ff627ad3 authored by Mariano Lizarraga's avatar Mariano Lizarraga

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

Conflicts:
	qgroundcontrol.pro
	src/ui/MainWindow.cc
	src/ui/SlugsDataSensorView.ui
parents 3732645d c84b1d0e
......@@ -147,7 +147,6 @@ FORMS += src/ui/MainWindow.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsVideoCamControl.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
......@@ -159,6 +158,7 @@ FORMS += src/ui/MainWindow.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui
src/ui/mission/QGCMissionDoWidget.ui \
src/ui/mission/QGCMissionConditionWidget.ui
......@@ -257,7 +257,6 @@ HEADERS += src/MG.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
......@@ -274,6 +273,7 @@ HEADERS += src/MG.h \
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \
src/ui/uas/UASControlParameters.h
src/ui/mission/QGCMissionDoWidget.h \
src/ui/mission/QGCMissionConditionWidget.h \
src/uas/QGCUASParamManager.h
......@@ -388,7 +388,6 @@ SOURCES += src/main.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
......@@ -405,6 +404,7 @@ SOURCES += src/main.cc \
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \
src/ui/uas/UASControlParameters.cpp
src/ui/mission/QGCMissionDoWidget.cc \
src/ui/mission/QGCMissionConditionWidget.cc \
src/uas/QGCUASParamManager.cc
......
......@@ -315,6 +315,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
currLossCounter = 0;
currReceiveCounter = 0;
emit receiveLossChanged(message.sysid, receiveLoss);
qDebug() << "LOSSCHANGED" << message.sysid<<" "<<receiveLoss;
}
// The packet is emitted as a whole, as it is only 255 - 261 bytes short
......
......@@ -131,11 +131,11 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
case MAVLINK_MSG_ID_MID_LVL_CMDS: //180
mavlink_msg_mid_lvl_cmds_decode(&message, &mlMidLevelCommands);
break;
case MAVLINK_MSG_ID_CTRL_SRFC_PT: //181
mavlink_msg_ctrl_srfc_pt_decode(&message, &mlPassthrough);
break;
case MAVLINK_MSG_ID_PID: //182
......
......@@ -395,6 +395,8 @@ void MainWindow::buildCommonWidgets()
dataplotWidget = new QGCDataPlot2D(this);
addToCentralWidgetsMenu (dataplotWidget, "Logfile Plot", SLOT(showCentralWidget()),CENTRAL_DATA_PLOT);
}
}
......@@ -628,21 +630,29 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu (slugsHilSimWidget, tr("HIL Sim Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_HIL, Qt::LeftDockWidgetArea);
}
if (!controlParameterWidget){
controlParameterWidget = new QDockWidget(tr("Control Parameters"), this);
controlParameterWidget->setObjectName("UNMANNED_SYSTEM_CONTROL_PARAMETERWIDGET");
controlParameterWidget->setWidget( new UASControlParameters(this) );
addToToolsMenu (controlParameterWidget, tr("Control Parameters"), SLOT(showToolWidget(bool)), MENU_UAS_CONTROL_PARAM, Qt::LeftDockWidgetArea);
}
if (!parametersDockWidget)
{
{
parametersDockWidget = new QDockWidget(tr("Calibration and Onboard Parameters"), this);
parametersDockWidget->setWidget( new ParameterInterface(this) );
parametersDockWidget->setObjectName("PARAMETER_INTERFACE_DOCKWIDGET");
addToToolsMenu (parametersDockWidget, tr("Calibration and Parameters"), SLOT(showToolWidget(bool)), MENU_PARAMETERS, Qt::RightDockWidgetArea);
}
// if (!slugsCamControlWidget)
// {
// slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
// slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
// slugsCamControlWidget->setObjectName("SLUGS_CAM_CONTROL_DOCK_WIDGET");
// addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
// }
if (!slugsCamControlWidget)
{
slugsCamControlWidget = new QDockWidget(tr("Camera Control"), this);
slugsCamControlWidget->setWidget(new SlugsPadCameraControl(this));
slugsCamControlWidget->setObjectName("SLUGS_CAM_CONTROL_DOCK_WIDGET");
addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget(bool)), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
}
}
......@@ -1026,10 +1036,6 @@ void MainWindow::connectCommonWidgets()
//
connect(waypointsDockWidget->widget(), SIGNAL(changePointList()), mapWidget, SLOT(clearWaypoints()));
}
//TODO temporaly debug
......@@ -1037,6 +1043,8 @@ void MainWindow::connectCommonWidgets()
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsHilSimWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
}
void MainWindow::createCustomWidget()
......@@ -1084,6 +1092,16 @@ void MainWindow::connectSlugsWidgets()
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsPIDControlWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
if (controlParameterWidget && controlParameterWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
controlParameterWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
if(controlDockWidget && controlParameterWidget)
{
connect(controlDockWidget->widget(), SIGNAL(changedMode(int)), controlParameterWidget->widget(), SLOT(changedMode(int)));
}
}
void MainWindow::arrangeCommonCenterStack()
......@@ -1942,6 +1960,8 @@ void MainWindow::presentView()
// UAS CONTROL
showTheWidget(MENU_UAS_CONTROL, currentView);
showTheWidget(MENU_UAS_CONTROL_PARAM, currentView);
// UAS LIST
showTheWidget(MENU_UAS_LIST, currentView);
......
......@@ -74,8 +74,8 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsHilSim.h"
#include "SlugsVideoCamControl.h"
#include "SlugsPadCameraControl.h"
#include "UASControlParameters.h"
/**
* @brief Main Application Window
......@@ -212,6 +212,7 @@ protected:
// FIXME: DO NOT PUT CUSTOM VALUES IN THIS ENUM since it is iterated over
// this will be fixed in a future release.
typedef enum _TOOLS_WIDGET_NAMES {
MENU_UAS_CONTROL_PARAM,
MENU_UAS_CONTROL,
MENU_UAS_INFO,
MENU_CAMERA,
......@@ -381,6 +382,7 @@ protected:
#endif
// Dock widgets
QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> controlParameterWidget;
QPointer<QDockWidget> infoDockWidget;
QPointer<QDockWidget> cameraDockWidget;
QPointer<QDockWidget> listDockWidget;
......
......@@ -93,6 +93,8 @@ void MapWidget::init()
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
homePosition = new qmapcontrol::GeometryLayer("Station", mapadapter);
mc->addLayer(homePosition);
//
......@@ -183,11 +185,17 @@ void MapWidget::init()
goToButton->setToolTip(tr("Enter a latitude/longitude position to move the map to"));
goToButton->setStatusTip(tr("Enter a latitude/longitude position to move the map to"));
setHome = new QPushButton(QIcon(":/images/actions/go-home.svg"), "", this);
setHome->setStyleSheet(buttonStyle);
setHome->setToolTip(tr("Set home"));
setHome->setStatusTip(tr("Set home"));
zoomin->setMaximumWidth(30);
zoomout->setMaximumWidth(30);
createPath->setMaximumWidth(30);
// clearTracking->setMaximumWidth(30);
followgps->setMaximumWidth(30);
setHome->setMaximumWidth(30);
goToButton->setMaximumWidth(30);
// Set checkable buttons
......@@ -195,6 +203,7 @@ void MapWidget::init()
// create a style and the slots to change the background so it is easier to distinguish
followgps->setCheckable(true);
createPath->setCheckable(true);
setHome->setCheckable(true);
// add buttons to control the map (zoom, GPS tracking and WP capture)
QGridLayout* innerlayout = new QGridLayout(mc);
......@@ -204,6 +213,7 @@ void MapWidget::init()
innerlayout->addWidget(zoomout, 1, 0);
innerlayout->addWidget(followgps, 2, 0);
innerlayout->addWidget(createPath, 3, 0);
innerlayout->addWidget(setHome, 4, 0);
//innerlayout->addWidget(clearTracking, 4, 0);
// Add spacers to compress buttons on the top left
innerlayout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 5, 0);
......@@ -223,8 +233,8 @@ void MapWidget::init()
//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);
//camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter);
//mc->addLayer(camLayer);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
......@@ -262,6 +272,12 @@ void MapWidget::init()
connect(createPath, SIGNAL(clicked(bool)),
this, SLOT(createPathButtonClicked(bool)));
connect(setHome, SIGNAL(clicked(bool)), this, SLOT(createHomePositionClick(bool)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*,QPointF)), this,
SLOT(createHomePosition(const QMouseEvent*,QPointF)));
//connect(setHome, SIGNAL(clicked(bool)), this, SLOT(createHomePosition(bool)));
connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)),
this, SLOT(captureGeometryClick(Geometry*, QPoint)));
......@@ -1199,3 +1215,46 @@ QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double beari
return temp;
}
void MapWidget::createHomePosition(const QMouseEvent *event, const QPointF coordinate)
{
if (QEvent::MouseButtonRelease == event->type() && setHome->isChecked())
{
homeCoordinate= coordinate;
Waypoint2DIcon* tempCirclePoint;
double latitud = homeCoordinate.x();
double longitud = homeCoordinate.y();
tempCirclePoint = new Waypoint2DIcon(
latitud,
longitud,
20, "g", qmapcontrol::Point::Middle);
QPen* pencil = new QPen(Qt::blue);
tempCirclePoint->setPen(pencil);
mc->layer("Station")->clearGeometries();
mc->layer("Station")->addGeometry(tempCirclePoint);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(latitud, longitud,"g");
if (isVisible())
{
mc->updateRequest(tempPoint->boundingBox().toRect());
}
}
}
void MapWidget::createHomePositionClick(bool click)
{
Q_UNUSED(click);
if (!setHome->isChecked())
{
UASManager::instance()->setHomePosition(
static_cast<double>(homeCoordinate.x()),
static_cast<double>(homeCoordinate.y()), 0);
qDebug()<<"Set home position "<<homeCoordinate.x()<<" "<<homeCoordinate.y();
}
}
......@@ -118,6 +118,7 @@ protected:
QPushButton* followgps;
QPushButton* createPath;
QPushButton* clearTracking;
QPushButton* setHome;
QLabel* gpsposition;
QMenu* mapMenu;
QPushButton* mapButton;
......@@ -128,9 +129,9 @@ protected:
qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::Layer* tracks; ///< Layer for UAV tracks
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
qmapcontrol::GeometryLayer* homePosition; ///< Layer for station control
//only for experiment
qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
//qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
int zoomLevel;
int detailZoom; ///< Steps zoomed in further than qMapControl allows
......@@ -163,6 +164,9 @@ protected:
void createWaypointGraphAtMap(int id, const QPointF coordinate);
void mapproviderSelected(QAction* action);
void createHomePosition(const QMouseEvent* event, const QPointF coordinate);
void createHomePositionClick(bool click);
signals:
//void movePoint(QPointF newCoord);
//void captureMapCoordinateClick(const QPointF coordinate); //ROCA
......@@ -188,6 +192,7 @@ private:
bool drawCamBorder;
int radioCamera;
QPointF homeCoordinate;
};
#endif // MAPWIDGET_H
......@@ -191,7 +191,11 @@ void QGCRemoteControlView::redraw()
progressBars.at(i)->setValue(vv);
}
// Update RSSI
rssiBar->setValue(rssi*100);
if(rssi>0)
{
rssiBar->setValue(rssi*100);
}
updated = false;
}
}
......
......@@ -6,7 +6,7 @@
<rect>
<x>0</x>
<y>0</y>
<width>392</width>
<width>495</width>
<height>768</height>
</rect>
</property>
......
This diff is collapsed.
#ifndef SLUGSPADCAMERACONTROL_H
#define SLUGSPADCAMERACONTROL_H
#include <QWidget>
#include <QGraphicsView>
namespace Ui {
class SlugsPadCameraControl;
}
class SlugsPadCameraControl : public QWidget //QGraphicsView//
{
Q_OBJECT
public:
explicit SlugsPadCameraControl(QWidget *parent = 0);
~SlugsPadCameraControl();
public slots:
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);
QPointF getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia);
signals:
void mouseMoveCoord(int x, int y);
void mousePressCoord(int x, int y);
void mouseReleaseCoord(int x, int y);
void dirCursorText(QString dir);
void distance_Bearing(double dist, double bearing);
void changeCursorPosition(double bearing, double distance, QString textDir);
protected:
void mousePressEvent(QMouseEvent* event);
void mouseReleaseEvent(QMouseEvent* event);
void mouseMoveEvent(QMouseEvent* event);
void paintEvent(QPaintEvent *pe);
private:
Ui::SlugsPadCameraControl *ui;
bool dragging;
int x1;
int y1;
int xFin;
int yFin;
double bearingPad;
double distancePad;
QString directionPad;
};
#endif // SLUGSPADCAMERACONTROL_H
#ifndef SLUGSPADCAMERACONTROL_H
#define SLUGSPADCAMERACONTROL_H
#include <QtGui/QWidget>
#include <QGraphicsView>
#include <QMouseEvent>
#include <QKeyEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include "UASManager.h"
namespace Ui {
class SlugsPadCameraControl;
}
class SlugsPadCameraControl : public QWidget //QGraphicsView//
{
Q_OBJECT
public:
explicit SlugsPadCameraControl(QWidget *parent = 0);
~SlugsPadCameraControl();
enum MotionCamera {
UP,
DOWN,
LEFT,
RIGHT,
RIGHT_UP,
RIGHT_DOWN,
LEFT_UP,
LEFT_DOWN,
NONE
};
public slots:
void getDeltaPositionPad(int x, int y);
QPointF ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2);
void activeUasSet(UASInterface *uas);
signals:
void changeMotionCamera(MotionCamera);
protected:
void mousePressEvent(QMouseEvent* event);
void mouseReleaseEvent(QMouseEvent* event);
void mouseMoveEvent(QMouseEvent* event);
void keyPressEvent(QKeyEvent *event);
//void paintEvent(QPaintEvent *pe);
private:
Ui::SlugsPadCameraControl *ui;
bool dragging;
int x1;
int y1;
int xFin;
int yFin;
QString directionPad;
MotionCamera motion;
UASInterface* activeUAS;
QPoint movePad;
};
#endif // SLUGSPADCAMERACONTROL_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>SlugsPadCameraControl</class>
<widget class="QWidget" name="SlugsPadCameraControl">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>183</width>
<height>127</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgb(255, 170, 0);</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="margin">
<number>1</number>
</property>
<property name="spacing">
<number>1</number>
</property>
<item row="0" column="0">
<widget class="QFrame" name="frame">
<property name="minimumSize">
<size>
<width>181</width>
<height>125</height>
</size>
</property>
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 0, 0,50%);</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>SlugsPadCameraControl</class>
<widget class="QWidget" name="SlugsPadCameraControl">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>200</width>
<height>200</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgb(255, 170, 0);</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="margin">
<number>1</number>
</property>
<property name="spacing">
<number>1</number>
</property>
<item row="0" column="0">
<widget class="QFrame" name="frame">
<property name="minimumSize">
<size>
<width>200</width>
<height>200</height>
</size>
</property>
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color: rgba(255, 0, 0,50%);</string>
</property>
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>156</height>
</size>
</property>
</spacer>
</item>
<item row="1" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="lbPixel">
<property name="text">
<string>----</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="lbDirection">
<property name="text">
<string>----</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "SlugsVideoCamControl.h"
#include "ui_SlugsVideoCamControl.h"
#include <QGraphicsScene>
#include <QGraphicsTextItem>
#include <QTextStream>
#include <QScrollBar>
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include "SlugsPadCameraControl.h"
SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsVideoCamControl)
{
ui->setupUi(this);
// x1= 0;
// y1 = 0;
connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
padCamera = new SlugsPadCameraControl(this);
ui->gridLayout->addWidget(padCamera);
connect(padCamera,SIGNAL(mouseMoveCoord(int,int)),this,SLOT(mousePadMoveEvent(int,int)));
connect(padCamera,SIGNAL(mousePressCoord(int,int)),this,SLOT(mousePadPressEvent(int,int)));
connect(padCamera,SIGNAL(mouseReleaseCoord(int,int)),this,SLOT(mousePadReleaseEvent(int,int)));
connect(padCamera,SIGNAL(changeCursorPosition(double,double,QString)),this,SLOT(getDeltaPositionPad(double,double,QString)));
}
SlugsVideoCamControl::~SlugsVideoCamControl()
{
delete ui;
}
//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
//{
// Q_UNUSED(event);
//}
//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
//{
//}
void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
{
emit viewCamBorderAtMap(status);
}
void SlugsVideoCamControl::getDeltaPositionPad(double bearing, double distance, QString dirText)
{
ui->label_dir->setText(dirText);
ui->label_x->setText("Distancia= " + QString::number(distance));
ui->label_y->setText("Bearing= " + QString::number(bearing));
emit changeCamPosition(20, bearing, dirText);
}
#include "SlugsVideoCamControl.h"
#include "ui_SlugsVideoCamControl.h"
#include <QGraphicsScene>
#include <QGraphicsTextItem>
#include <QTextStream>
#include <QScrollBar>
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include "SlugsPadCameraControl.h"
SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsVideoCamControl)
{
ui->setupUi(this);
// x1= 0;
// y1 = 0;
connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
padCamera = new SlugsPadCameraControl(this);
ui->gridLayout->addWidget(padCamera);
//connect(padCamera,SIGNAL(mouseMoveCoord(int,int)),this,SLOT(mousePadMoveEvent(int,int)));
//connect(padCamera,SIGNAL(mousePressCoord(int,int)),this,SLOT(mousePadPressEvent(int,int)));
//connect(padCamera,SIGNAL(mouseReleaseCoord(int,int)),this,SLOT(mousePadReleaseEvent(int,int)));
//connect(padCamera,SIGNAL(changeCursorPosition(double,double,QString)),this,SLOT(getDeltaPositionPad(double,double,QString)));
}
SlugsVideoCamControl::~SlugsVideoCamControl()
{
delete ui;
}
//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
//{
// Q_UNUSED(event);
//}
//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
//{
//}
void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
{
emit viewCamBorderAtMap(status);
}
void SlugsVideoCamControl::getDeltaPositionPad(double bearing, double distance, QString dirText)
{
ui->label_dir->setText(dirText);
ui->label_x->setText("Distancia= " + QString::number(distance));
ui->label_y->setText("Bearing= " + QString::number(bearing));
//emit changeCamPosition(20, bearing, dirText);
}
#ifndef SLUGSVIDEOCAMCONTROL_H
#define SLUGSVIDEOCAMCONTROL_H
#include <QWidget>
#include <QMouseEvent>
#include <QGraphicsView>
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#include "SlugsPadCameraControl.h"
#include <QPushButton>
#define DELTA 1000
namespace Ui {
class SlugsVideoCamControl;
}
class SlugsVideoCamControl : public QWidget
{
Q_OBJECT
public:
explicit SlugsVideoCamControl(QWidget *parent = 0);
~SlugsVideoCamControl();
public slots:
/**
* @brief status = true: emit signal to draw a border cam over the map
*/
void changeViewCamBorderAtMapStatus(bool status);
/**
* @brief show the values of mousepad on ui (labels) and emit a changeCamPosition(signal)
* with values:
* bearing and distance from mouse over the pad
* dirText: direction of mouse movement in text format (up, right,right up,right down,
* left, left up, left down, down)
*/
void getDeltaPositionPad(double bearing, double distance, QString dirText);
// /**
// * @brief
// */
// void mousePadPressEvent(int x, int y);
// void mousePadReleaseEvent(int x, int y);
// void mousePadMoveEvent(int x, int y);
signals:
/**
* @brief emit values from mousepad:
* bearing and distance from mouse over the pad
* dirText: direction of mouse movement in text format (up, right,right up,right down,
* left, left up, left down, down)
*/
void changeCamPosition(double distance, double bearing, QString textDir);
/**
* @brief emit signal to draw a border cam over the map if status is true
*/
void viewCamBorderAtMap(bool status);
protected:
// void mousePressEvent(QMouseEvent* event);
// void mouseReleaseEvent(QMouseEvent* event);
// void mouseMoveEvent(QMouseEvent* event);
private:
Ui::SlugsVideoCamControl *ui;
SlugsPadCameraControl* padCamera;
};
#endif // SLUGSVIDEOCAMCONTROL_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>SlugsVideoCamControl</class>
<widget class="QWidget" name="SlugsVideoCamControl">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<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">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_x">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<string>Coord_X</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_y">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<string>Coord_Y</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QCheckBox" name="viewCamBordeatMap_checkBox">
<property name="text">
<string>Camera at Map</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_dir">
<property name="text">
<string>Camera Pos</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>UASControlParameters</class>
<widget class="QWidget" name="UASControlParameters">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>204</width>
<height>246</height>
</rect>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>150</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>267</width>
<height>16777215</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_5">
<item>
<spacer name="horizontalSpacer_2">
<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="lbMode">
<property name="minimumSize">
<size>
<width>100</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>16777215</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>----</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="1" column="0">
<widget class="QTabWidget" name="tabWidget">
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="currentIndex">
<number>1</number>
</property>
<widget class="QWidget" name="tab">
<attribute name="title">
<string>Commands</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_2">
<item row="1" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label_2">
<property name="text">
<string>Height (m)</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="sbHeight">
<property name="maximum">
<double>1500.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>Airspeed (m/s)</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="sbAirSpeed">
<property name="maximum">
<double>500.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item row="3" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QLabel" name="label_4">
<property name="text">
<string>Turn Rate (rad/s)</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="sbTurnRate">
<property name="maximum">
<double>180.000000000000000</double>
</property>
</widget>
</item>
</layout>
</item>
<item row="4" column="0">
<layout class="QHBoxLayout" name="horizontalLayout_4">
<item>
<widget class="QPushButton" name="btSetCommands">
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="btGetCommands">
<property name="text">
<string>Get</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="5" column="0">
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>27</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab_2">
<attribute name="title">
<string>Passthrough</string>
</attribute>
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QCheckBox" name="cxdle_c">
<property name="text">
<string>Elevator</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxdr_c">
<property name="text">
<string>Rudder</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxdt_c">
<property name="text">
<string>Throttle</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="cxdla_c">
<property name="text">
<string>Ailerons</string>
</property>
</widget>
</item>
</layout>
</item>
<item row="1" column="0">
<widget class="QPushButton" name="btSetCtrl">
<property name="text">
<string>Set</string>
</property>
</widget>
</item>
<item row="2" column="0">
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>26</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "src\ui\uas\UASControlParameters.h"
#include "ui_UASControlParameters.h"
#define CONTROL_MODE_LOCKED "MODE LOCKED"
#define CONTROL_MODE_MANUAL "MODE MANUAL"
#define CONTROL_MODE_GUIDED "MODE GUIDED"
#define CONTROL_MODE_AUTO "MODE AUTO"
#define CONTROL_MODE_TEST1 "MODE TEST1"
#define CONTROL_MODE_TEST2 "MODE TEST2"
#define CONTROL_MODE_TEST3 "MODE TEST3"
#define CONTROL_MODE_READY "MODE TEST3"
#define CONTROL_MODE_RC_TRAINING "RC SIMULATION"
#define CONTROL_MODE_LOCKED_INDEX 1
#define CONTROL_MODE_MANUAL_INDEX 2
#define CONTROL_MODE_GUIDED_INDEX 3
#define CONTROL_MODE_AUTO_INDEX 4
#define CONTROL_MODE_TEST1_INDEX 5
#define CONTROL_MODE_TEST2_INDEX 6
#define CONTROL_MODE_TEST3_INDEX 7
#define CONTROL_MODE_READY_INDEX 8
#define CONTROL_MODE_RC_TRAINING_INDEX 9
UASControlParameters::UASControlParameters(QWidget *parent) :
QWidget(parent),
ui(new Ui::UASControlParameters)
{
ui->setupUi(this);
ui->btSetCtrl->setStatusTip(tr("Set Passthrough"));
connect(ui->btGetCommands, SIGNAL(clicked()), this, SLOT(getCommands()));
connect(ui->btSetCtrl, SIGNAL(clicked()), this, SLOT(setPassthrough()));
}
UASControlParameters::~UASControlParameters()
{
delete ui;
}
void UASControlParameters::changedMode(int mode)
{
QString modeTemp;
switch (mode)
{
case (uint8_t)MAV_MODE_LOCKED:
modeTemp = "LOCKED MODE";
break;
case (uint8_t)MAV_MODE_MANUAL:
modeTemp = "MANUAL MODE";
break;
case (uint8_t)MAV_MODE_AUTO:
modeTemp = "AUTO MODE";
break;
case (uint8_t)MAV_MODE_GUIDED:
modeTemp = "GUIDED MODE";
break;
case (uint8_t)MAV_MODE_READY:
modeTemp = "READY MODE";
break;
case (uint8_t)MAV_MODE_TEST1:
modeTemp = "TEST1 MODE";
break;
case (uint8_t)MAV_MODE_TEST2:
modeTemp = "TEST2 MODE";
break;
case (uint8_t)MAV_MODE_TEST3:
modeTemp = "TEST3 MODE";
break;
case (uint8_t)MAV_MODE_RC_TRAINING:
modeTemp = "RC TRAINING MODE";
break;
default:
modeTemp = "UNINIT MODE";
break;
}
if(modeTemp != this->mode)
{
ui->lbMode->setStyleSheet("background-color: rgb(255, 0, 0)");
}
else
{
ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)");
}
}
void UASControlParameters::activeUasSet(UASInterface *uas)
{
if(uas)
{
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(speedChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(thrustChanged(UASInterface*,double)), this, SLOT(thrustChanged(UASInterface*,double)) );
activeUAS= uas;
}
}
void UASControlParameters::updateGlobalPosition(UASInterface * a, double b, double c, double aa, quint64 ab)
{
//ui->sbHeight->setValue(aa);
this->altitude=aa;
}
void UASControlParameters::speedChanged(UASInterface* uas, double vx, double vy, double vz, quint64 time)
{
this->speed = sqrt(pow(vx, 2.0) + pow(vy, 2.0) + pow(vz, 2.0));
//ui->sbAirSpeed->setValue(speed);
}
void UASControlParameters::updateAttitude(UASInterface *uas, double roll, double pitch, double yaw, quint64 time)
{
Q_UNUSED(uas);
Q_UNUSED(time);
//ui->sbTurnRate->setValue(roll);
this->roll = roll;
}
void UASControlParameters::setCommands()
{
if(this->activeUAS)
{
UAS* myUas= static_cast<UAS*>(this->activeUAS);
mavlink_message_t msg;
tempCmds.uCommand = ui->sbAirSpeed->value();
tempCmds.hCommand = ui->sbHeight->value();
tempCmds.rCommand = ui->sbTurnRate->value();
mavlink_msg_mid_lvl_cmds_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCmds);
myUas->sendMessage(msg);
}
}
void UASControlParameters::getCommands()
{
ui->sbAirSpeed->setValue(this->speed);
ui->sbHeight->setValue(this->altitude);
ui->sbTurnRate->setValue(this->roll);
}
void UASControlParameters::setPassthrough()
{
if(this->activeUAS)
{
UAS* myUas= static_cast<UAS*>(this->activeUAS);
mavlink_message_t msg;
int8_t tmpBit=0;
if(ui->cxdle_c->isChecked())//left elevator command
{
tmpBit+=8;
}
if(ui->cxdr_c->isChecked())//rudder command
{
tmpBit+=16;
}
if(ui->cxdla_c->isChecked())//left aileron command
{
tmpBit+=64;
}
if(ui->cxdt_c->isChecked())//throttle command
{
tmpBit+=128;
}
generic_16bit r;
r.b[1] = 0;
r.b[0] = tmpBit;//255;
tempCtrl.target= this->activeUAS->getUASID();
tempCtrl.bitfieldPt= (uint16_t)r.s;
mavlink_msg_ctrl_srfc_pt_encode(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, &this->tempCtrl);
myUas->sendMessage(msg);
//qDebug()<<tempCtrl.bitfieldPt;
}
}
void UASControlParameters::updateMode(int uas,QString mode,QString description)
{
Q_UNUSED(uas);
Q_UNUSED(description);
this->mode = mode;
ui->lbMode->setText(this->mode);
ui->lbMode->setStyleSheet("background-color: rgb(0, 255, 0)");
}
void UASControlParameters::thrustChanged(UASInterface *uas, double throttle)
{
Q_UNUSED(uas);
this->throttle= throttle;
}
#ifndef UASCONTROLPARAMETERS_H
#define UASCONTROLPARAMETERS_H
#include <QWidget>
#include "UASManager.h"
#include "SlugsMAV.h"
#include <QTimer>
#include <QTabWidget>
namespace Ui {
class UASControlParameters;
}
class UASControlParameters : public QWidget
{
Q_OBJECT
public:
explicit UASControlParameters(QWidget *parent = 0);
~UASControlParameters();
public slots:
void changedMode(int mode);
void activeUasSet(UASInterface* uas);
void updateGlobalPosition(UASInterface*,double,double,double,quint64);
void speedChanged(UASInterface*,double,double,double,quint64);
void updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 time);
void setCommands();
void getCommands();
void setPassthrough();
void updateMode(int uas,QString mode,QString description);
void thrustChanged(UASInterface* uas,double throttle);
private:
Ui::UASControlParameters *ui;
QTimer* refreshTimerGet;
UASInterface* activeUAS;
double speed;
double roll;
double altitude;
double throttle;
QString mode;
QString REDcolorStyle;
QPointer<RadioCalibrationData> radio;
LinkInterface* hilLink;
mavlink_mid_lvl_cmds_t tempCmds;
mavlink_ctrl_srfc_pt_t tempCtrl;
};
#endif // UASCONTROLPARAMETERS_H
......@@ -253,6 +253,8 @@ void UASControlWidget::setMode(int mode)
qDebug() << "SET MODE REQUESTED" << uasMode;
emit changedMode(mode);
}
void UASControlWidget::transmitMode()
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of class UASControlWidget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UASCONTROLWIDGET_H_
#define _UASCONTROLWIDGET_H_
#include <QWidget>
#include <QLineEdit>
#include <QString>
#include <QPushButton>
#include <ui_UASControl.h>
#include <UASInterface.h>
/**
* @brief Widget controlling one MAV
*/
class UASControlWidget : public QWidget
{
Q_OBJECT
public:
UASControlWidget(QWidget *parent = 0);
~UASControlWidget();
public slots:
/** @brief Set the system this widget controls */
void setUAS(UASInterface* uas);
/** @brief Trigger next context action */
void cycleContextButton();
/** @brief Set the operation mode of the MAV */
void setMode(int mode);
/** @brief Transmit the operation mode */
void transmitMode();
/** @brief Update the mode */
void updateMode(int uas,QString mode,QString description);
/** @brief Update state */
void updateState(int state);
/** @brief Update internal state machine */
void updateStatemachine();
protected slots:
/** @brief Set the background color for the widget */
void setBackgroundColor(QColor color);
protected:
int uas; ///< Reference to the current uas
unsigned int uasMode; ///< Current uas mode
bool engineOn; ///< Engine state
private:
Ui::uasControl ui;
};
#endif // _UASCONTROLWIDGET_H_
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Definition of class UASControlWidget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#ifndef _UASCONTROLWIDGET_H_
#define _UASCONTROLWIDGET_H_
#include <QWidget>
#include <QLineEdit>
#include <QString>
#include <QPushButton>
#include <ui_UASControl.h>
#include <UASInterface.h>
/**
* @brief Widget controlling one MAV
*/
class UASControlWidget : public QWidget
{
Q_OBJECT
public:
UASControlWidget(QWidget *parent = 0);
~UASControlWidget();
public slots:
/** @brief Set the system this widget controls */
void setUAS(UASInterface* uas);
/** @brief Trigger next context action */
void cycleContextButton();
/** @brief Set the operation mode of the MAV */
void setMode(int mode);
/** @brief Transmit the operation mode */
void transmitMode();
/** @brief Update the mode */
void updateMode(int uas,QString mode,QString description);
/** @brief Update state */
void updateState(int state);
/** @brief Update internal state machine */
void updateStatemachine();
signals:
void changedMode(int);
protected slots:
/** @brief Set the background color for the widget */
void setBackgroundColor(QColor color);
protected:
int uas; ///< Reference to the current uas
unsigned int uasMode; ///< Current uas mode
bool engineOn; ///< Engine state
private:
Ui::uasControl ui;
};
#endif // _UASCONTROLWIDGET_H_
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