Commit 3ad00a0d authored by pixhawk's avatar pixhawk

Merge branch 'master' of pixhawk.ethz.ch:qgroundcontrol

parents 6641fcad 15caabd1
......@@ -24,3 +24,4 @@ doc/doxy.log
deploy/mac
deploy/linux
controller_log*
user_config.pri
This diff is collapsed.
......@@ -97,6 +97,36 @@ namespace qmapcontrol
geometries.clear();
}
Geometry* Layer::get_Geometry(int index)
{
if(geometrySelected)
{
return geometrySelected;
}
else
{
for(int i = 0; i <= geometries.size(); i++)
{
Geometry *geometry = geometries[i];
if(geometry->name() == QString::number(index))
{
return geometry;
}
}
// foreach(Geometry *geometry, geometries)
// {
// if(geometry->name() == QString::number(index))
// {
// return geometry;
// }
// }
}
}
bool Layer::isVisible() const
{
return visible;
......@@ -323,3 +353,5 @@ namespace qmapcontrol
mapAdapter = mapadapter;
}
}
......@@ -200,6 +200,12 @@ namespace qmapcontrol
*/
void setVisible(bool visible);
//! get geometry selected by index
/*!
* @param index of geometry selected
*/
Geometry* get_Geometry(int index);
};
}
#endif
......@@ -309,6 +309,7 @@ namespace qmapcontrol
click.y()-screen_middle.y()+layermanager->getMapmiddle_px().y());
// image coordinate to world coordinate
return layermanager->layer()->mapadapter()->displayToCoordinate(displayToImage);
}
void MapControl::updateRequest(QRect rect)
......
#-------------------------------------------------
#
# MAVGround - Micro Air Vehicle Groundstation
#
# QGroundControl - Micro Air Vehicle Groundstation
#
# Please see our website at <http://qgroundcontrol.org>
#
# Original Author:
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
#
# Contributing Authors (in alphabetical order):
#
# (c) 2009 PIXHAWK Team
# (c) 2009-2010 PIXHAWK Team
#
# This file is part of the mav groundstation project
# MAVGround is free software: you can redistribute it and/or modify
# 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.
# MAVGround is distributed in the hope that it will be useful,
# 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 MAVGround. If not, see <http://www.gnu.org/licenses/>.
# along with QGroundControl. If not, see <http://www.gnu.org/licenses/>.
#
#-------------------------------------------------
......
#-------------------------------------------------
#
# QGroundControl - Micro Air Vehicle Groundstation
#
# Please see our website at <http://qgroundcontrol.org>
#
# Author:
# Lorenz Meier <mavteam@student.ethz.ch>
#
# (c) 2009-2010 PIXHAWK Team
#
# This file is part of the mav groundstation 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/>.
#
#-------------------------------------------------
# Include QMapControl map library
# prefer version from external directory /
# from http://github.com/pixhawk/qmapcontrol/
......@@ -5,6 +31,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")
......@@ -24,6 +51,39 @@ OBJECTS_DIR = $$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated
MAVLINK_CONF = ""
exists(user_config.pri) {
message("----- USING USER QGROUNDCONTROL CONFIG FROM user_config.pri -----")
include(user_config.pri)
}
INCLUDEPATH += $$BASEDIR/../mavlink/include/common
contains(MAVLINK_CONF, pixhawk) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# PIXHAWK SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/pixhawk
DEFINES += QGC_USE_PIXHAWK_MESSAGES
}
contains(MAVLINK_CONF, slugs) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# SLUGS SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/slugs
DEFINES += QGC_USE_SLUGS_MESSAGES
}
contains(MAVLINK_CONF, ualberta) {
# Remove the default set - it is included anyway
INCLUDEPATH -= $$BASEDIR/../mavlink/include/common
# UALBERTA SPECIAL MESSAGES
INCLUDEPATH += $$BASEDIR/../mavlink/include/ualberta
DEFINES += QGC_USE_UALBERTA_MESSAGES
}
# }
# Include general settings for MAVGround
# necessary as last include to override any non-acceptable settings
......@@ -42,7 +102,6 @@ DEPENDPATH += . \
plugins
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/contrib/slugs/include \
$$BASEDIR/../mavlink/include
# ../mavlink/include \
......@@ -159,8 +218,13 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/CheetahModel.h \
src/ui/map3D/CheetahGL.h \
......@@ -169,7 +233,8 @@ HEADERS += src/MG.h \
src/ui/map3D/TextureCache.h \
src/ui/map3D/WebImage.h \
src/ui/map3D/WebImageCache.h \
src/ui/map3D/Imagery.h
src/ui/map3D/Imagery.h \
src/comm/QGCMAVLink.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -233,8 +298,13 @@ SOURCES += src/main.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/WaypointGlobal.cpp \
src/ui/WaypointGlobalView.cpp \
src/ui/RadioCalibration/RadioCalibrationWindow.cc \
src/ui/RadioCalibration/AirfoilServoCalibrator.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/WaypointGlobalView.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/CheetahModel.cc \
src/ui/map3D/CheetahGL.cc \
......@@ -247,7 +317,7 @@ SOURCES += src/main.cc \
RESOURCES = mavground.qrc
# Include RT-LAB Library
win32:exists(src/lib/opalrt/OpalApi.h) {
win32:exists(src/lib/opalrt/OpalApi.h):exists(C:\OPAL-RT\RT-LAB7.2.4\Common\bin) {
message("Building support for Opal-RT")
LIBS += -LC:\OPAL-RT\RT-LAB7.2.4\Common\bin \
-lOpalApi
......
......@@ -2,9 +2,9 @@
<!-- Parameters in the top level block -->
<Block name="TopLevel">
<Parameter>
</Parameter>
</Block>
<!--Parameters related to the navigation block -->
......@@ -23,6 +23,117 @@
<!-- Paremters for the Pilot Input/Raw RC block -->
<Block name="ServoInputs">
<!-- Settings for Aileron Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="AIL_RIGHT_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="AIL_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/AileronInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="AIL_LEFT_IN"
/>
<!-- Settings for Elevator Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="ELE_DOWN_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="ELE_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ElevatorInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="ELE_UP_IN"
/>
<!-- Settings for Throttle Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="THR_SET0_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="THR_SET1_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="THR_SET2_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint3"
QGCParamID="THR_SET3_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/ThrottleInput/"
SimulinkParameterName="Setpoint4"
QGCParamID="THR_SET4_IN"
/>
<!-- Settings for Rudder Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="RUD_LEFT_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="RUD_CENTER_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/RudderInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="RUD_RIGHT_IN"
/>
<!-- Settings for Gyro Mode/Gain Switch -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/GyroInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="GYRO_DEF_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/GyroInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="GYRO_TOG_IN"
/>
<!-- Settings for Pitch Servo -->
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint0"
QGCParamID="PIT_SET0_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint1"
QGCParamID="PIT_SET1_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint2"
QGCParamID="PIT_SET2_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint3"
QGCParamID="PIT_SET3_IN"
/>
<Parameter
SimulinkPath="avionics_src/sm_avionics/Pilot_Inputs/PitchInput/"
SimulinkParameterName="Setpoint4"
QGCParamID="PIT_SET4_IN"
/>
</Block>
......
<!-- Values are ordered low center high -->
<channels>
<threeSetpoint name="Aileron" number="1">1000.0, 1500.0, 2000.0</threeSetpoint>
<threeSetpoint name="Elevator" number="2">1000.0, 1500.0, 2000.0</threeSetpoint>
<threeSetpoint name="Rudder" number="4">1000.0, 1500.0, 2000.0</threeSetpoint>
<twoSetpoint name="Gyro" number="5">2000.0, 1000.0</twoSetpoint>
<fiveSetpoint name="Pitch" number="6">1000.0, 1250.0, 1500.0, 1750.0, 2000.0</fiveSetpoint>
<fiveSetpoint name="Throttle" number="3">1000.0, 1250.0, 1500.0, 1750.0, 2000.0</fiveSetpoint>
</channels>
......@@ -81,6 +81,7 @@ public slots:
void setOrbit(float orbit);
void setHoldTime(int holdTime);
//for QDoubleSpin
void setX(double x);
void setY(double y);
......
#include "WaypointGlobal.h"
#include <QPointF>
WaypointGlobal::WaypointGlobal(const QPointF coordinate):
Waypoint(id, x, y, z, yaw, autocontinue, current, orbit, holdTime)
{
coordinateWP = coordinate;
}
#ifndef WAYPOINTGLOBAL_H
#define WAYPOINTGLOBAL_H
#include "Waypoint.h"
#include <QPointF>
class WaypointGlobal: public Waypoint {
Q_OBJECT
public:
WaypointGlobal(const QPointF coordinate);
public slots:
// void set_latitud(double latitud);
// void set_longitud(double longitud);
// double get_latitud();
// double get_longitud();
private:
QPointF coordinateWP;
};
#endif // WAYPOINTGLOBAL_H
......@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
......
......@@ -45,7 +45,7 @@ This file is part of the QGROUNDCONTROL project
#include "ArduPilotMAV.h"
#include "configuration.h"
#include "LinkManager.h"
#include <mavlink.h>
#include <QGCMAVLink.h>
#include "QGC.h"
/**
......
......@@ -39,8 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QByteArray>
#include "ProtocolInterface.h"
#include "LinkInterface.h"
#include "protocol.h"
#include "mavlink.h"
#include "QGCMAVLink.h"
/**
* @brief MAVLink micro air vehicle protocol reference implementation.
......
......@@ -41,7 +41,7 @@ This file is part of the QGROUNDCONTROL project
#include "MAVLinkProtocol.h"
#include "MAVLinkSimulationLink.h"
// MAVLINK includes
#include <mavlink.h>
#include <QGCMAVLink.h>
#include "QGC.h"
/**
......@@ -100,9 +100,10 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
mavlinkLogFile = new QFile(MAVLinkProtocol::getLogfileName());
mavlinkLogFile->open(QIODevice::ReadOnly);
x = 0;
y = 0;
z = 0;
// position at Pixhawk lab @ ETHZ
x = 5247273.0f;
y = 465955.0f;
z = -0.2f;
yaw = 0;
}
......@@ -181,7 +182,7 @@ void MAVLinkSimulationLink::mainloop()
mavlink_attitude_t attitude;
memset(&attitude, 0, sizeof(mavlink_attitude_t));
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_raw_aux_t rawAuxValues;
memset(&rawAuxValues, 0, sizeof(mavlink_raw_aux_t));
#endif
......@@ -304,7 +305,7 @@ void MAVLinkSimulationLink::mainloop()
{
rawImuValues.zgyro = d;
}
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
if (keys.value(i, "") == "Pressure")
{
rawAuxValues.baro = d;
......@@ -376,22 +377,20 @@ void MAVLinkSimulationLink::mainloop()
{
rate10hzCounter = 1;
// Move X Position
x += sin(QGC::groundTimeUsecs()*1000) * 0.05f;
y += sin(QGC::groundTimeUsecs()) * 0.05f;
z += sin(QGC::groundTimeUsecs()) * 0.009f;
x = (x > 5.0f) ? 5.0f : x;
y = (y > 5.0f) ? 5.0f : y;
z = (z > 3.0f) ? 3.0f : z;
x = (x < -5.0f) ? -5.0f : x;
y = (y < -5.0f) ? -5.0f : y;
z = (z < -3.0f) ? -3.0f : z;
// position at Pixhawk lab @ ETHZ
x += 5247273.0f;
y += 465955.0f;
// Move X Position
x = x*0.93f + 0.07f*(x+sin(QGC::groundTimeUsecs()) * 0.08f);
y = y*0.93f + 0.07f*(y+sin(QGC::groundTimeUsecs()) * 0.5f);
z = z*0.93f + 0.07f*(z+sin(QGC::groundTimeUsecs()*100000) * 0.1f);
// x = (x > 5.0f) ? 5.0f : x;
// y = (y > 5.0f) ? 5.0f : y;
// z = (z > 3.0f) ? 3.0f : z;
//
// x = (x < -5.0f) ? -5.0f : x;
// y = (y < -5.0f) ? -5.0f : y;
// z = (z < -3.0f) ? -3.0f : z;
// Send back new setpoint
mavlink_message_t ret;
......@@ -402,7 +401,7 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// Send back new position
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, x, y, z, 0, 0, 0);
mavlink_msg_local_position_pack(systemId, componentId, &ret, 0, y+z, y, -fabs(z), 0, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......@@ -469,7 +468,7 @@ void MAVLinkSimulationLink::mainloop()
static int detectionCounter = 6;
if (detectionCounter % 10 == 0)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_pattern_detected_t detected;
detected.confidence = 5.0f;
......@@ -583,7 +582,7 @@ void MAVLinkSimulationLink::mainloop()
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
#endif
......@@ -620,7 +619,7 @@ void MAVLinkSimulationLink::mainloop()
//qDebug() << "BOOT" << "BUF LEN" << bufferlength << "POINTER" << streampointer;
// AUX STATUS
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
rawAuxValues.vbat = voltage;
#endif
......@@ -761,14 +760,12 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
}
}
break;
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_MANUAL_CONTROL:
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_manual_control_t control;
mavlink_msg_manual_control_decode(&msg, &control);
qDebug() << "\n" << "ROLL:" << control.roll << "PITCH:" << control.pitch;
#endif
}
break;
#endif
......
......@@ -39,7 +39,7 @@ This file is part of the QGROUNDCONTROL project
#include <QMutex>
#include <QMap>
#include <inttypes.h>
#include <mavlink.h>
#include "QGCMAVLink.h"
#include "LinkInterface.h"
......
......@@ -71,7 +71,13 @@ bool MAVLinkXMLParser::generate()
bool success = true;
// Only generate if output dir is correctly set
if (outputDirName == "") return false;
if (outputDirName == "")
{
emit parseState(tr("<font color=\"red\">ERROR: No output directory given.\nAbort.</font>"));
return false;
}
QString topLevelOutputDirName = outputDirName;
// print out the element names of all elements that are direct children
// of the outermost element.
......@@ -87,6 +93,31 @@ bool MAVLinkXMLParser::generate()
QString lcmStructDefs = "";
QString pureFileName;
QString pureIncludeFileName;
QFileInfo fInfo(this->fileName);
pureFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first();
// XML parsed and converted to C code. Now generating the files
outputDirName += QDir::separator() + pureFileName;
QDateTime now = QDateTime::currentDateTime().toUTC();
QLocale loc(QLocale::English);
QString dateFormat = "dddd, MMMM d yyyy, hh:mm UTC";
QString date = loc.toString(now, dateFormat);
QString includeLine = "#include \"%1\"\n";
QString mainHeaderName = pureFileName + ".h";
QString messagesDirName = ".";//"generated";
QDir dir(outputDirName + "/" + messagesDirName);
// Start main header
QString mainHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef " + pureFileName.toUpper() + "_H\n#define " + pureFileName.toUpper() + "_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mainHeader += "#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n";
mainHeader += "\n#include \"../protocol.h\"\n";
mainHeader += "\n#define MAVLINK_ENABLED_" + pureFileName.toUpper() + "\n\n";
// Run through root children
while(!n.isNull())
......@@ -107,47 +138,55 @@ bool MAVLinkXMLParser::generate()
// Handle all include tags
if (e.tagName() == "include")
{
QString fileName = e.text();
QString incFileName = e.text();
// Load file
QDomDocument includeDoc = QDomDocument();
//QDomDocument includeDoc = QDomDocument();
// Prepend file path if it is a relative path and
// make it relative to opened file
QFileInfo fInfo(fileName);
QFileInfo fInfo(incFileName);
QString incFilePath;
if (fInfo.isRelative())
{
QFileInfo rInfo(this->fileName);
fileName = rInfo.absoluteDir().canonicalPath() + "/" + fileName;
pureFileName = rInfo.baseName().split(".").first();
incFilePath = rInfo.absoluteDir().canonicalPath() + "/" + incFileName;
pureIncludeFileName = fInfo.baseName().split(".", QString::SkipEmptyParts).first();
}
QFile file(fileName);
QFile file(incFilePath);
if (file.open(QIODevice::ReadOnly | QIODevice::Text))
{
const QString instanceText(QString::fromUtf8(file.readAll()));
includeDoc.setContent(instanceText);
// Get all messages
QDomNode in = includeDoc.documentElement().firstChild();
//while (!in.isNull())
//{
QDomElement ie = in.toElement();
if (!ie.isNull())
{
if (ie.tagName() == "messages" || ie.tagName() == "include")
{
QDomNode ref = n.parentNode().insertAfter(in, n);
if (ref.isNull())
{
emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName));
return false;
}
}
}
//in = in.nextSibling();
//}
emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(fileName));
emit parseState(QString("<font color=\"green\">Included messages from file: %1</font>").arg(incFileName));
// NEW MODE: CREATE INDIVIDUAL FOLDERS
// Create new output directory, parse included XML and generate C-code
MAVLinkXMLParser includeParser(incFilePath, topLevelOutputDirName, this);
connect(&includeParser, SIGNAL(parseState(QString)), this, SIGNAL(parseState(QString)));
// Generate and write
includeParser.generate();
mainHeader += "\n#include \"../" + pureIncludeFileName + "/" + pureIncludeFileName + ".h\"\n";
// OLD MODE: MERGE BOTH FILES
// const QString instanceText(QString::fromUtf8(file.readAll()));
// includeDoc.setContent(instanceText);
// // Get all messages
// QDomNode in = includeDoc.documentElement().firstChild();
// QDomElement ie = in.toElement();
// if (!ie.isNull())
// {
// if (ie.tagName() == "messages" || ie.tagName() == "include")
// {
// QDomNode ref = n.parentNode().insertAfter(in, n);
// if (ref.isNull())
// {
// emit parseState(QString("<font color=\"red\">ERROR: Inclusion failed: XML syntax error in file %1. Wrong/misspelled XML?\nAbort.</font>").arg(fileName));
// return false;
// }
// }
// }
emit parseState(QString("<font color=\"green\">End of inclusion from file: %1</font>").arg(incFileName));
}
else
{
......@@ -406,20 +445,7 @@ bool MAVLinkXMLParser::generate()
n = n.nextSibling();
} // While through root children
// XML parsed and converted to C code. Now generating the files
QDateTime now = QDateTime::currentDateTime().toUTC();
QLocale loc(QLocale::English);
QString dateFormat = "dddd, MMMM d yyyy, hh:mm UTC";
QString date = loc.toString(now, dateFormat);
QString mainHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef MAVLINK_H\n#define MAVLINK_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mainHeader += "#ifdef __cplusplus\nextern \"C\" {\n#endif\n\n";
mainHeader += "\n#include \"protocol.h\"\n";
mainHeader += "\n#define MAVLINK_ENABLED_" + pureFileName.toUpper() + "\n\n";
QString includeLine = "#include \"%1\"\n";
QString mainHeaderName = "mavlink.h";
QString messagesDirName = "generated";
QDir dir(outputDirName + "/" + messagesDirName);
// Create directory if it doesn't exist, report result in success
if (!dir.exists()) success = success && dir.mkpath(outputDirName + "/" + messagesDirName);
for (int i = 0; i < cFiles.size(); i++)
......@@ -428,6 +454,7 @@ bool MAVLinkXMLParser::generate()
bool ok = rawFile.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
rawFile.write(cFiles.at(i).second.toLatin1());
rawFile.close();
mainHeader += includeLine.arg(messagesDirName + "/" + cFiles.at(i).first);
}
......@@ -441,6 +468,18 @@ bool MAVLinkXMLParser::generate()
bool ok = rawHeader.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
rawHeader.write(mainHeader.toLatin1());
rawHeader.close();
// Write alias mavlink header
QFile mavlinkHeader(outputDirName + "/mavlink.h");
ok = mavlinkHeader.open(QIODevice::WriteOnly | QIODevice::Text);
success = success && ok;
QString mHeader = QString("/** @file\n *\t@brief MAVLink comm protocol.\n *\t@see http://pixhawk.ethz.ch/software/mavlink\n *\t Generated on %1\n */\n#ifndef MAVLINK_H\n#define MAVLINK_H\n\n").arg(date); // The main header includes all messages
// Mark all code as C code
mHeader += "#include \"" + mainHeaderName + "\"\n\n";
mHeader += "#endif\n";
mavlinkHeader.write(mHeader.toLatin1());
mavlinkHeader.close();
// Write C structs / lcm definitions
// QFile lcmStructs(outputDirName + "/mavlink.lcm");
......
This diff is collapsed.
......@@ -43,8 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "LinkInterface.h"
#include "LinkManager.h"
#include "MG.h"
#include "mavlink.h"
#include "mavlink_types.h"
#include "QGCMAVLink.h"
#include "configuration.h"
#include "OpalRT.h"
#include "ParameterList.h"
......@@ -153,6 +152,9 @@ protected:
unsigned short opalInstID;
uint16_t duty2PulseMicros(double duty);
uint8_t rescaleNorm(double norm, int ch);
bool sendRCValues;
};
#endif // OPALLINK_H
......@@ -41,7 +41,7 @@ namespace OpalRT
Configuration info for the model
*/
const unsigned short NUM_OUTPUT_SIGNALS=57;
const unsigned short NUM_OUTPUT_SIGNALS=42;
/* ------------------------------ Outputs ------------------------------
*
......@@ -86,7 +86,7 @@ namespace OpalRT
B_W_0,
B_W_1,
B_W_2,
RAW_CHANNEL_1 = 39,
RAW_CHANNEL_1 = 24,
RAW_CHANNEL_2,
RAW_CHANNEL_3,
RAW_CHANNEL_4,
......
......@@ -32,7 +32,8 @@ using namespace OpalRT;
ParameterList::ParameterList()
:params(new QMap<int, QMap<QGCParamID, Parameter> >),
paramList(new QList<QList<Parameter*> >())
paramList(new QList<QList<Parameter*> >()),
reqdServoParams(new QStringList())
{
QDir settingsDir = QDir(qApp->applicationDirPath());
......@@ -40,40 +41,20 @@ ParameterList::ParameterList()
settingsDir.cdUp();
settingsDir.cd("settings");
// Enforce a list of parameters which are necessary for flight
reqdServoParams->append("AIL_RIGHT_IN");
reqdServoParams->append("AIL_CENTER_IN");
reqdServoParams->append("AIL_LEFT_IN");
reqdServoParams->append("ELE_DOWN_IN");
reqdServoParams->append("ELE_CENTER_IN");
reqdServoParams->append("ELE_UP_IN");
reqdServoParams->append("RUD_LEFT_IN");
reqdServoParams->append("RUD_CENTER_IN");
reqdServoParams->append("RUD_RIGHT_IN");
QString filename(settingsDir.path() + "/ParameterList.xml");
if ((QFile::exists(filename)) && open(filename))
{
/* Populate the map with parameter names. There is no elegant way of doing this so all
parameter paths and names must be known at compile time and defined here.
Note: This function is written in a way that calls a lot of copy constructors and is
therefore not particularly efficient. However since it is only called once memory
and computation time are sacrificed for code clarity when adding and modifying
parameters.
When defining the path, the trailing slash is necessary
*/
// Parameter *p;
// /* Component: Navigation Filter */
// p = new Parameter("avionics_src/sm_ampro/NAV_FILT_INIT/",
// "Value",
// OpalRT::NAV_ID,
// QGCParamID("NAV_FILT_INIT"));
// (*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p);
// delete p;
//
// p = new Parameter("avionics_src/sm_ampro/Gain/",
// "Gain",
// OpalRT::NAV_ID,
// QGCParamID("TEST_OUTP_GAIN"));
// (*params)[OpalRT::NAV_ID].insert(p->getParamID(), *p);
// delete p;
//
// /* Component: Log Facility */
// p = new Parameter("avionics_src/sm_ampro/LOG_FILE_ON/",
// "Value",
// OpalRT::LOG_ID,
// QGCParamID("LOG_FILE_ON"));
// (*params)[OpalRT::LOG_ID].insert(p->getParamID(), *p);
// delete p;
/* Get a list of the available parameters from opal-rt */
QMap<QString, unsigned short> *opalParams = new QMap<QString, unsigned short>;
......@@ -271,6 +252,8 @@ bool ParameterList::open(QString filename)
read(&paramFile);
paramFile.close();
return true;
}
......@@ -336,11 +319,25 @@ void ParameterList::parseBlock(const QDomElement &block)
static_cast<uint8_t>(id),
QGCParamID(e.attribute("QGCParamID")));
(*params)[id].insert(p->getParamID(), *p);
if (reqdServoParams->contains((QString)p->getParamID()))
reqdServoParams->removeAt(reqdServoParams->indexOf((QString)p->getParamID()));
delete p;
}
}
else
{
qDebug() << __FILE__ << ":" << __LINE__ << ": error in xml doc";
qDebug() << __FILE__ << ":" << __LINE__ << ": error in xml doc in block" << block.attribute("name");
}
}
if (!reqdServoParams->empty())
{
qDebug() << __FILE__ << __LINE__ << "Missing the following required servo parameters";
foreach(QString s, *reqdServoParams)
{
qDebug() << s;
}
}
......
......@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QDir>
#include <QApplication>
#include <QtXml>
#include <QStringList>
#include "mavlink_types.h"
#include "QGCParamID.h"
......@@ -119,6 +120,10 @@ namespace OpalRT
are made through the map container.
*/
QList<QList<Parameter*> > *paramList;
/**
List of parameters which are necessary to control the servos.
*/
QStringList *reqdServoParams;
/**
Get the list of available parameters from Opal-RT.
\param[out] opalParams Map of parameter paths/names to ids which are valid in Opal-RT
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 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 MAVLink header file for QGroundControl
* @author Lorenz Meier <pixhawk@switched.com>
*/
#ifndef QGCMAVLINK_H
#define QGCMAVLINK_H
#include <mavlink_types.h>
#include <mavlink.h>
#ifdef QGC_USE_PIXHAWK_MESSAGES
#include <pixhawk.h>
#endif
#ifdef QGC_USE_SLUGS_MESSAGES
#include <slugs.h>
#endif
#ifdef QGC_USE_UALBERTA_MESSAGES
#include <ualberta.h>
#endif
#ifdef QGC_USE_ARDUPILOT_MESSAGES
#include <ardupilot.h>
#endif
#endif // QGCMAVLINK_H
......@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 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.
PIXHAWK is distributed in the hope that it will be useful,
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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 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.
PIXHAWK is distributed in the hope that it will be useful,
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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
QGroundControl Open Source Ground Control Station
(c) 2009 - 2011 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.
PIXHAWK is distributed in the hope that it will be useful,
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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
QGroundControl Open Source Ground Control Station
(c) 2009 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
(c) 2009 - 2011 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the PIXHAWK project
This file is part of the QGROUNDCONTROL project
PIXHAWK is free software: you can redistribute it and/or modify
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.
PIXHAWK is distributed in the hope that it will be useful,
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 PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
......
......@@ -46,7 +46,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
//qDebug() << "PX RECEIVED" << msg->sysid << msg->compid << msg->msgid;
// Only compile this portion if matching MAVLink packets have been compiled
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
if (message.sysid == uasId)
{
......@@ -169,7 +169,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
void PxQuadMAV::sendProcessCommand(int watchdogId, int processId, unsigned int command)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_watchdog_command_t payload;
payload.target_system_id = uasId;
payload.watchdog_id = watchdogId;
......
......@@ -53,7 +53,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
}
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES
#ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_CPU_LOAD:
{
......
......@@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGC.h"
#include "GAudioOutput.h"
#include "MAVLinkProtocol.h"
#include <mavlink.h>
#include "QGCMAVLink.h"
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
uasId(id),
......@@ -556,7 +556,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, severity, text);
}
break;
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES
#ifdef MAVLINK_ENABLED_UALBERTA
case MAVLINK_MSG_ID_NAV_FILTER_BIAS:
{
mavlink_nav_filter_bias_t bias;
......@@ -570,6 +570,41 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "b_w[2]", bias.gyro_2, time);
}
break;
case MAVLINK_MSG_ID_RADIO_CALIBRATION:
{
mavlink_radio_calibration_t radioMsg;
mavlink_msg_radio_calibration_decode(&message, &radioMsg);
QVector<float> aileron;
QVector<float> elevator;
QVector<float> rudder;
QVector<float> gyro;
QVector<float> pitch;
QVector<float> throttle;
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_AILERON_LEN; ++i)
aileron << radioMsg.aileron[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_ELEVATOR_LEN; ++i)
elevator << radioMsg.elevator[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_RUDDER_LEN; ++i)
rudder << radioMsg.rudder[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_GYRO_LEN; ++i)
gyro << radioMsg.gyro[i];
for (int i=0; i<MAVLINK_MSG_RADIO_CALIBRATION_FIELD_PITCH_LEN; ++i)
pitch << radioMsg.pitch[i];
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);
emit radioCalibrationReceived(radioData);
delete radioData;
}
break;
#endif
default:
{
......@@ -588,7 +623,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_setpoint_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, 0, x, y, z, yaw);
sendMessage(msg);
......@@ -597,7 +632,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw)
void UAS::setLocalPositionOffset(float x, float y, float z, float yaw)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t msg;
mavlink_msg_position_control_offset_set_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, x, y, z, yaw);
sendMessage(msg);
......@@ -827,7 +862,7 @@ void UAS::readParametersFromStorage()
void UAS::enableAllDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -853,7 +888,7 @@ void UAS::enableAllDataTransmission(bool enabled)
void UAS::enableRawSensorDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -877,7 +912,7 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
void UAS::enableExtendedSystemStatusTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -901,7 +936,7 @@ void UAS::enableExtendedSystemStatusTransmission(bool enabled)
void UAS::enableRCChannelDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -920,12 +955,16 @@ void UAS::enableRCChannelDataTransmission(bool enabled)
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
#elif defined(MAVLINK_ENABLED_UALBERTA_MESSAGES)
mavlink_message_t msg;
mavlink_msg_request_rc_channels_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, enabled);
sendMessage(msg);
#endif
}
void UAS::enableRawControllerDataTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -949,7 +988,7 @@ void UAS::enableRawControllerDataTransmission(bool enabled)
void UAS::enableRawSensorFusionTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -973,7 +1012,7 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
void UAS::enablePositionTransmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -997,7 +1036,7 @@ void UAS::enablePositionTransmission(bool enabled)
void UAS::enableExtra1Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1021,7 +1060,7 @@ void UAS::enableExtra1Transmission(bool enabled)
void UAS::enableExtra2Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1045,7 +1084,7 @@ void UAS::enableExtra2Transmission(bool enabled)
void UAS::enableExtra3Transmission(bool enabled)
{
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
......@@ -1161,7 +1200,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
// if(mode == (int)MAV_MODE_MANUAL)
// {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
#ifdef MAVLINK_ENABLED_PIXHAWK
mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
sendMessage(message);
......@@ -1191,7 +1230,7 @@ void UAS::receiveButton(int buttonIndex)
break;
}
qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
// qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!";
}
......
......@@ -35,7 +35,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h"
#include "MG.h"
#include <MAVLinkProtocol.h>
#include <mavlink.h>
#include "QGCMAVLink.h"
/**
* @brief A generic MAVLINK-connected MAV/UAV
......
......@@ -36,10 +36,12 @@ This file is part of the QGROUNDCONTROL project
#include <QList>
#include <QAction>
#include <QColor>
#include <QPointer>
#include "LinkInterface.h"
#include "ProtocolInterface.h"
#include "UASWaypointManager.h"
#include "RadioCalibration/RadioCalibrationData.h"
/**
* @brief Interface for all robots.
......@@ -354,6 +356,8 @@ signals:
void remoteControlChannelChanged(int channelId, float raw, float normalized);
/** @brief Remote control RSSI changed */
void remoteControlRSSIChanged(float rssi);
/** @brief Radio Calibration Data has been received from the MAV*/
void radioCalibrationReceived(const QPointer<RadioCalibrationData>&);
/**
* @brief Localization quality changed
......
......@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QVector>
#include <QTimer>
#include "Waypoint.h"
#include <mavlink.h>
#include "QGCMAVLink.h"
class UAS;
/**
......
......@@ -171,6 +171,9 @@ void MainWindow::buildWidgets()
rcViewDockWidget = new QDockWidget(tr("Radio Control"), this);
rcViewDockWidget->setWidget( new QGCRemoteControlView(this) );
headUpDockWidget = new QDockWidget(tr("Control Indicator"), this);
headUpDockWidget->setWidget( new HUD(320, 240, this));
// Dialogue widgets
//FIXME: free memory in destructor
joystick = new JoystickInput();
......@@ -203,8 +206,13 @@ void MainWindow::connectWidgets()
// add Waypoint widget in the WaypointList widget when mouse clicked
connect(mapWidget, SIGNAL(captureMapCoordinateClick(QPointF)), waypointsDockWidget->widget(), SLOT(addWaypointMouse(QPointF)));
// it notifies that a waypoint global goes to do create
connect(mapWidget, SIGNAL(createGlobalWP(bool)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool)));
connect(mapWidget, SIGNAL(createGlobalWP(bool, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
// it notifies that a waypoint global goes to do create and a map graphic too
connect(waypointsDockWidget->widget(), SIGNAL(createWaypointAtMap(QPointF)), mapWidget, SLOT(createWaypointGraphAtMap(QPointF)));
// it notifies that a waypoint global change its position by spinBox on Widget WaypointView
connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
}
}
......@@ -213,7 +221,6 @@ void MainWindow::arrangeCenterStack()
QStackedWidget *centerStack = new QStackedWidget(this);
if (!centerStack) return;
if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget);
......@@ -362,7 +369,7 @@ void MainWindow::connectActions()
connect(ui.actionShow_MAVLink_view, SIGNAL(triggered()), this, SLOT(loadMAVLinkView()));
connect(ui.actionShow_data_analysis_view, SIGNAL(triggered()), this, SLOT(loadDataView()));
connect(ui.actionStyleConfig, SIGNAL(triggered()), this, SLOT(reloadStylesheet()));
connect(ui.actionGlobalOperatorView, SIGNAL(triggered()), this, SLOT(loadGlobalOperatorView()));
connect(ui.actionOnline_documentation, SIGNAL(triggered()), this, SLOT(showHelp()));
connect(ui.actionCredits_Developers, SIGNAL(triggered()), this, SLOT(showCredits()));
connect(ui.actionProject_Roadmap, SIGNAL(triggered()), this, SLOT(showRoadMap()));
......@@ -808,6 +815,7 @@ void MainWindow::loadOperatorView()
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
......@@ -865,6 +873,83 @@ void MainWindow::loadOperatorView()
this->show();
}
void MainWindow::loadGlobalOperatorView()
{
clearView();
// MAP
if (mapWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
centerStack->setCurrentWidget(mapWidget);
}
}
// UAS CONTROL
if (controlDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, controlDockWidget);
controlDockWidget->show();
}
// UAS LIST
if (listDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, listDockWidget);
listDockWidget->show();
}
// UAS STATUS
if (infoDockWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, infoDockWidget);
infoDockWidget->show();
}
// WAYPOINT LIST
if (waypointsDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, waypointsDockWidget);
waypointsDockWidget->show();
}
// // HORIZONTAL SITUATION INDICATOR
// if (hsiDockWidget)
// {
// HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
// if (hsi)
// {
// addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
// hsiDockWidget->show();
// hsi->start();
// }
// }
// PROCESS CONTROL
if (watchdogControlDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, watchdogControlDockWidget);
watchdogControlDockWidget->show();
}
// HEAD UP DISPLAY
if (headUpDockWidget)
{
addDockWidget(Qt::RightDockWidgetArea, headUpDockWidget);
// FIXME Replace with default ->show() call
HUD* hud = dynamic_cast<HUD*>(headUpDockWidget->widget());
if (hud)
{
headUpDockWidget->show();
hud->start();
}
}
}
void MainWindow::load3DView()
{
clearView();
......
......@@ -122,6 +122,8 @@ public slots:
void loadDataView();
/** @brief Load data view, allowing to plot flight data */
void loadDataView(QString fileName);
/** @brief Load view for global operator, allowing to flight on earth */
void loadGlobalOperatorView();
/** @brief Show the online help for users */
void showHelp();
......@@ -174,6 +176,7 @@ protected:
QPointer<QDockWidget> headDown1DockWidget;
QPointer<QDockWidget> headDown2DockWidget;
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
......
......@@ -76,6 +76,7 @@
<addaction name="actionPilotView"/>
<addaction name="actionOperatorView"/>
<addaction name="action3DView"/>
<addaction name="actionGlobalOperatorView"/>
<addaction name="separator"/>
<addaction name="actionShow_MAVLink_view"/>
<addaction name="actionShow_data_analysis_view"/>
......@@ -308,6 +309,15 @@
<string>Credits / Developers</string>
</property>
</action>
<action name="actionGlobalOperatorView">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/categories/applications-internet.svg</normaloff>:/images/categories/applications-internet.svg</iconset>
</property>
<property name="text">
<string>Show Global operator view</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
......@@ -47,10 +47,13 @@ MapWidget::MapWidget(QWidget *parent) :
zoomLevel(0),
uasIcons(),
uasTrails(),
mav(NULL),
m_ui(new Ui::MapWidget)
{
m_ui->setupUi(this);
waypointIsDrag = false;
// Accept focus by clicking or keyboard
this->setFocusPolicy(Qt::StrongFocus);
......@@ -314,8 +317,9 @@ void MapWidget::createPathButtonClicked(bool checked)
this->setCursor(Qt::PointingHandCursor);
mc->setMouseMode(qmapcontrol::MapControl::None);
// emit signal start to create a Waypoint global
emit createGlobalWP(true);
emit createGlobalWP(true, mc->currentCoordinate());
// // Clear the previous WP track
// // TODO: Move this to an actual clear track button and add a warning dialog
......@@ -337,9 +341,11 @@ void MapWidget::createPathButtonClicked(bool checked)
}
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate){
void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate)
{
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()){
if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked())
{
// Create waypoint name
QString str;
......@@ -373,18 +379,45 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
}
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
{
// Create waypoint name
QString str;
str = QString("%1").arg(path->numberOfPoints());
// create the WP and set everything in the LineString to display the path
CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str);
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
wpIndex.insert(str,tempPoint);
// Refresh the screen
mc->updateRequestNew();
//// // emit signal mouse was clicked
// emit captureMapCoordinateClick(coordinate);
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point)
{
Q_UNUSED(geom);
Q_UNUSED(point);
mc->setMouseMode(qmapcontrol::MapControl::None);
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
{
Q_UNUSED(coordinate);
waypointIsDrag = true;
// Refresh the screen
mc->updateRequestNew();
......@@ -412,6 +445,7 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
{
waypointIsDrag = false;
mc->setMouseMode(qmapcontrol::MapControl::Panning);
......@@ -603,10 +637,35 @@ void MapWidget::clearPath()
wpIndex.clear();
mc->updateRequestNew();
// si el boton de crear wp globales esta activo desactivarlo llamando a su evento clicket
if(createPath->isChecked())
{
createPath->click();
}
}
void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon)
{
if(!waypointIsDrag)
{
qDebug() <<"indice WP= "<<index <<"\n";
QPointF coordinate;
coordinate.setX(lon);
coordinate.setY(lat);
Point* point2Find;
point2Find = wpIndex[QString::number(index)];
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <Point*> (mc->layer("Waypoints")->get_Geometry(index));
point2Find->setCoordinate(coordinate);
// Refresh the screen
mc->updateRequestNew();
}
}
......@@ -66,6 +66,7 @@ public slots:
//ROCA
void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
protected:
void changeEvent(QEvent* e);
......@@ -106,6 +107,7 @@ 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);
......@@ -114,10 +116,11 @@ protected:
signals:
//void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value);
void createGlobalWP(bool value, QPointF centerCoordinate);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
......@@ -127,6 +130,7 @@ private:
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
bool waypointIsDrag;
};
#endif // MAPWIDGET_H
......@@ -25,6 +25,7 @@ This file is part of the QGROUNDCONTROL project
* @file
* @brief Implementation of QGCRemoteControlView
* @author Lorenz Meier <mail@qgroundcontrol.org>
* @author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
#include <QGridLayout>
......@@ -70,6 +71,14 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
layout->addItem(rssiLayout, 2, 0, 1, 2);
setVisible(false);
calibrate = new QPushButton(tr("Calibrate"), this);
QHBoxLayout *calibrateButtonLayout = new QHBoxLayout();
calibrateButtonLayout->addWidget(calibrate, 0, Qt::AlignHCenter);
layout->addItem(calibrateButtonLayout, 3, 0, 1, 2);
calibrationWindow = new RadioCalibrationWindow(this);
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
}
......@@ -89,6 +98,8 @@ void QGCRemoteControlView::setUASId(int id)
// The UAS exists, disconnect any existing connections
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
}
}
......@@ -98,7 +109,10 @@ void QGCRemoteControlView::setUASId(int id)
{
// New UAS exists, connect
nameLabel->setText(QString("RC Input of %1").arg(newUAS->getUASName()));
calibrationWindow->setUASId(id);
connect(newUAS, SIGNAL(radioCalibrationReceived(const QPointer<RadioCalibrationData>&)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlChannelChanged(int,float,float)), calibrationWindow, SLOT(setChannel(int,float,float)));
connect(newUAS, SIGNAL(remoteControlRSSIChanged(float)), this, SLOT(setRemoteRSSI(float)));
}
}
......@@ -173,7 +187,7 @@ void QGCRemoteControlView::changeEvent(QEvent *e)
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
//ui->retranslateUi(this);
break;
default:
break;
......
......@@ -32,6 +32,9 @@ This file is part of the QGROUNDCONTROL project
#include <QWidget>
#include <QVector>
#include <QPushButton>
#include "RadioCalibration/RadioCalibrationWindow.h"
namespace Ui {
class QGCRemoteControlView;
......@@ -68,6 +71,8 @@ protected:
QVector<QProgressBar*> progressBars;
QProgressBar* rssiBar;
QLabel* nameLabel;
QPushButton *calibrate;
RadioCalibrationWindow *calibrationWindow;
private:
Ui::QGCRemoteControlView *ui;
......
#include "AbstractCalibrator.h"
AbstractCalibrator::AbstractCalibrator(QWidget *parent) :
QWidget(parent),
pulseWidth(new QLabel()),
log(new QVector<float>())
{
}
AbstractCalibrator::~AbstractCalibrator()
{
delete log;
}
float AbstractCalibrator::logAverage()
{
float total = 0;
for (int i=0; i<log->size(); ++i)
total += log->value(i);
return floor(total/log->size());
}
float AbstractCalibrator::logExtrema()
{
float extrema = logAverage();
if (logAverage() < 1500)
{
for (int i=0; i<log->size(); ++i)
{
if (log->value(i) < extrema)
extrema = log->value(i);
}
extrema -= 5; // add 5us to prevent integer overflow
}
else
{
for (int i=0; i<log->size(); ++i)
{
if (log->value(i) > extrema)
extrema = log->value(i);
}
extrema += 5; // subtact 5us to prevent integer overflow
}
return extrema;
}
void AbstractCalibrator::channelChanged(float raw)
{
pulseWidth->setText(QString::number(static_cast<double>(raw)));
if (log->size() == 5)
log->pop_front();
log->push_back(raw);
}
/*=====================================================================
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 Common aspects of radio calibration widgets
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef ABSTRACTCALIBRATOR_H
#define ABSTRACTCALIBRATOR_H
#include <QWidget>
#include <QString>
#include <QLabel>
#include <QVector>
#include <math.h>
/**
@brief Holds the code which is common to all the radio calibration widgets.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class AbstractCalibrator : public QWidget
{
Q_OBJECT
public:
explicit AbstractCalibrator(QWidget *parent = 0);
~AbstractCalibrator();
/** Change the setpoints of the widget. Used when
changing the display from an external source (file/uav).
@param data QVector of setpoints
*/
virtual void set(const QVector<float>& data)=0;
signals:
/** Announce a setpoint change.
@param index setpoint number - 0 based in the current implementation
@param value new value
*/
void setpointChanged(int index, float value);
public slots:
/** Slot to call when the relevant channel is updated
@param raw current channel value
*/
void channelChanged(float raw);
protected:
/** Display the current pulse width */
QLabel *pulseWidth;
/** Log of the past few samples for use in averaging and finding extrema */
QVector<float> *log;
/** Find the maximum or minimum of the data log */
float logExtrema();
/** Find the average of the log */
float logAverage();
};
#endif // ABSTRACTCALIBRATOR_H
#include "AirfoilServoCalibrator.h"
AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent) :
AbstractCalibrator(parent),
highPulseWidth(new QLabel()),
centerPulseWidth(new QLabel()),
lowPulseWidth(new QLabel())
{
QGridLayout *grid = new QGridLayout(this);
/* Add title */
QHBoxLayout *titleLayout = new QHBoxLayout();
QLabel *title;
if (type == AILERON)
{
title = new QLabel(tr("Aileron"));
}
else if (type == ELEVATOR)
{
title = new QLabel(tr("Elevator"));
}
else if (type == RUDDER)
{
title = new QLabel(tr("Rudder"));
}
titleLayout->addWidget(title);
grid->addLayout(titleLayout, 0, 0, 1, 3, Qt::AlignHCenter);
/* Add current Pulse Width Display */
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 3);
QLabel *highPulseString;
QLabel *centerPulseString;
QLabel *lowPulseString;
if (type == AILERON)
{
highPulseString = new QLabel(tr("Bank Left"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Bank Right"));
}
else if (type == ELEVATOR)
{
highPulseString = new QLabel(tr("Nose Down"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Nose Up"));
}
else if (type == RUDDER)
{
highPulseString = new QLabel(tr("Nose Left"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Nose Right"));
}
else
{
highPulseString = new QLabel(tr("High"));
centerPulseString = new QLabel(tr("Center"));
lowPulseString = new QLabel(tr("Low"));
}
QPushButton *highButton = new QPushButton(tr("Set"));
QPushButton *centerButton = new QPushButton(tr("Set"));
QPushButton *lowButton = new QPushButton(tr("Set"));
grid->addWidget(highPulseString, 2, 0);
grid->addWidget(highPulseWidth, 2, 1);
grid->addWidget(highButton, 2, 2);
grid->addWidget(centerPulseString, 3, 0);
grid->addWidget(centerPulseWidth, 3, 1);
grid->addWidget(centerButton, 3, 2);
grid->addWidget(lowPulseString, 4, 0);
grid->addWidget(lowPulseWidth, 4, 1);
grid->addWidget(lowButton, 4, 2);
this->setLayout(grid);
connect(highButton, SIGNAL(clicked()), this, SLOT(setHigh()));
connect(centerButton, SIGNAL(clicked()), this, SLOT(setCenter()));
connect(lowButton, SIGNAL(clicked()), this, SLOT(setLow()));
}
void AirfoilServoCalibrator::setHigh()
{
highPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(2, logExtrema());
}
void AirfoilServoCalibrator::setCenter()
{
centerPulseWidth->setText(QString::number(static_cast<double>(logAverage())));
emit setpointChanged(1, logAverage());
}
void AirfoilServoCalibrator::setLow()
{
lowPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(0, logExtrema());
}
void AirfoilServoCalibrator::set(const QVector<float> &data)
{
if (data.size() == 3)
{
lowPulseWidth->setText(QString::number(data[0]));
centerPulseWidth->setText(QString::number(data[1]));
highPulseWidth->setText(QString::number(data[2]));
}
}
/*=====================================================================
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 Calibration widget for 3 point airfoil servo
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef AIRFOILSERVOCALIBRATOR_H
#define AIRFOILSERVOCALIBRATOR_H
#include <QWidget>
#include <QLabel>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget three setpoint control input.
For the helicopter autopilot at UAlberta this is used for Aileron, Elevator, and Rudder channels.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class AirfoilServoCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
enum AirfoilType
{
AILERON,
ELEVATOR,
RUDDER
};
explicit AirfoilServoCalibrator(AirfoilType type = AILERON, QWidget *parent = 0);
/** @param data must have exaclty 3 elemets. they are assumed to be low center high */
void set(const QVector<float>& data);
protected slots:
void setHigh();
void setCenter();
void setLow();
protected:
QLabel *highPulseWidth;
QLabel *centerPulseWidth;
QLabel *lowPulseWidth;
};
#endif // AIRFOILSERVOCALIBRATOR_H
#include "CurveCalibrator.h"
CurveCalibrator::CurveCalibrator(QString titleString, QWidget *parent) :
AbstractCalibrator(parent),
setpoints(new QVector<double>(5)),
positions(new QVector<double>())
{
QGridLayout *grid = new QGridLayout(this);
QLabel *title = new QLabel(titleString);
grid->addWidget(title, 0, 0, 1, 5, Qt::AlignHCenter);
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
pulseWidth = new QLabel();
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 5, Qt::AlignHCenter);
for (int i=0; i<=100; i=i+100/4)
positions->append(static_cast<double>(i));
setpoints->fill(1500);
plot = new QwtPlot();
grid->addWidget(plot, 2, 0, 1, 5, Qt::AlignHCenter);
plot->setAxisScale(QwtPlot::yLeft, 1000, 2000, 200);
plot->setAxisScale(QwtPlot::xBottom, 0, 100, 25);
curve = new QwtPlotCurve();
curve->setPen(QPen(QColor(QString("lime"))));
curve->setData(*positions, *setpoints);
curve->attach(plot);
plot->replot();
QPushButton *zero = new QPushButton(tr("0 %"));
QPushButton *twentyfive = new QPushButton(tr("25 %"));
QPushButton *fifty = new QPushButton(tr("50 %"));
QPushButton *seventyfive = new QPushButton(tr("75 %"));
QPushButton *hundred = new QPushButton(tr("100 %"));
grid->addWidget(zero, 3, 0);
grid->addWidget(twentyfive, 3, 1);
grid->addWidget(fifty, 3, 2);
grid->addWidget(seventyfive, 3, 3);
grid->addWidget(hundred, 3, 4);
this->setLayout(grid);
signalMapper = new QSignalMapper(this);
signalMapper->setMapping(zero, 0);
signalMapper->setMapping(twentyfive, 1);
signalMapper->setMapping(fifty, 2);
signalMapper->setMapping(seventyfive, 3);
signalMapper->setMapping(hundred, 4);
connect(zero, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(twentyfive, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(fifty, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(seventyfive, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(hundred, SIGNAL(clicked()), signalMapper, SLOT(map()));
connect(signalMapper, SIGNAL(mapped(int)), this, SLOT(setSetpoint(int)));
}
CurveCalibrator::~CurveCalibrator()
{
delete setpoints;
delete positions;
}
void CurveCalibrator::setSetpoint(int setpoint)
{
if (setpoint == 0 || setpoint == 4)
{
setpoints->replace(setpoint, static_cast<double>(logExtrema()));
}
else
{
setpoints->replace(setpoint, static_cast<double>(logAverage()));
}
curve->setData(*positions, *setpoints);
plot->replot();
emit setpointChanged(setpoint, static_cast<float>(setpoints->value(setpoint)));
}
void CurveCalibrator::set(const QVector<float> &data)
{
if (data.size() == 5)
{
for (int i=0; i<data.size(); ++i)
setpoints->replace(i, static_cast<double>(data[i]));
curve->setData(*positions, *setpoints);
plot->replot();
}
else
{
qDebug() << __FILE__ << __LINE__ << ": wrong data vector size";
}
}
/*=====================================================================
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 Calibration widget for 5 point inerpolated curve
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef CURVECALIBRATOR_H
#define CURVECALIBRATOR_H
#include <QWidget>
#include <QVector>
#include <qwt_plot.h>
#include <qwt_plot_curve.h>
//#include <qwt_array.h>
#include <QGridLayout>
#include <QHBoxLayout>
#include <QLabel>
#include <QPushButton>
#include <QPen>
#include <QColor>
#include <QString>
#include <QSignalMapper>
#include <QDebug>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget for 5 point inerpolated curve.
For the helicopter autopilot at UAlberta this is used for the throttle and pitch curves.
*/
class CurveCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
explicit CurveCalibrator(QString title = QString(), QWidget *parent = 0);
~CurveCalibrator();
void set(const QVector<float> &data);
protected slots:
void setSetpoint(int setpoint);
protected:
QVector<double> *setpoints;
QVector<double> *positions;
/** Plot to display calibration curve */
QwtPlot *plot;
/** Curve object of calibration curve */
QwtPlotCurve *curve;
QSignalMapper *signalMapper;
};
#endif // CURVECALIBRATOR_H
#include "RadioCalibrationData.h"
RadioCalibrationData::RadioCalibrationData()
{
data = new QVector<QVector<float> >(6);
(*data).insert(AILERON, QVector<float>(3));
(*data).insert(ELEVATOR, QVector<float>(3));
(*data).insert(RUDDER, QVector<float>(3));
(*data).insert(GYRO, QVector<float>(2));
(*data).insert(PITCH, QVector<float>(5));
(*data).insert(THROTTLE, QVector<float>(5));
}
RadioCalibrationData::RadioCalibrationData(const QVector<float> &aileron,
const QVector<float> &elevator,
const QVector<float> &rudder,
const QVector<float> &gyro,
const QVector<float> &pitch,
const QVector<float> &throttle)
{
data = new QVector<QVector<float> >();
(*data) << aileron
<< elevator
<< rudder
<< gyro
<< pitch
<< throttle;
}
RadioCalibrationData::RadioCalibrationData(const RadioCalibrationData &other)
:QObject()
{
data = new QVector<QVector<float> >(*other.data);
}
RadioCalibrationData::~RadioCalibrationData()
{
delete data;
}
const float* RadioCalibrationData::operator [](int i) const
{
if (i < data->size())
{
return (*data)[i].constData();
}
return NULL;
}
const QVector<float>& RadioCalibrationData::operator ()(int i) const
{
if (i < data->size())
{
return (*data)[i];
}
// This is not good. If it is ever used after being returned it will cause a crash
// return QVector<float>();
}
QString RadioCalibrationData::toString(RadioElement element) const
{
QString s;
foreach (float f, (*data)[element])
{
s += QString::number(f) + ", ";
}
return s.mid(0, s.length()-2);
}
/*=====================================================================
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 Class to hold the calibration data
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef RADIOCALIBRATIONDATA_H
#define RADIOCALIBRATIONDATA_H
#include <QObject>
#include <QDebug>
#include <QVector>
#include <QString>
/**
@brief Class to hold the calibration data.
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class RadioCalibrationData : public QObject
{
Q_OBJECT
public:
explicit RadioCalibrationData();
RadioCalibrationData(const RadioCalibrationData&);
RadioCalibrationData(const QVector<float>& aileron,
const QVector<float>& elevator,
const QVector<float>& rudder,
const QVector<float>& gyro,
const QVector<float>& pitch,
const QVector<float>& throttle);
~RadioCalibrationData();
enum RadioElement
{
AILERON=0,
ELEVATOR,
RUDDER,
GYRO,
PITCH,
THROTTLE
};
const float* operator[](int i) const;
const QVector<float>& operator()(int i) const;
void set(int element, int index, float value) {(*data)[element][index] = value;}
public slots:
void setAileron(int index, float value) {set(AILERON, index, value);}
void setElevator(int index, float value) {set(ELEVATOR, index, value);}
void setRudder(int index, float value) {set(RUDDER, index, value);}
void setGyro(int index, float value) {set(GYRO, index, value);}
void setPitch(int index, float value) {set(PITCH, index, value);}
void setThrottle(int index, float value) {set(THROTTLE, index, value);}
public:
/// Creates a comma seperated list of the values for a particular element
QString toString(const RadioElement element) const;
protected:
QVector<QVector<float> > *data;
void init(const QVector<float>& aileron,
const QVector<float>& elevator,
const QVector<float>& rudder,
const QVector<float>& gyro,
const QVector<float>& pitch,
const QVector<float>& throttle);
};
#endif // RADIOCALIBRATIONDATA_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 Main window for radio calibration
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef RADIOCALIBRATIONWINDOW_H
#define RADIOCALIBRATIONWINDOW_H
#include <QWidget>
#include <QLabel>
#include <QGroupBox>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include <QDebug>
#include <QPointer>
#include <QFileDialog>
#include <QFile>
#include <QtXml>
#include <QTextStream>
#include "AirfoilServoCalibrator.h"
#include "SwitchCalibrator.h"
#include "CurveCalibrator.h"
#include "mavlink.h"
#include "mavlink_types.h"
#include "UAS.h"
#include "UASManager.h"
#include "RadioCalibrationData.h"
/**
@brief Main window for radio calibration
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class RadioCalibrationWindow : public QWidget
{
Q_OBJECT
public:
explicit RadioCalibrationWindow(QWidget *parent = 0);
public slots:
void setChannel(int ch, float raw, float normalized);
void loadFile();
void saveFile();
void send();
void request();
void receive(const QPointer<RadioCalibrationData>& radio);
void setUASId(int id) {this->uasId = id;}
protected:
AirfoilServoCalibrator *aileron;
AirfoilServoCalibrator *elevator;
AirfoilServoCalibrator *rudder;
SwitchCalibrator *gyro;
CurveCalibrator *pitch;
CurveCalibrator *throttle;
int uasId;
QPointer<RadioCalibrationData> radio;
QSignalMapper mapper;
void parseSetpoint(const QDomElement& setpoint, const QPointer<RadioCalibrationData>& radio);
};
#endif // RADIOCALIBRATIONWINDOW_H
#include "SwitchCalibrator.h"
SwitchCalibrator::SwitchCalibrator(QString titleString, QWidget *parent) :
AbstractCalibrator(parent),
defaultPulseWidth(new QLabel()),
toggledPulseWidth(new QLabel())
{
/* Add title label*/
QLabel *title = new QLabel(titleString);
QGridLayout *grid = new QGridLayout();
grid->addWidget(title, 0, 0, 1, 3);
/* Add current Pulse Width Display */
QLabel *pulseWidthTitle = new QLabel(tr("Pulse Width (us)"));
QHBoxLayout *pulseLayout = new QHBoxLayout();
pulseLayout->addWidget(pulseWidthTitle);
pulseLayout->addWidget(pulseWidth);
grid->addLayout(pulseLayout, 1, 0, 1, 3);
QLabel *defaultPulseString = new QLabel(tr("Default Position"));
QPushButton *defaultButton = new QPushButton(tr("Set"));
grid->addWidget(defaultPulseString, 2, 0);
grid->addWidget(defaultPulseWidth, 2, 1);
grid->addWidget(defaultButton, 2, 2);
QLabel *toggledPulseString = new QLabel(tr("Toggled Position"));
QPushButton *toggledButton = new QPushButton(tr("Set"));
grid->addWidget(toggledPulseString, 3, 0);
grid->addWidget(toggledPulseWidth, 3, 1);
grid->addWidget(toggledButton, 3, 2);
this->setLayout(grid);
connect(defaultButton, SIGNAL(clicked()), this, SLOT(setDefault()));
connect(toggledButton, SIGNAL(clicked()), this, SLOT(setToggled()));
}
void SwitchCalibrator::setDefault()
{
defaultPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(0, logExtrema());
}
void SwitchCalibrator::setToggled()
{
toggledPulseWidth->setText(QString::number(static_cast<double>(logExtrema())));
emit setpointChanged(1, logExtrema());
}
void SwitchCalibrator::set(const QVector<float> &data)
{
if (data.size() == 2)
{
defaultPulseWidth->setText(QString::number(data[0]));
toggledPulseWidth->setText(QString::number(data[1]));
}
}
/*=====================================================================
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 Calibration widget for 2 setpoint switch
* @author Bryan Godbolt <godbolt@ualberta.ca>
*/
#ifndef SWITCHCALIBRATOR_H
#define SWITCHCALIBRATOR_H
#include <QWidget>
#include <QLabel>
#include <QPushButton>
#include <QVector>
#include <QGridLayout>
#include <QHBoxLayout>
#include "AbstractCalibrator.h"
/**
@brief Calibration widget for 2 setpoint switch
@author Bryan Godbolt <godbolt@ece.ualberta.ca>
*/
class SwitchCalibrator : public AbstractCalibrator
{
Q_OBJECT
public:
explicit SwitchCalibrator(QString title=QString(), QWidget *parent = 0);
void set(const QVector<float> &data);
protected slots:
void setDefault();
void setToggled();
protected:
QLabel *defaultPulseWidth;
QLabel *toggledPulseWidth;
};
#endif // SWITCHCALIBRATOR_H
......@@ -12,14 +12,30 @@ WaypointGlobalView::WaypointGlobalView(Waypoint* wp,QWidget *parent) :
ui->m_orbitalSpinBox->hide();
// Read values and set user interface
updateValues();
connect(ui->m_orbitalSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(ui->m_heigthSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
//for spinBox Latitude
connect(ui->m_latitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLatitudeWP(int)));
connect(ui->m_latitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLatitudeMinuteWP(double)));
connect(ui->m_dirLatitudeN_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP()));
connect(ui->m_dirLatitudeS_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLatitudeWP()));
//for spinBox Longitude
connect(ui->m_longitudGrados_spinBox, SIGNAL(valueChanged(int)), this, SLOT(updateLongitudeWP(int)));
connect(ui->m_longitudMinutos_spinBox, SIGNAL(valueChanged(double)), this, SLOT(updateLongitudeMinuteWP(double)));
connect(ui->m_dirLongitudeW_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP()));
connect(ui->m_dirLongitudeE_radioButton, SIGNAL(clicked()), this, SLOT(changeDirectionLongitudeWP()));
connect(ui->m_orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
// Read values and set user interface
updateValues();
// connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
......@@ -48,9 +64,46 @@ WaypointGlobalView::~WaypointGlobalView()
void WaypointGlobalView::updateValues()
{
ui->m_latitudtextEdit->setText(getLatitudString(wp->getY()));
ui->m_longitudtextEdit->setText(getLongitudString(wp->getX()));
ui->idWP_label->setText(QString("%1").arg(wp->getId()));\
int gradoLat, gradoLon;
float minLat, minLon;
QString dirLat, dirLon;
getLatitudeGradoMin(wp->getY(), &gradoLat, &minLat, &dirLat);
getLongitudGradoMin(wp->getX(), &gradoLon, &minLon, &dirLon);
//latitude on spinBox
ui->m_latitudGrados_spinBox->setValue(gradoLat);
ui->m_latitudMinutos_spinBox->setValue(minLat);
if(dirLat == "N")
{
ui->m_dirLatitudeN_radioButton->setChecked(true);
ui->m_dirLatitudeS_radioButton->setChecked(false);
}
else
{
ui->m_dirLatitudeS_radioButton->setChecked(true);
ui->m_dirLatitudeN_radioButton->setChecked(false);
}
//longitude on spinBox
ui->m_longitudGrados_spinBox->setValue(gradoLon);
ui->m_longitudMinutos_spinBox->setValue(minLon);
if(dirLon == "W")
{
ui->m_dirLongitudeW_radioButton->setChecked(true);
ui->m_dirLongitudeE_radioButton->setChecked(false);
}
else
{
ui->m_dirLongitudeE_radioButton->setChecked(true);
ui->m_dirLongitudeW_radioButton->setChecked(false);
}
ui->idWP_label->setText(QString("WP-%1").arg(wp->getId()));
}
......@@ -152,4 +205,258 @@ void WaypointGlobalView::changeOrbitalState(int state)
}
}
void WaypointGlobalView::getLatitudeGradoMin(float latitud, int *gradoLat, float *minLat, QString *dirLat)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (latitud<0){*dirLat="S"; latitud = latitud * -1;}
else {*dirLat="N";}
if(latitud< 90 || latitud > -90)
{
dec = latitud - (entero = ::floor(latitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
*gradoLat = grados;
*minLat = minutos;
}
else
{
*gradoLat = -1;
*minLat = -1;
*dirLat="N/A";
}
}
void WaypointGlobalView::getLongitudGradoMin(float longitud, int *gradoLon, float *minLon, QString *dirLon)
{
float minutos = 0;
float grados = 0;
float entero = 0;
float dec = 0;
if (longitud<0){*dirLon="W"; longitud = longitud * -1;}
else {*dirLon="E";}
if(longitud<180 || longitud > -180)
{
dec = longitud - (entero = ::floor(longitud));;
minutos = dec * 60;
grados = entero;
if(grados < 0) grados = grados * (-1);
if(minutos < 0) minutos = minutos * (-1);
*gradoLon = grados;
*minLon = minutos;
}
else
{
*gradoLon = -1;
*minLon = -1;
*dirLon="N/A";
}
}
void WaypointGlobalView::updateCoordValues(float lat, float lon)
{
}
void WaypointGlobalView::updateLatitudeWP(int value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
//dirLat = ui->m_dirLatitud_label->text();
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLatitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLat;
float minLat;
float Latitud;
QString dirLat;
gradoLat = ui->m_latitudGrados_spinBox->value();
minLat = ui->m_latitudMinutos_spinBox->value();
//dirLat = ui->m_dirLatitud_label->text();
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
dirLat = "N";
}
else
{
dirLat = "S";
}
Latitud = gradoLat + (minLat/60);
if(dirLat == "S"){Latitud = Latitud * -1;}
wp->setY(Latitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeWP(int value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::updateLongitudeMinuteWP(double value)
{
Q_UNUSED(value);
int gradoLon;
float minLon;
float Longitud;
QString dirLon;
gradoLon = ui->m_longitudGrados_spinBox->value();
minLon = ui->m_longitudMinutos_spinBox->value();
// dirLon = ui->m_dirLongitud_label->text();
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
dirLon = "W";
}
else
{
dirLon = "E";
}
Longitud = gradoLon + (minLon/60);
if(dirLon == "W"){Longitud = Longitud * -1;}
wp->setX(Longitud);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
void WaypointGlobalView::changeDirectionLatitudeWP()
{
if(ui->m_dirLatitudeN_radioButton->isChecked())
{
if(wp->getY() < 0)
{
wp->setY(wp->getY()* -1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
if(ui->m_dirLatitudeS_radioButton->isChecked())
{
if(wp->getY() > 0)
{
wp->setY(wp->getY()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
}
void WaypointGlobalView::changeDirectionLongitudeWP()
{
if(ui->m_dirLongitudeW_radioButton->isChecked())
{
if(wp->getX() > 0)
{
wp->setX(wp->getX()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
if(ui->m_dirLongitudeE_radioButton->isChecked())
{
if(wp->getX() < 0)
{
wp->setX(wp->getX()*-1);
//emit signal waypoint position was changed
emit changePositionWP(wp);
}
}
}
......@@ -22,12 +22,30 @@ public slots:
void remove();
QString getLatitudString(float lat);
QString getLongitudString(float lon);
void getLatitudeGradoMin(float lat, int *gradoLat, float *minLat, QString *dirLat);
void getLongitudGradoMin(float lon, int *gradoLon, float *minLon, QString *dirLon);
void changeOrbitalState(int state);
void updateCoordValues(float lat, float lon);
//update latitude
void updateLatitudeWP(int value);
void updateLatitudeMinuteWP(double value);
void changeDirectionLatitudeWP();
//update longitude
void updateLongitudeWP(int value);
void updateLongitudeMinuteWP(double value);
void changeDirectionLongitudeWP();
signals:
void removeWaypoint(Waypoint*);
void changePositionWP(Waypoint*);
protected:
virtual void changeEvent(QEvent *e);
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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