Commit ee725d72 authored by lm's avatar lm

Merge branch 'master' of github.com:pixhawk/qgroundcontrol into dev

parents efc0e3c6 72a41511
......@@ -27,3 +27,7 @@ deploy/linux
controller_log*
user_config.pri
*.app
*.ncb
*.vcproj
*.sln
\ No newline at end of file
......@@ -84,6 +84,7 @@
<file>images/mapproviders/yahoo.png</file>
<file>images/earth.html</file>
<file>images/mapproviders/googleearth.svg</file>
<file>images/contrib/slugs.png</file>
</qresource>
<qresource prefix="/general">
<file alias="vera.ttf">images/Vera.ttf</file>
......
......@@ -125,10 +125,11 @@ macx {
-framework GEOS \
-framework SQLite3 \
-framework osgFX \
-framework osgTerrain \
-framework osgTerrain
DEFINES += QGC_OSGEARTH_ENABLED
}
exists(/opt/local/include/libfreenect) {
message("Building support for libfreenect")
DEPENDENCIES_PRESENT += libfreenect
......@@ -324,7 +325,7 @@ exists($$BASEDIR/lib/osgEarth123) {
BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
QMAKE_PRE_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\debug\SDL.dll\"
QMAKE_PRE_LINK += && copy /Y \"$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll\" \"$$TARGETDIR_WIN\\debug\\SDL.dll\"
QMAKE_PRE_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\release\SDL.dll\"
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\debug\audio\" /S /E /Y
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\release\audio\" /S /E /Y
......@@ -365,15 +366,13 @@ win32-g++ {
RC_FILE = $$BASEDIR/qgroundcontrol.rc
# Copy dependencies
BASEDIR_WIN = $$replace(BASEDIR,"/","\\")
TARGETDIR_WIN = $$replace(TARGETDIR,"/","\\")
QMAKE_PRE_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\debug\SDL.dll\"
QMAKE_PRE_LINK += && copy /Y \"$$BASEDIR_WIN\lib\sdl\win32\SDL.dll\" \"$$TARGETDIR_WIN\release\SDL.dll\"
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\debug\audio\" /S /E /Y
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\audio\" \"$$TARGETDIR_WIN\release\audio\" /S /E /Y
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\debug\models\" /S /E /Y
QMAKE_PRE_LINK += && xcopy \"$$BASEDIR_WIN\models\" \"$$TARGETDIR_WIN\release\models\" /S /E /Y
QMAKE_PRE_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/debug/SDL.dll
QMAKE_PRE_LINK += && cp $$BASEDIR/lib/sdl/win32/SDL.dll $$TARGETDIR/release/SDL.dll
QMAKE_PRE_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/debug/audio
QMAKE_PRE_LINK += && cp -r $$BASEDIR/audio $$TARGETDIR/release/audio
QMAKE_PRE_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/debug/models
QMAKE_PRE_LINK += && cp -r $$BASEDIR/models $$TARGETDIR/release/models
# osg/osgEarth dynamic casts might fail without this compiler option.
# see http://osgearth.org/wiki/FAQ for details.
......
......@@ -23,6 +23,7 @@
# Version from GIT repository is preferred
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri)
# message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")
......@@ -139,13 +140,18 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/WaypointGlobalView.ui \
src/ui/QMap3D.ui \
src/ui/QGCWebView.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/map3D/QGCGoogleEarthViewWin.ui \
src/ui/map3D/QGCGoogleEarthControls.ui
src/ui/map3D/QGCGoogleEarthControls.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsVideoCamControl.ui \
src/ui/SlugsPadCameraControl.ui
# src/ui/WaypointGlobalView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -160,6 +166,7 @@ INCLUDEPATH += src \
src/ui/param \
src/ui/watchdog \
src/ui/map3D
HEADERS += src/MG.h \
src/Core.h \
src/uas/UASInterface.h \
......@@ -236,8 +243,14 @@ HEADERS += src/MG.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/comm/QGCMAVLink.h \
src/ui/QGCWebView.h \
src/ui/map3D/QGCGoogleEarthView.h \
src/ui/map3D/QGCWebPage.h
src/ui/map3D/QGCWebPage.h \
src/ui/map3D/QGCGoogleEarthView.h\
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsVideoCamControl.h \
src/ui/SlugsPadCameraControl.h
contains(DEPENDENCIES_PRESENT, osg) {
message("Including headers for OpenSceneGraph")
......@@ -269,6 +282,7 @@ contains(DEPENDENCIES_PRESENT, libfreenect) {
# Enable only if libfreenect is available
HEADERS += src/input/Freenect.h
}
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -340,7 +354,12 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/QGCWebView.cc \
src/ui/map3D/QGCGoogleEarthView.cc \
src/ui/map3D/QGCWebPage.cc
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsVideoCamControl.cpp \
src/ui/SlugsPadCameraControl.cpp
contains(DEPENDENCIES_PRESENT, osg) {
message("Including sources for OpenSceneGraph")
......@@ -358,7 +377,9 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc
src/ui/map3D/WaypointGroupNode.cc \
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
......
......@@ -77,6 +77,7 @@ bool Waypoint::load(QTextStream &loadStream)
return false;
}
void Waypoint::setId(quint16 id)
{
this->id = id;
......
......@@ -63,6 +63,7 @@ public:
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
protected:
quint16 id;
float x;
......
......@@ -64,7 +64,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
// Set the port name
if (porthandle == "")
{
name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
// name = tr("serial link ") + QString::number(getId()) + tr(" (unconfigured)");
name = tr("Serial Link ") + QString::number(getId());
}
else
{
......@@ -89,6 +90,7 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
#else
// *nix (Linux, MacOS tested) serial port support
port = new QextSerialPort(porthandle, QextSerialPort::Polling);
//port = new QextSerialPort(porthandle, QextSerialPort::EventDriven);
port->setTimeout(timeout); // Timeout of 0 ms, we don't want to wait for data, we just poll again next time
port->setBaudRate(baudrate);
port->setFlowControl(flow);
......
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "mavlink.h"
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL 2
#ifdef MAVLINK_ENABLED_SLUGS
#define SERIAL_POLL_INTERVAL 7
#else
#define SERIAL_POLL_INTERVAL 2
#endif
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
......
This diff is collapsed.
......@@ -25,7 +25,10 @@ This file is part of the QGROUNDCONTROL project
#define SLUGSMAV_H
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
......@@ -36,6 +39,88 @@ public:
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS
private:
void emitGpsSignals (void);
void emitPidSignal(void);
int uasId;
#endif // if SLUGS
};
#endif // SLUGSMAV_H
......@@ -637,12 +637,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_THROTTLE_LEN; ++i)
throttle << radioMsg.throttle[i];
QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron,
elevator,
rudder,
gyro,
pitch,
throttle);
QPointer<RadioCalibrationData> radioData = new RadioCalibrationData(aileron, elevator, rudder, gyro, pitch, throttle);
emit radioCalibrationReceived(radioData);
delete radioData;
}
......
......@@ -391,6 +391,11 @@ signals:
* @param fix 0: No IR/Ultrasound sensor, N > 0: Found N active sensors
*/
void irUltraSoundLocalizationChanged(UASInterface* uas, int fix);
};
Q_DECLARE_INTERFACE(UASInterface, "org.qgroundcontrol/1.0");
......
......@@ -154,6 +154,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;
......@@ -295,6 +296,7 @@ void UASWaypointManager::addWaypoint(Waypoint *wp)
{
wp->setId(waypoints.size());
waypoints.insert(waypoints.size(), wp);
emit waypointListChanged();
}
}
......@@ -384,7 +386,20 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
}
file.close();
emit loadWPFile();
emit waypointListChanged();
}
void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
{
}
int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
{
return 0;
}
void UASWaypointManager::clearWaypointList()
......@@ -405,6 +420,7 @@ void UASWaypointManager::clearWaypointList()
void UASWaypointManager::readWaypoints()
{
emit readGlobalWPFromUAS(true);
if(current_state == WP_IDLE)
{
while(waypoints.size()>0)
......@@ -412,6 +428,7 @@ void UASWaypointManager::readWaypoints()
Waypoint *t = waypoints.back();
delete t;
waypoints.pop_back();
}
protocol_timer.start(PROTOCOL_TIMEOUT_MS);
......@@ -423,6 +440,7 @@ void UASWaypointManager::readWaypoints()
current_partner_compid = MAV_COMP_ID_WAYPOINTPLANNER;
sendWaypointRequestList();
}
}
......@@ -532,6 +550,7 @@ void UASWaypointManager::sendWaypointCount()
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
emit updateStatusString(QString("start transmitting waypoints..."));
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
......@@ -556,6 +575,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)
......
......@@ -91,6 +91,19 @@ public:
void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void localAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int localRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void localMoveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void localSaveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void localLoadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
/*@}*/
/** @name Global waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getGlobalWaypointList(void) { return waypoints; } ///< Returns a const reference to the global waypoint list.
void globalAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int globalRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
/*@}*/
private:
......@@ -113,6 +126,9 @@ signals:
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
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
quint32 current_retries; ///< The current number of retries left
......
This diff is collapsed.
......@@ -64,8 +64,16 @@ This file is part of the QGROUNDCONTROL project
#include "QGCDataPlot2D.h"
#include "QGCRemoteControlView.h"
#include "QGCGoogleEarthView.h"
//#include "QMap3DWidget.h"
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsPIDControl.h"
#include "slugshilsim.h"
#include "SlugsVideoCamControl.h"
/**
* @brief Main Application Window
......@@ -188,6 +196,11 @@ protected:
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsPIDControlWidget;
QPointer<QDockWidget> slugsHilSimWidget;
QPointer<QDockWidget> slugsCamControlWidget;
// Popup widgets
JoystickWidget* joystickWidget;
......
......@@ -84,6 +84,7 @@
<addaction name="actionShow_data_analysis_view"/>
<addaction name="actionShow_full_view"/>
<addaction name="actionStyleConfig"/>
<addaction name="actionShow_Slugs_View"/>
</widget>
<widget class="QMenu" name="menuHelp">
<property name="title">
......@@ -338,6 +339,15 @@
<string>Google Earth View</string>
</property>
</action>
<action name="actionShow_Slugs_View">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/contrib/slugs.png</normaloff>:/images/contrib/slugs.png</iconset>
</property>
<property name="text">
<string>Show Slugs View</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -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);
}
......@@ -340,10 +357,19 @@ void MapWidget::createPathButtonClicked(bool checked)
}
/**
* Captures a click on the map and if in create WP path mode, it adds the WP on MouseButtonRelease
*
* @param event The mouse event
* @param coordinate The coordinate in which it occured the mouse event
* @note This slot is connected to the mouseEventCoordinate of the QMapControl object
*/
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate)
{
qDebug() << mc->mouseMode();
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
{
// Create waypoint name
......@@ -381,13 +407,27 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
{
if (!wpExists(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
CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
//CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
......@@ -395,14 +435,27 @@ 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
// emit captureMapCoordinateClick(coordinate);
}
int MapWidget::wpExists(const QPointF coordinate){
for (int i = 0; i < wps.size(); i++){
if (wps.at(i)->latitude() == coordinate.y() &&
wps.at(i)->longitude()== coordinate.x()){
return 1;
}
}
return 0;
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
{
Q_UNUSED(geom);
......@@ -414,7 +467,7 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
{
Q_UNUSED(coordinate);
waypointIsDrag = true;
......@@ -445,13 +498,15 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{
waypointIsDrag = false;
// TODO: Investigate why when creating the waypoint path this slot is being called
// Only change the mouse mode back to panning when not creating a WP path
if (!createPath->isChecked()){
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning);
}
// qDebug() << geom->name();
// qDebug() << geom->GeometryType;
// qDebug() << point;
}
MapWidget::~MapWidget()
......@@ -580,6 +635,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)
......@@ -669,3 +728,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
......@@ -107,13 +119,15 @@ protected:
protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
void createWaypointGraphAtMap (const QPointF coordinate);
void createPathButtonClicked(bool checked);
void captureGeometryClick(Geometry*, QPoint);
void mapproviderSelected(QAction* action);
void captureGeometryDrag(Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(Geometry* geom, QPointF coordinate);
void createPathButtonClicked(bool checked);
void createWaypointGraphAtMap (const QPointF coordinate);
void mapproviderSelected(QAction* action);
......@@ -130,7 +144,16 @@ private:
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
int wpExists(const QPointF coordinate);
bool waypointIsDrag;
qmapcontrol::LineString* camLine;
QList<qmapcontrol::Point*> camPoints;
QPointF lastCamBorderPos;
bool drawCamBorder;
int radioCamera;
};
#endif // MAPWIDGET_H
This diff is collapsed.
/*=====================================================================
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 Grpahical presentation of SLUGS generated data
*
* @author Juan F. Robles <jfroblesc@gmail.com>
*
*/
#ifndef SLUGSDATASENSORVIEW_H
#define SLUGSDATASENSORVIEW_H
#include <QWidget>
#include "UASInterface.h"
#include "SlugsMAV.h"
#include "mavlink.h"
namespace Ui {
class SlugsDataSensorView;
}
class SlugsDataSensorView : public QWidget
{
Q_OBJECT
public:
explicit SlugsDataSensorView(QWidget *parent = 0);
~SlugsDataSensorView();
public slots:
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets. If
* there is no current UAS active, it sets it as active.
* @param uas The UAS being added
*/
void addUAS(UASInterface* uas);
/**
* @brief Sets the UAS as active
*
* @param uas The UAS being set as active
*/
void setActiveUAS(UASInterface* uas);
void slugRawDataChanged (int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
*/
void slugLocalPositionChanged(UASInterface* uas,
double x,
double y,
double z,
quint64 time);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
*/
void slugSpeedLocalPositionChanged(UASInterface* uas,
double vx,
double vy,
double vz,
quint64 time);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
*/
void slugAttitudeChanged(UASInterface* uas,
double slugroll,
double slugpitch,
double slugyaw,
quint64 time);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
*/
void slugsGlobalPositionChanged(UASInterface* uas,
double lat,
double lon,
double alt,
quint64 time);
/**
* @brief Updates the sensor bias widget
*/
void slugsSensorBiasChanged(int systemId,
const mavlink_sensor_bias_t& sensorBias);
/**
* @brief Updates the diagnostic widget
*/
void slugsDiagnosticMessageChanged(int systemId,
const mavlink_diagnostic_t& diagnostic);
/**
* @brief Updates the CPU load widget
*/
void slugsCpuLoadChanged(int systemId,
const mavlink_cpu_load_t& cpuLoad);
/**
* @brief Updates the Navigation widget
*/
void slugsNavegationChanged(int systemId,
const mavlink_slugs_navigation_t& slugsNavigation);
/**
* @brief Updates the Data Log widget
*/
void slugsDataLogChanged(int systemId,
const mavlink_data_log_t& dataLog);
/**
* @brief Updates the PWM Commands widget
*/
void slugsPWMChanged(int systemId,
const mavlink_pwm_commands_t& pwmCommands);
/**
* @brief Updates the filtered sensor measurements widget
*/
void slugsFilteredDataChanged(int systemId,
const mavlink_filtered_data_t& filteredData);
/**
* @brief Updates the gps Date Time widget
*/
void slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime);
#endif // MAVLINK_ENABLED_SLUGS
protected:
UASInterface* activeUAS;
private:
Ui::SlugsDataSensorView *ui;
};
#endif // SLUGSDATASENSORVIEW_H
This diff is collapsed.
This diff is collapsed.
#ifndef SLUGSPIDCONTROL_H
#define SLUGSPIDCONTROL_H
#include <QWidget>
#include<QGroupBox>
#include "UASInterface.h"
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
#include "mavlink.h"
#include <QTimer>
#include <QMutex>
namespace Ui {
class SlugsPIDControl;
}
class SlugsPIDControl : public QWidget
{
Q_OBJECT
public:
explicit SlugsPIDControl(QWidget *parent = 0);
~SlugsPIDControl();
public slots:
/**
* @brief Called when the a new UAS is set to active.
*
* Called when the a new UAS is set to active.
*
* @param uas The new active UAS
*/
void activeUasSet(UASInterface* uas);
/**
*/
void setRedColorStyle();
/**
* @brief Set color StyleSheet GREEN
*
* @param
*/
void setGreenColorStyle();
/**
* @brief Connect Set pushButtons to change the color GroupBox
*
* @param
*/
void connect_set_pushButtons();
/**
* @brief Connect Set pushButtons to change the color GroupBox
*
* @param
*/
void connect_get_pushButtons();
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void connect_editLinesPDIvalues();
/**
* @brief send a PDI request message to UAS
*
* @param
*/
void sendMessagePIDStatus(int PIDtype);
// Fuctions for Air Speed GroupBox
/**
* @brief Change color style to red when PID values of Air Speed are edited
*
*
* @param
*/
void changeColor_RED_AirSpeed_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Air Speed are send to UAS
*
* @param
*/
void changeColor_GREEN_AirSpeed_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT changeColor_RED_AirSpeed_groupBox()
*
* @param
*/
void connect_AirSpeed_LineEdit();
/**
* @brief get message PID Air Speed(loop index = 0) from UAS
*
* @param
*/
void get_AirSpeed_PID();
// Functions for Pitch Followei GroupBox
/**
* @brief Change color style to red when PID values of Pitch Followei are edited
*
*
* @param
*/
void changeColor_RED_PitchFollowei_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Pitch Followei are send to UAS
*
* @param
*/
void changeColor_GREEN_PitchFollowei_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT PitchFlowei_groupBox
*
* @param
*/
void connect_PitchFollowei_LineEdit();
/**
* @brief get message PID Pitch Followei(loop index = 2) from UAS
*
* @param
*/
void get_PitchFollowei_PID();
// Functions for Roll Control GroupBox
/**
* @brief Change color style to red when PID values of Roll Control are edited
*
*
* @param
*/
void changeColor_RED_RollControl_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Roll Control are send to UAS
*
* @param
*/
void changeColor_GREEN_RollControl_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT RollControl_groupBox
*
* @param
*/
void connect_RollControl_LineEdit();
/**
* @brief get message PID Roll Control(loop index = 4) from UAS
*
* @param
*/
void get_RollControl_PID();
// Functions for Heigth Error GroupBox
/**
* @brief Change color style to red when PID values of Heigth Error are edited
*
*
* @param
*/
void changeColor_RED_HeigthError_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Heigth Error are send to UAS
*
* @param
*/
void changeColor_GREEN_HeigthError_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT HeigthError_groupBox
*
* @param
*/
void connect_HeigthError_LineEdit();
/**
* @brief get message PID Heigth Error(loop index = 1) from UAS
*
* @param
*/
void get_HeigthError_PID();
// Functions for Yaw Damper GroupBox
/**
* @brief Change color style to red when PID values of Yaw Damper are edited
*
*
* @param
*/
void changeColor_RED_YawDamper_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Yaw Damper are send to UAS
*
* @param
*/
void changeColor_GREEN_YawDamper_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT YawDamper_groupBox
*
* @param
*/
void connect_YawDamper_LineEdit();
/**
* @brief get message PID Yaw Damper(loop index = 3) from UAS
*
* @param
*/
void get_YawDamper_PID();
// Functions for Pitch to dT GroupBox
/**
* @brief Change color style to red when PID values of Pitch to dT are edited
*
*
* @param
*/
void changeColor_RED_Pitch2dT_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Pitch to dT are send to UAS
*
* @param
*/
void changeColor_GREEN_Pitch2dT_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT Pitch2dT_groupBox
*
* @param
*/
void connect_Pitch2dT_LineEdit();
/**
* @brief get message PID Pitch2dT(loop index = 8) from UAS
*
* @param
*/
void get_Pitch2dT_PID();
/**
* @brief get and updates the values on widget
*/
void slugsGetGeneral();
/**
* @brief Sent all values to UAS
*/
void slugsSetGeneral();
void slugsTimerStartSet();
void slugsTimerStartGet();
void slugsTimerStop();
//Create, send and get Messages PID
// void createMessagePID();
#ifdef MAVLINK_ENABLED_SLUGS
void recibeMensaje(int systemId, const mavlink_action_ack_t& action);
void receivePidValues(int systemId, const mavlink_pid_t& pidValues);
#endif // MAVLINK_ENABLED_SLUG
private:
Ui::SlugsPIDControl *ui;
UASInterface* activeUAS;
int systemId;
bool change_dT;
//Color Styles
QString REDcolorStyle;
QString GREENcolorStyle;
QString ORIGINcolorStyle;
//SlugsMav Message
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pid_t pidMessage;
mavlink_slugs_action_t actionSlugs;
#endif
QTimer* refreshTimerSet; ///< The main timer, controls the update view
QTimer* refreshTimerGet; ///< The main timer, controls the update view
int counterRefreshSet;
int counterRefreshGet;
QMutex valuesMutex;
};
#endif // SLUGSPIDCONTROL_H
This diff is collapsed.
#include "SlugsPadCameraControl.h"
#include "ui_SlugsPadCameraControl.h"
#include <QMouseEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
SlugsPadCameraControl::SlugsPadCameraControl(QWidget *parent) :
QWidget(parent), //QGraphicsView(parent),
ui(new Ui::SlugsPadCameraControl),
dragging(0)
{
ui->setupUi(this);
x1= 0;
y1 = 0;
}
SlugsPadCameraControl::~SlugsPadCameraControl()
{
delete ui;
}
void SlugsPadCameraControl::mouseMoveEvent(QMouseEvent *event)
{
emit mouseMoveCoord(event->x(),event->y());
}
void SlugsPadCameraControl::mousePressEvent(QMouseEvent *event)
{
emit mousePressCoord(event->x(),event->y());
x1 = event->x();
y1 = event->y();
}
void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event)
{
emit mouseReleaseCoord(event->x(),event->y());
getDeltaPositionPad(event->x(), event->y());
}
void SlugsPadCameraControl::paintEvent(QPaintEvent *pe)
{
Q_UNUSED(pe);
QPainter painter(this);
painter.setPen(Qt::blue);
painter.setFont(QFont("Arial", 30));
// QRectF rectangle(tL.x(), tL.y(), ui->padCamContro_frame->width(), ui->padCamContro_frame->height());
// int startAngle = 30 * 16;
// int spanAngle = 120 * 16;
painter.drawLine(QPoint(ui->frame->width()/2,ui->frame->geometry().topLeft().y()),
QPoint(ui->frame->width()/2,ui->frame->geometry().bottomRight().y()));
painter.drawLine(QPoint(ui->frame->geometry().topLeft().x(),ui->frame->height()/2),
QPoint(ui->frame->geometry().bottomRight().x(),ui->frame->height()/2));
// painter.drawLine(QPoint());
//painter.drawLines(padLines);
// painter.drawPie(rectangle, startAngle, spanAngle);
//painter.drawText(rect(), Qt::AlignCenter, "Qt");
}
void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
QString dir = "nd";
QPointF localMeasures = ObtenerMarcacionDistanciaPixel(y1,x1,y2,x2);
double bearing = localMeasures.x();
double dist = getDistPixel(y1,x1,y2,x2);
if(((bearing > 330)&&(bearing < 360)) || ((bearing >= 0)&&(bearing <= 30)))
{
emit dirCursorText("up");
//bearing = 315;
dir = "up";
}
else
{
if((bearing > 30)&&(bearing <= 60) )
{
emit dirCursorText("right up");
//bearing = 315;
dir = "riht up";
}
else
{
if((bearing > 60)&&(bearing <= 105) )
{
emit dirCursorText("right");
//bearing = 315;
dir = "riht";
}
else
{
if((bearing > 105)&&(bearing <= 150) )
{
emit dirCursorText("right down");
//bearing = 315;
dir = "riht down";
}
else
{
if((bearing > 150)&&(bearing <= 195) )
{
emit dirCursorText("down");
//bearing = 315;
dir = "down";
}
else
{
if((bearing > 195)&&(bearing <= 240) )
{
emit dirCursorText("left down");
//bearing = 315;
dir = "left down";
}
else
{
if((bearing > 240)&&(bearing <= 300) )
{
emit dirCursorText("left");
//bearing = 315;
dir = "left";
}
else
{
if((bearing > 300)&&(bearing <= 330) )
{
emit dirCursorText("left up");
//bearing = 315;
dir = "left up";
}
}
}
}
}
}
}
}
emit changeCursorPosition(bearing, dist, dir);
}
double SlugsPadCameraControl::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 SlugsPadCameraControl::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;
// this only convert real bearing to frame widget bearing
marcacion = marcacion +90;
if(marcacion>= 360) marcacion = marcacion - 360;
return QPointF(marcacion,distancia);
}
#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);
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;
};
#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>
#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)
//dragging(0)
{
ui->setupUi(this);
// x1= 0;
// y1 = 0;
connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
// tL = ui->padCamContro_frame->frameGeometry().topLeft();
// bR = ui->padCamContro_frame->frameGeometry().bottomRight();
//ui->padCamContro_frame->setVisible(true);
// // create a layout for camera pad
// QGridLayout* padCameraLayout = new QGridLayout(this);
// padCameraLayout->setSpacing(2);
// padCameraLayout->setMargin(0);
// padCameraLayout->setAlignment(Qt::AlignTop);
//ui->padCamContro_frame->setLayout(padCameraLayout);
// create a camera pad widget
//test = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
//test->setMaximumWidth(50);
//ui->gridLayout->addWidget(test, 0,0);
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)));
//padCamera->setVisible(true);
// padCameraLayout->addWidget(padCamera);
// QGraphicsScene *scene = new QGraphicsScene(ui->CamControlPanel_graphicsView);
// scene->setItemIndexMethod(QGraphicsScene::NoIndex);
// scene->setSceneRect(-200, -200, 400, 400);
// setScene(scene);
// setCacheMode(CacheBackground);
// setViewportUpdateMode(BoundingRectViewportUpdate);
// setRenderHint(QPainter::Antialiasing);
// setTransformationAnchor(AnchorUnderMouse);
// setResizeAnchor(AnchorViewCenter);
// ui->CamControlPanel_graphicsView->installEventFilter(this);
// ui->label_x->installEventFilter(this);
}
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:
void changeViewCamBorderAtMapStatus(bool status);
void getDeltaPositionPad(double dir, double dist, QString dirText);
void mousePadPressEvent(int x, int y);
void mousePadReleaseEvent(int x, int y);
void mousePadMoveEvent(int x, int y);
signals:
void changeCamPosition(double dist, double dir, QString textDir);
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="QGridLayout" name="gridLayout">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QLabel" name="label_x">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<string>Coord_X</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_y">
<property name="mouseTracking">
<bool>true</bool>
</property>
<property name="text">
<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="1" 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>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
......@@ -88,6 +88,8 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
updateStatusLabel("");
this->setVisible(false);
loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
......@@ -128,6 +130,9 @@ void WaypointList::setUAS(UASInterface* uas)
connect(&uas->getWaypointManager(), SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
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)));
}
}
......@@ -144,6 +149,8 @@ void WaypointList::loadWaypoints()
{
if (uas)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
uas->getWaypointManager().loadWaypoints(fileName);
}
......@@ -242,6 +249,8 @@ void WaypointList::addCurrentPositonWaypoint()
void WaypointList::updateStatusLabel(const QString &string)
{
m_ui->statusLabel->setText(string);
}
void WaypointList::changeCurrentWaypoint(quint16 seq)
......@@ -388,7 +397,7 @@ void WaypointList::waypointListChanged()
}
loadFileGlobalWP = false;
}
......@@ -462,15 +471,23 @@ void WaypointList::changeEvent(QEvent *e)
void WaypointList::on_clearWPListButton_clicked()
{
if (uas)
{
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
else
{
// if(isGlobalWP)
// {
// emit clearPathclicked();
// }
}
}
......@@ -534,14 +551,24 @@ void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
void WaypointList::clearWPWidget()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
if (uas)
{
const QVector<Waypoint *> &waypoints = uas->getWaypointManager().getWaypointList();
while(!waypoints.isEmpty())//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView* widget = wpViews.find(waypoints[0]).value();
widget->remove();
}
}
//emit changePositionWPBySpinBox(wp->getId(), wp->getY(), wp->getX());
}
void WaypointList::setIsLoadFileWP()
{
loadFileGlobalWP = true;
}
void WaypointList::setIsReadGlobalWP(bool value)
{
// readGlobalWP = value;
}
......@@ -65,7 +65,7 @@ public slots:
/** @brief Save the local waypoint list to a file */
void saveWaypoints();
/** @brief Load a waypoint list from a file */
void loadWaypoints();
void loadWaypoints();
/** @brief Transmit the local waypoint list to the UAS */
void transmit();
/** @brief Read the remote waypoint list */
......@@ -102,6 +102,9 @@ public slots:
void moveDown(Waypoint* wp);
void removeWaypoint(Waypoint* wp);
void setIsLoadFileWP();
void setIsReadGlobalWP(bool value);
......@@ -126,6 +129,8 @@ protected:
double mavZ;
double mavYaw;
QPointF centerMapCoordinate;
bool loadFileGlobalWP;
bool readGlobalWP;
private:
Ui::WaypointList *m_ui;
......
......@@ -54,7 +54,9 @@ void Linecharts::addSystem(UASInterface* uas)
LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this);
addWidget(widget);
plots.insert(uas->getUASID(), widget);
#ifndef MAVLINK_ENABLED_SLUGS
connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64)));
#endif
connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString)));
// Set system active if this is the only system
if (active)
......
This diff is collapsed.
/*=====================================================================
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 the configuration Window for Slugs' HIL Simulator
* @author Mariano Lizarraga <malife@gmail.com>
*/
#ifndef SLUGSHILSIM_H
#define SLUGSHILSIM_H
#include <QWidget>
#include <QHostAddress>
#include <QUdpSocket>
#include <QMessageBox>
#include "LinkInterface.h"
#include "UAS.h"
#include <stdint.h>
namespace Ui {
class SlugsHilSim;
}
class SlugsHilSim : public QWidget
{
Q_OBJECT
public:
explicit SlugsHilSim(QWidget *parent = 0);
~SlugsHilSim();
protected:
LinkInterface* hilLink;
QHostAddress* simulinkIp;
QUdpSocket* txSocket;
QUdpSocket* rxSocket;
UAS* activeUas;
public slots:
/**
* @brief Adds a link to the combo box listing so the user can select a link
*
* Populates the Combo box that allows the user to select the link with which Slugs will
* receive the simulated sensor data from Simulink
*
* @param theLink the link that is being added to the combo box
*/
void addToCombo(LinkInterface* theLink);
/**
* @brief Puts Slugs in HIL Mode
*
* Sends the required messages through the main communication link to set Slugs in HIL Mode
*
*/
void putInHilMode(void);
/**
* @brief Receives a datagram from Simulink containing the sensor data.
*
* Receives a datagram from Simulink containing the simulated sensor data. This data is then
* forwarded to Slugs to use as input to the attitude estimation and navigation algorithms.
*
*/
void readDatagram(void);
/**
* @brief Called when the a new UAS is set to active.
*
* Called when the a new UAS is set to active.
*
* @param uas The new active UAS
*/
void activeUasSet(UASInterface* uas);
/**
* @brief Called when the Link combobox selects a new link.
*
* @param uas The new index of the selected link
*/
void linkSelected (int cbIndex);
public slots:
private:
typedef union _tFloatToChar {
unsigned char chData[4];
float flData;
} tFloatToChar;
typedef union _tUint16ToChar {
unsigned char chData[2];
uint16_t uiData;
} tUint16ToChar;
Ui::SlugsHilSim *ui;
QHash <int, LinkInterface*> linksAvailable;
void processHilDatagram (const QByteArray* datagram);
float getFloatFromDatagram (const QByteArray* datagram, unsigned char * i);
uint16_t getUint16FromDatagram (const QByteArray* datagram, unsigned char * i);
};
#endif // SLUGSHILSIM_H
This diff is collapsed.
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