Commit db719606 authored by Lorenz Meier's avatar Lorenz Meier

Merge branch 'master' of github.com:mavlink/qgroundcontrol

parents 4e81ee8c 906c3f21
......@@ -258,26 +258,6 @@ LinuxBuild : contains(MAVLINK_CONF, pixhawk) {
message("Skipping support for Protocol Buffers")
}
#
# libfreenect Kinect support
#
MacBuild | LinuxBuild {
exists(/opt/local/include/libfreenect) | exists(/usr/local/include/libfreenect) {
message("Including support for libfreenect")
#INCLUDEPATH += /usr/include/libusb-1.0
DEFINES += QGC_LIBFREENECT_ENABLED
LIBS += -lfreenect
HEADERS += src/input/Freenect.h
SOURCES += src/input/Freenect.cc
} else {
message("Skipping support for libfreenect")
}
} else {
message("Skipping support for libfreenect")
}
#
# EIGEN matrix library (NOMINMAX needed to make internal min/max work)
#
......
......@@ -28,6 +28,11 @@
#include <qmath.h>
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#endif
namespace projections {
LKS94Projection::LKS94Projection():MinLatitude (53.33 ), MaxLatitude (56.55 ), MinLongitude (20.22 ),
......@@ -787,3 +792,8 @@ Size LKS94Projection::GetTileMatrixMaxXY(int const& zoom)
}
}
#ifdef Q_OS_LINUX
#pragma GCC diagnostic pop
#endif
......@@ -57,6 +57,16 @@ Point MercatorProjectionYandex::FromLatLngToPixel(double lat, double lng, const
return ret;
}
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#elif defined(Q_OS_MAC)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-variable"
#endif
internals::PointLatLng MercatorProjectionYandex::FromPixelToLatLng(const int &x, const int &y, const int &zoom)
{
Size s = GetTileMatrixSizePixel(zoom);
......@@ -82,6 +92,11 @@ internals::PointLatLng MercatorProjectionYandex::FromPixelToLatLng(const int &x,
return ret;
}
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
double MercatorProjectionYandex::Clip(const double &n, const double &minValue, const double &maxValue) const
{
return qMin(qMax(n, minValue), maxValue);
......
......@@ -533,6 +533,15 @@ QwtRasterData::ContourLines QwtPlotSpectrogram::renderContourLines(
d_data->contourLevels, d_data->conrecAttributes );
}
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#elif defined(Q_OS_MAC)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-variable"
#endif
/*!
Paint the contour lines
......@@ -578,6 +587,10 @@ void QwtPlotSpectrogram::drawContourLines(QPainter *painter,
}
}
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
/*!
\brief Draw the spectrogram
......
......@@ -85,8 +85,19 @@ public:
public slots:
void moveBy(double x, double y);
// These pragmas are local modifications to this third party library to silence warnings
#ifndef Q_OS_WIN
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
virtual void move(double x, double y);
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
virtual void zoom(const QwtDoubleRect &);
virtual void zoom(int up);
......
......@@ -55,4 +55,4 @@ unix:!symbian {
}
}
HEADERS += $$PUBLIC_HEADERS $$PRIVATE_HEADERS
HEADERS *= $$PUBLIC_HEADERS $$PRIVATE_HEADERS
......@@ -117,16 +117,23 @@ WindowsBuild {
}
#
# Warnings cleanup. Plan of attack is to turn on warnings as error once all warnings are fixed. Please
# do no change the warning level from what they are currently set to below.
# We treat all warnings as errors which must be fixed before proceeding. If you run into a problem you can't fix
# you can always use local pragmas to work around the warning. This should be used sparingly and only in cases where
# the problem absolultey can't be fixed.
#
MacBuild | LinuxBuild {
QMAKE_CXXFLAGS_WARN_ON += -Wall
}
MacBuild {
QMAKE_CXXFLAGS_WARN_ON += -Werror
}
WindowsBuild {
QMAKE_CXXFLAGS_WARN_ON += /W3
QMAKE_CXXFLAGS_WARN_ON += /W3 \
/wd4996 \ # silence warnings about deprecated strcpy and whatnot
/wd4290 # ignore exception specifications
}
#
......
......@@ -196,15 +196,7 @@ void MAVLinkProtocol::linkStatusChanged(bool connected)
// Start NSH
const char init[] = {0x0d, 0x0d, 0x0d};
link->writeBytes(init, sizeof(init));
// Stop any running mavlink instance
const char* cmd = "mavlink stop\n";
link->writeBytes(cmd, strlen(cmd));
link->writeBytes(init, 2);
cmd = "uorb start";
link->writeBytes(cmd, strlen(cmd));
link->writeBytes(init, 2);
cmd = "sh /etc/init.d/rc.usb\n";
const char* cmd = "sh /etc/init.d/rc.usb\n";
link->writeBytes(cmd, strlen(cmd));
link->writeBytes(init, 4);
}
......
......@@ -168,6 +168,9 @@ public slots:
virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites)
{ Q_UNUSED(time_us); Q_UNUSED(lat); Q_UNUSED(lon); Q_UNUSED(alt); Q_UNUSED(fix_type); Q_UNUSED(eph); Q_UNUSED(epv); Q_UNUSED(vel); Q_UNUSED(vn); Q_UNUSED(ve); Q_UNUSED(vd); Q_UNUSED(cog); Q_UNUSED(satellites); Q_ASSERT(false); };
virtual bool isRotaryWing() { Q_ASSERT(false); return false; }
virtual bool isFixedWing() { Q_ASSERT(false); return false; }
private:
int _systemType;
int _systemId;
......
......@@ -2115,7 +2115,7 @@ void UAS::requestImage()
if (imagePacketsArrived == 0)
{
mavlink_message_t msg;
mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50);
mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, MAVLINK_DATA_STREAM_IMG_JPEG, 0, 0, 0, 0, 0, 50);
sendMessage(msg);
}
}
......@@ -2170,6 +2170,32 @@ void UAS::readParametersFromStorage()
sendMessage(msg);
}
bool UAS::isRotaryWing()
{
switch (type) {
case MAV_TYPE_QUADROTOR:
/* fallthrough */
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
return true;
default:
return false;
}
}
bool UAS::isFixedWing()
{
switch (type) {
case MAV_TYPE_FIXED_WING:
return true;
default:
return false;
}
}
/**
* @param rate The update rate in Hz the message should be sent
*/
......
......@@ -306,6 +306,9 @@ public:
return nedAttGlobalOffset;
}
bool isRotaryWing();
bool isFixedWing();
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px::GLOverlay getOverlay()
{
......
......@@ -267,6 +267,9 @@ public:
*/
virtual QList<QAction*> getActions() const = 0;
static const unsigned int WAYPOINT_RADIUS_DEFAULT_FIXED_WING = 25;
static const unsigned int WAYPOINT_RADIUS_DEFAULT_ROTARY_WING = 5;
public slots:
/** @brief Set a new name for the system */
......@@ -376,6 +379,11 @@ public slots:
virtual void startGyroscopeCalibration() = 0;
virtual void startPressureCalibration() = 0;
/** @brief Return if this a rotary wing */
virtual bool isRotaryWing() = 0;
/** @brief Return if this is a fixed wing */
virtual bool isFixedWing() = 0;
/** @brief Set the current battery type and voltages */
virtual void setBatterySpecs(const QString& specs) = 0;
/** @brief Get the current battery type and specs */
......@@ -393,7 +401,6 @@ public slots:
/** @brief Send raw GPS for sensor HIL */
virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites) = 0;
protected:
QColor color;
......
......@@ -225,6 +225,17 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli
current_state = WP_IDLE;
readWaypoints(false); //Update "Onboard Waypoints"-tab immidiately after the waypoint list has been sent.
emit updateStatusString("done.");
} else if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && wpa->type != 0) {
//give up transmitting if a WP is rejected
if (wpa->type == 1) {
emit updateStatusString("upload failed: general error");
} else if (wpa->type == 2) {
emit updateStatusString("upload failed: coordinate frame unsupported.");
} else {
emit updateStatusString("upload failed: other error.");
}
protocol_timer.stop();
current_state = WP_IDLE;
} else if(current_state == WP_CLEARLIST) {
protocol_timer.stop();
current_state = WP_IDLE;
......@@ -905,7 +916,7 @@ void UASWaypointManager::writeWaypoints()
sendWaypointCount();
} else if (waypointsEditable.count() == 0)
{
sendWaypointClearAll();
clearWaypointList();
}
}
else
......@@ -1063,11 +1074,23 @@ int UASWaypointManager::getFrameRecommendation()
float UASWaypointManager::getAcceptanceRadiusRecommendation()
{
if (waypointsEditable.count() > 0) {
if (waypointsEditable.count() > 0)
{
return waypointsEditable.last()->getAcceptanceRadius();
} else {
return 10.0f;
}
else
{
if (uas->isRotaryWing())
{
return UASInterface::WAYPOINT_RADIUS_DEFAULT_ROTARY_WING;
}
else if (uas->isFixedWing())
{
return UASInterface::WAYPOINT_RADIUS_DEFAULT_FIXED_WING;
}
}
return 10.0f;
}
float UASWaypointManager::getHomeAltitudeOffsetDefault()
......
......@@ -283,9 +283,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
wp->setZ(last->getZ());
}
wp->setParam1(last->getParam1());
wp->setParam1(last->getParam2());
wp->setParam1(last->getParam3());
wp->setParam1(last->getParam4());
wp->setParam2(last->getParam2());
wp->setParam3(last->getParam3());
wp->setParam4(last->getParam4());
wp->setAutocontinue(last->getAutoContinue());
// wp->blockSignals(false);
wp->setAction(last->getAction());
......
......@@ -39,8 +39,20 @@ This file is part of the QGROUNDCONTROL project
#include <osg/PositionAttitudeTransform>
#include <osgGA/TrackballManipulator>
#include <osgText/Font>
// OpenSceneGraph has overloaded virtuals defined, since third party code we silence the warnings when the
// headers are used.
#ifndef Q_OS_WIN
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
#include <osgViewer/Viewer>
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
#include "CameraParams.h"
#include "GCManipulator.h"
#include "SystemGroupNode.h"
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment