Commit 6f583e02 authored by pixhawk's avatar pixhawk

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

parents c7dfc6e8 24201265
*Makefile*
tags
build
Info.plist
obj
......
......@@ -127,8 +127,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCFirmwareUpdate.ui \
src/ui/QGCPxImuFirmwareUpdate.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/WaypointGlobalView.ui
src/ui/QGCRemoteControlView.ui
#src/ui/WaypointGlobalView.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -195,7 +195,7 @@ HEADERS += src/MG.h \
src/ui/linechart/Linecharts.h \
src/uas/SlugsMAV.h \
src/uas/PxQuadMAV.h \
src/uas/ArduPilotMAV.h \
src/uas/ArduPilotMegaMAV.h \
src/comm/MAVLinkSyntaxHighlighter.h \
src/ui/watchdog/WatchdogControl.h \
src/ui/watchdog/WatchdogProcessView.h \
......@@ -211,7 +211,7 @@ HEADERS += src/MG.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/ui/WaypointGlobalView.h \
#src/ui/WaypointGlobalView.h \
src/ui/RadioCalibration/RadioCalibrationData.h \
src/ui/RadioCalibration/RadioCalibrationWindow.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \
......@@ -271,7 +271,7 @@ SOURCES += src/main.cc \
src/ui/linechart/Linecharts.cc \
src/uas/SlugsMAV.cc \
src/uas/PxQuadMAV.cc \
src/uas/ArduPilotMAV.cc \
src/uas/ArduPilotMegaMAV.cc \
src/comm/MAVLinkSyntaxHighlighter.cc \
src/ui/watchdog/WatchdogControl.cc \
src/ui/watchdog/WatchdogProcessView.cc \
......@@ -293,7 +293,7 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/WaypointGlobalView.cc \
#src/ui/WaypointGlobalView.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/PixhawkCheetahGeode.cc \
src/ui/map3D/Pixhawk3DWidget.cc \
......
......@@ -33,7 +33,8 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h"
#include <QStringList>
Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _autocontinue, bool _current, float _orbit, int _holdTime)
Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _autocontinue, bool _current, float _orbit, int _holdTime,
MAV_FRAME _frame, MAV_ACTION _action)
: id(_id),
x(_x),
y(_y),
......@@ -42,7 +43,9 @@ Waypoint::Waypoint(quint16 _id, float _x, float _y, float _z, float _yaw, bool _
autocontinue(_autocontinue),
current(_current),
orbit(_orbit),
holdTime(_holdTime)
holdTime(_holdTime),
frame(_frame),
action(_action)
{
}
......@@ -100,9 +103,14 @@ void Waypoint::setYaw(float yaw)
this->yaw = yaw;
}
void Waypoint::setType(type_enum type)
void Waypoint::setAction(MAV_ACTION action)
{
this->type = type;
this->action = action;
}
void Waypoint::setFrame(MAV_FRAME frame)
{
this->frame = frame;
}
void Waypoint::setAutocontinue(bool autoContinue)
......
......@@ -36,14 +36,16 @@ This file is part of the PIXHAWK project
#include <QObject>
#include <QString>
#include <QTextStream>
#include <inttypes.h>
#include "mavlink_types.h"
class Waypoint : public QObject
{
Q_OBJECT
public:
Waypoint(quint16 id = 0, float x = 0.0f, float y = 0.0f, float z = 0.0f, float yaw = 0.0f, bool autocontinue = false, bool current = false, float orbit = 0.1f, int holdTime = 2000);
Waypoint(quint16 id = 0, float x = 0.0f, float y = 0.0f, float z = 0.0f, float yaw = 0.0f, bool autocontinue = false,
bool current = false, float orbit = 0.1f, int holdTime = 2000,
MAV_FRAME frame=MAV_FRAME_GLOBAL, MAV_ACTION action=MAV_ACTION_NAVIGATE);
~Waypoint();
quint16 getId() const { return id; }
......@@ -55,26 +57,20 @@ public:
bool getCurrent() const { return current; }
float getOrbit() const { return orbit; }
float getHoldTime() const { return holdTime; }
MAV_FRAME getFrame() const { return frame; }
MAV_ACTION getAction() const { return action; }
void save(QTextStream &saveStream);
bool load(QTextStream &loadStream);
enum type_enum
{
GLOBAL = 0,
LOCAL = 1,
GLOBAL_ORBIT = 2,
LOCAL_ORBIT = 3
};
protected:
quint16 id;
float x;
float y;
float z;
float yaw;
type_enum type;
MAV_FRAME frame;
MAV_ACTION action;
bool autocontinue;
bool current;
float orbit;
......@@ -86,7 +82,8 @@ public slots:
void setY(float y);
void setZ(float z);
void setYaw(float yaw);
void setType(type_enum type);
void setAction(MAV_ACTION action);
void setFrame(MAV_FRAME frame);
void setAutocontinue(bool autoContinue);
void setCurrent(bool current);
void setOrbit(float orbit);
......
......@@ -29,7 +29,7 @@ This file is part of the QGROUNDCONTROL project
#include "MAVLinkLightProtocol.h"
#include "UASManager.h"
#include "ArduPilotMAV.h"
#include "ArduPilotMegaMAV.h"
#include "LinkManager.h"
MAVLinkLightProtocol::MAVLinkLightProtocol() :
......@@ -113,7 +113,7 @@ void MAVLinkLightProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// // Check and (if necessary) create UAS object
// if (uas == NULL)
// {
// ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// ArduPilotMegaMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// // Connect this robot to the UAS object
// // it is IMPORTANT here to use the right object type,
// // else the slot of the parent object is called (and thus the special
......
......@@ -42,7 +42,7 @@ This file is part of the QGROUNDCONTROL project
#include "UAS.h"
#include "SlugsMAV.h"
#include "PxQuadMAV.h"
#include "ArduPilotMAV.h"
#include "ArduPilotMegaMAV.h"
#include "configuration.h"
#include "LinkManager.h"
#include <QGCMAVLink.h>
......@@ -186,9 +186,9 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
uas = mav;
}
break;
case MAV_AUTOPILOT_ARDUPILOT:
case MAV_AUTOPILOT_ARDUPILOTMEGA:
{
ArduPilotMAV* mav = new ArduPilotMAV(this, message.sysid);
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(this, message.sysid);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
......
......@@ -425,7 +425,7 @@ void MAVLinkSimulationLink::mainloop()
static int rcCounter = 0;
if (rcCounter == 2)
{
mavlink_rc_channels_t chan;
mavlink_rc_channels_raw_t chan;
chan.chan1_raw = 1000 + ((int)(fabs(x) * 1000) % 2000);
chan.chan2_raw = 1000 + ((int)(fabs(y) * 1000) % 2000);
chan.chan3_raw = 1000 + ((int)(fabs(z) * 1000) % 2000);
......@@ -434,15 +434,7 @@ void MAVLinkSimulationLink::mainloop()
chan.chan6_raw = (chan.chan3_raw + chan.chan2_raw) / 2.0f;
chan.chan7_raw = (chan.chan4_raw + chan.chan2_raw) / 2.0f;
chan.chan8_raw = (chan.chan6_raw + chan.chan2_raw) / 2.0f;
chan.chan1_255 = ((chan.chan1_raw - 1000)/1000.0f) * 255.0f;
chan.chan2_255 = ((chan.chan2_raw - 1000)/1000.0f) * 255.0f;
chan.chan3_255 = ((chan.chan3_raw - 1000)/1000.0f) * 255.0f;
chan.chan4_255 = ((chan.chan4_raw - 1000)/1000.0f) * 255.0f;
chan.chan5_255 = ((chan.chan5_raw - 1000)/1000.0f) * 255.0f;
chan.chan6_255 = ((chan.chan6_raw - 1000)/1000.0f) * 255.0f;
chan.chan7_255 = ((chan.chan7_raw - 1000)/1000.0f) * 255.0f;
chan.chan8_255 = ((chan.chan8_raw - 1000)/1000.0f) * 255.0f;
messageSize = mavlink_msg_rc_channels_encode(systemId, componentId, &msg, &chan);
messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan);
// Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream
......
......@@ -323,7 +323,7 @@ void OpalLink::getSignals()
if (sendRCValues)
{
mavlink_message_t rc;
mavlink_msg_rc_channels_pack(systemID, componentID, &rc,
mavlink_msg_rc_channels_raw_pack(systemID, componentID, &rc,
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_1]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_2]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_3]),
......@@ -332,14 +332,6 @@ void OpalLink::getSignals()
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_6]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_7]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_8]),
rescaleNorm(values[OpalRT::NORM_CHANNEL_1], OpalRT::NORM_CHANNEL_1),
rescaleNorm(values[OpalRT::NORM_CHANNEL_2], OpalRT::NORM_CHANNEL_2),
rescaleNorm(values[OpalRT::NORM_CHANNEL_3], OpalRT::NORM_CHANNEL_3),
rescaleNorm(values[OpalRT::NORM_CHANNEL_4], OpalRT::NORM_CHANNEL_4),
rescaleNorm(values[OpalRT::NORM_CHANNEL_5], OpalRT::NORM_CHANNEL_5),
rescaleNorm(values[OpalRT::NORM_CHANNEL_6], OpalRT::NORM_CHANNEL_6),
rescaleNorm(values[OpalRT::NORM_CHANNEL_7], OpalRT::NORM_CHANNEL_7),
rescaleNorm(values[OpalRT::NORM_CHANNEL_8], OpalRT::NORM_CHANNEL_8),
0 //rssi unused
);
receiveMessage(rc);
......
......@@ -27,9 +27,9 @@ This file is part of the QGROUNDCONTROL project
* @author Your Name here
*/
#include "ArduPilotMAV.h"
#include "ArduPilotMegaMAV.h"
ArduPilotMAV::ArduPilotMAV(MAVLinkProtocol* mavlink, int id) :
ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// place other initializers here
{
......@@ -43,7 +43,7 @@ ArduPilotMAV::ArduPilotMAV(MAVLinkProtocol* mavlink, int id) :
* messages can be sent back to the system via this link
* @param message MAVLink message, as received from the MAVLink protocol stack
*/
void ArduPilotMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
void ArduPilotMegaMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
// Let UAS handle the default message set
UAS::receiveMessage(link, message);
......
......@@ -21,16 +21,16 @@ This file is part of the QGROUNDCONTROL project
======================================================================*/
#ifndef ARDUPILOTMAV_H
#define ARDUPILOTMAV_H
#ifndef ARDUPILOTMEGAMAV_H
#define ARDUPILOTMEGAMAV_H
#include "UAS.h"
class ArduPilotMAV : public UAS
class ArduPilotMegaMAV : public UAS
{
Q_OBJECT
public:
ArduPilotMAV(MAVLinkProtocol* mavlink, int id = 0);
ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
......
......@@ -410,41 +410,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(&message, &channels);
mavlink_rc_channels_raw_t channels;
mavlink_msg_rc_channels_raw_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
for (int i = 0; i < 8; i++)
{
switch (i)
{
case 0:
emit remoteControlChannelChanged(i, channels.chan1_raw, channels.chan1_255/255.0f);
break;
case 1:
emit remoteControlChannelChanged(i, channels.chan2_raw, channels.chan2_255/255.0f);
break;
case 2:
emit remoteControlChannelChanged(i, channels.chan3_raw, channels.chan3_255/255.0f);
break;
case 3:
emit remoteControlChannelChanged(i, channels.chan4_raw, channels.chan4_255/255.0f);
break;
case 4:
emit remoteControlChannelChanged(i, channels.chan5_raw, channels.chan5_255/255.0f);
break;
case 5:
emit remoteControlChannelChanged(i, channels.chan6_raw, channels.chan6_255/255.0f);
break;
case 6:
emit remoteControlChannelChanged(i, channels.chan7_raw, channels.chan7_255/255.0f);
break;
case 7:
emit remoteControlChannelChanged(i, channels.chan8_raw, channels.chan8_255/255.0f);
break;
}
}
emit remoteControlChannelRawChanged(0, channels.chan1_raw);
emit remoteControlChannelRawChanged(1, channels.chan2_raw);
emit remoteControlChannelRawChanged(2, channels.chan3_raw);
emit remoteControlChannelRawChanged(3, channels.chan4_raw);
emit remoteControlChannelRawChanged(4, channels.chan5_raw);
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
{
mavlink_rc_channels_scaled_t channels;
mavlink_msg_rc_channels_scaled_decode(&message, &channels);
emit remoteControlRSSIChanged(channels.rssi/255.0f);
emit remoteControlChannelScaledChanged(0, channels.chan1_scaled/10000.0f);
emit remoteControlChannelScaledChanged(1, channels.chan2_scaled/10000.0f);
emit remoteControlChannelScaledChanged(2, channels.chan3_scaled/10000.0f);
emit remoteControlChannelScaledChanged(3, channels.chan4_scaled/10000.0f);
emit remoteControlChannelScaledChanged(4, channels.chan5_scaled/10000.0f);
emit remoteControlChannelScaledChanged(5, channels.chan6_scaled/10000.0f);
emit remoteControlChannelScaledChanged(6, channels.chan7_scaled/10000.0f);
emit remoteControlChannelScaledChanged(7, channels.chan8_scaled/10000.0f);
}
break;
case MAVLINK_MSG_ID_PARAM_VALUE:
......
......@@ -356,8 +356,10 @@ signals:
void positionZControlEnabled(bool enabled);
/** @brief Heading control enabled/disabled */
void positionYawControlEnabled(bool enabled);
/** @brief Value of a remote control channel */
void remoteControlChannelChanged(int channelId, float raw, float normalized);
/** @brief Value of a remote control channel (raw) */
void remoteControlChannelRawChanged(int channelId, float raw);
/** @brief Value of a remote control channel (scaled)*/
void remoteControlChannelScaledChanged(int channelId, float normalized);
/** @brief Remote control RSSI changed */
void remoteControlRSSIChanged(float rssi);
/** @brief Radio Calibration Data has been received from the MAV*/
......
......@@ -132,7 +132,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if(wp->seq == current_wp_id)
{
Waypoint *lwp = new Waypoint(wp->seq, wp->x, wp->y, wp->z, wp->yaw, wp->autocontinue, wp->current, wp->param1, wp->param2);
localAddWaypoint(lwp);
addWaypoint(lwp);
//get next waypoint
current_wp_id++;
......@@ -288,7 +288,7 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq)
return -1;
}
void UASWaypointManager::localAddWaypoint(Waypoint *wp)
void UASWaypointManager::addWaypoint(Waypoint *wp)
{
if (wp)
{
......@@ -298,7 +298,7 @@ void UASWaypointManager::localAddWaypoint(Waypoint *wp)
}
}
int UASWaypointManager::localRemoveWaypoint(quint16 seq)
int UASWaypointManager::removeWaypoint(quint16 seq)
{
if (seq < waypoints.size())
{
......@@ -316,7 +316,7 @@ int UASWaypointManager::localRemoveWaypoint(quint16 seq)
return -1;
}
void UASWaypointManager::localMoveWaypoint(quint16 cur_seq, quint16 new_seq)
void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
{
if (cur_seq != new_seq && cur_seq < waypoints.size() && new_seq < waypoints.size())
{
......@@ -344,7 +344,7 @@ void UASWaypointManager::localMoveWaypoint(quint16 cur_seq, quint16 new_seq)
}
}
void UASWaypointManager::localSaveWaypoints(const QString &saveFile)
void UASWaypointManager::saveWaypoints(const QString &saveFile)
{
QFile file(saveFile);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text))
......@@ -358,7 +358,7 @@ void UASWaypointManager::localSaveWaypoints(const QString &saveFile)
file.close();
}
void UASWaypointManager::localLoadWaypoints(const QString &loadFile)
void UASWaypointManager::loadWaypoints(const QString &loadFile)
{
QFile file(loadFile);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
......@@ -386,16 +386,6 @@ void UASWaypointManager::localLoadWaypoints(const QString &loadFile)
emit waypointListChanged();
}
void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
{
}
int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
{
return 0;
}
void UASWaypointManager::clearWaypointList()
{
if(current_state == WP_IDLE)
......@@ -474,8 +464,8 @@ void UASWaypointManager::writeWaypoints()
cur_d->orbit_direction = 0;
cur_d->param1 = cur_s->getOrbit();
cur_d->param2 = cur_s->getHoldTime();
// TODO: Replace this value depending on the type of waypoint
cur_d->type = 1; //FIXME: we only use local waypoints at the moment
cur_d->frame = cur_s->getFrame();
cur_d->action = cur_s->getAction();
cur_d->seq = i; // don't read out the sequence number of the waypoint class
cur_d->x = cur_s->getX();
cur_d->y = cur_s->getY();
......
......@@ -79,25 +79,18 @@ public:
/*@{*/
void clearWaypointList(); ///< Sends the waypoint clear all message to the MAV
void readWaypoints(); ///< Requests the MAV's current waypoint list
void writeWaypoints(); ///< Sends the local waypoint list to the MAV
void writeWaypoints(); ///< Sends the waypoint list to the MAV
int setCurrentWaypoint(quint16 seq); ///< Changes the current waypoint and sends the sequence number of the waypoint that should get the new target waypoint to the UAS
/*@}*/
/** @name Local waypoint list operations */
/** @name Waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the local waypoint list.
void localAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int localRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void localMoveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void localSaveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void localLoadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
/*@}*/
/** @name Global waypoint list operations */
/*@{*/
const QVector<Waypoint *> &getGlobalWaypointList(void) { return waypoints; } ///< Returns a const reference to the global waypoint list.
void globalAddWaypoint(Waypoint *wp); ///< locally adds a new waypoint to the end of the list and changes its sequence number accordingly
int globalRemoveWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
const QVector<Waypoint *> &getWaypointList(void) { return waypoints; } ///< Returns a const reference to the waypoint list.
void addWaypoint(Waypoint *wp); ///< adds a new waypoint to the end of the list and changes its sequence number accordingly
int removeWaypoint(quint16 seq); ///< locally remove the specified waypoint from the storage
void moveWaypoint(quint16 cur_seq, quint16 new_seq); ///< locally move a waypoint from its current position cur_seq to a new position new_seq
void saveWaypoints(const QString &saveFile); ///< saves the local waypoint list to saveFile
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
/*@}*/
private:
......
......@@ -206,13 +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, QPointF)), waypointsDockWidget->widget(), SLOT(setIsWPGlobal(bool, QPointF)));
connect(mapWidget, SIGNAL(sendGeometryEndDrag(QPointF,int)), waypointsDockWidget->widget(), SLOT(waypointGlobalChanged(QPointF,int)) );
//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)));
//connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
}
}
......
......@@ -96,10 +96,11 @@ void QGCRemoteControlView::setUASId(int id)
if (uas)
{
// 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)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float,float)), this, SLOT(setChannel(int,float,float)));
disconnect(uas, SIGNAL(remoteControlRSSIRawChanged(float)), this, SLOT(setRemoteRSSI(float)));
disconnect(uas, SIGNAL(radioCalibrationRawReceived(const QPointer<RadioCalibrationData>)), calibrationWindow, SLOT(receive(const QPointer<RadioCalibrationData>&)));
disconnect(uas, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
disconnect(uas, SIGNAL(remoteControlChannelScaledChanged(int,float,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
......@@ -111,25 +112,49 @@ void QGCRemoteControlView::setUASId(int id)
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)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), this, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelRawChanged(int,float)), calibrationWindow, SLOT(setChannelRaw(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), this, SLOT(setChannelScaled(int,float)));
connect(newUAS, SIGNAL(remoteControlChannelScaledChanged(int,float)), calibrationWindow, SLOT(setChannelScaled(int,float)));
}
}
void QGCRemoteControlView::setChannel(int channelId, float raw, float normalized)
void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
{
if (this->raw.size() <= channelId)
{
// This is a new channel, append it
this->raw.append(raw);
this->normalized.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, aupdate it
this->raw[channelId] = raw;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
{
if (this->raw.size() <= channelId) // using raw vector as size indicator
{
// This is a new channel, append it
this->normalized.append(normalized);
this->raw.append(0);
appendChannelWidget(channelId);
}
else
{
// This is an existing channel, update it
this->raw[channelId] = raw;
this->normalized[channelId] = normalized;
}
updated = true;
......@@ -156,8 +181,9 @@ void QGCRemoteControlView::appendChannelWidget(int channelId)
layout->addWidget(raw);
// Append progress bar
QProgressBar* normalized = new QProgressBar(this);
normalized->setMinimum(0);
normalized->setMinimum(-100);
normalized->setMaximum(100);
normalized->setFormat("%v%");
progressBars.append(normalized);
layout->addWidget(normalized);
channelLayout->addLayout(layout);
......
......@@ -52,7 +52,8 @@ public:
public slots:
void setUASId(int id);
void setChannel(int channelId, float raw, float normalized);
void setChannelRaw(int channelId, float raw);
void setChannelScaled(int channelId, float normalized);
void setRemoteRSSI(float rssiNormalized);
void redraw();
......
......@@ -165,8 +165,20 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="textVisible">
<bool>true</bool>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan2ProgressBar">
......@@ -178,8 +190,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan3ProgressBar">
......@@ -191,8 +209,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan4ProgressBar">
......@@ -204,8 +228,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan5ProgressBar">
......@@ -217,8 +247,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan6ProgressBar">
......@@ -230,8 +266,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan7ProgressBar">
......@@ -243,8 +285,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QProgressBar" name="chan8ProgressBar">
......@@ -256,8 +304,14 @@
<height>16</height>
</rect>
</property>
<property name="minimum">
<number>-100</number>
</property>
<property name="value">
<number>24</number>
<number>0</number>
</property>
<property name="format">
<string>%v%</string>
</property>
</widget>
<widget class="QLabel" name="label_11">
......
This diff is collapsed.
......@@ -56,7 +56,7 @@ class WaypointList : public QWidget {
virtual ~WaypointList();
public slots:
void updateLocalPosition(UASInterface*, double x, double y, double z, quint64 usec);
void updatePosition(UASInterface*, double x, double y, double z, quint64 usec);
void updateAttitude(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
void setUAS(UASInterface* uas);
......@@ -77,7 +77,7 @@ public slots:
/** @brief Add a waypoint by mouse click over the map */
void addWaypointMouse(QPointF coordinate);
/** @brief it notifies that a global waypoint goes to do created */
void setIsWPGlobal(bool value, QPointF centerCoordinate);
//void setIsWPGlobal(bool value, QPointF centerCoordinate);
//Update events
......@@ -93,9 +93,9 @@ public slots:
/** @brief The MapWidget informs that a waypoint global was changed on the map */
void waypointGlobalChanged(const QPointF coordinate, const int indexWP);
void clearLocalWPWidget();
void clearWPWidget();
void changeWPPositionBySpinBox(Waypoint* wp);
//void changeWPPositionBySpinBox(Waypoint* wp);
// Waypoint operations
void moveUp(Waypoint* wp);
......@@ -109,7 +109,7 @@ signals:
void clearPathclicked();
void createWaypointAtMap(const QPointF coordinate);
// void ChangeWaypointGlobalPosition(int index, QPointF coord);
void changePositionWPGlobalBySpinBox(int indexWP, float lat, float lon);
void changePositionWPBySpinBox(int indexWP, float lat, float lon);
......@@ -118,15 +118,13 @@ protected:
protected:
QMap<Waypoint*, WaypointView*> wpViews;
QMap<Waypoint*, WaypointGlobalView*> wpGlobalViews;
//QMap<Waypoint*, WaypointGlobalView*> wpGlobalViews;
QVBoxLayout* listLayout;
UASInterface* uas;
double mavX;
double mavY;
double mavZ;
double mavYaw;
bool isGlobalWP;
bool isLocalWP;
QPointF centerMapCoordinate;
private:
......
......@@ -46,16 +46,32 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui->setupUi(this);
this->wp = wp;
wp->setType(Waypoint::LOCAL);
m_ui->orbitSpinBox->setEnabled(false);
m_ui->orbitSpinBox->hide();
wp->setFrame(MAV_FRAME_LOCAL);
// add actions
m_ui->comboBox_action->addItem("Navigate",MAV_ACTION_NAVIGATE);
m_ui->comboBox_action->addItem("TakeOff",MAV_ACTION_TAKEOFF);
m_ui->comboBox_action->addItem("Land",MAV_ACTION_LAND);
m_ui->comboBox_action->addItem("Loiter",MAV_ACTION_LOITER);
// add frames
m_ui->comboBox_frame->addItem("Global",MAV_FRAME_GLOBAL);
m_ui->comboBox_frame->addItem("Local",MAV_FRAME_LOCAL);
// defaults
changedAction(0);
changedFrame(0);
// Read values and set user interface
updateValues();
connect(m_ui->xSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->ySpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->zSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(m_ui->posNSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->posESpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->posDSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
connect(m_ui->lonSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setX(double)));
connect(m_ui->latSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setY(double)));
connect(m_ui->altSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setZ(double)));
//hidden degree to radian conversion of the yaw angle
connect(m_ui->yawSpinBox, SIGNAL(valueChanged(int)), this, SLOT(setYaw(int)));
......@@ -67,9 +83,8 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->autoContinue, SIGNAL(stateChanged(int)), this, SLOT(changedAutoContinue(int)));
connect(m_ui->selectedBox, SIGNAL(stateChanged(int)), this, SLOT(changedCurrent(int)));
connect(m_ui->orbitCheckBox, SIGNAL(stateChanged(int)), this, SLOT(changeOrbitalState(int)));
connect(m_ui->comboBox_action, SIGNAL(activated(int)), this, SLOT(changedAction(int)));
connect(m_ui->comboBox_frame, SIGNAL(activated(int)), this, SLOT(changedFrame(int)));
connect(m_ui->orbitSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setOrbit(double)));
connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
......@@ -104,6 +119,72 @@ void WaypointView::changedAutoContinue(int state)
wp->setAutocontinue(true);
}
void WaypointView::changedAction(int index)
{
// set action for waypoint
// hide everything to start
m_ui->orbitSpinBox->hide();
m_ui->takeOffAngleSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
// set waypoint action
MAV_ACTION action = (MAV_ACTION)m_ui->comboBox_action->itemData(index).toUInt();
wp->setAction(action);
// expose ui based on action
switch(action)
{
case MAV_ACTION_TAKEOFF:
m_ui->takeOffAngleSpinBox->show();
break;
case MAV_ACTION_LAND:
break;
case MAV_ACTION_NAVIGATE:
m_ui->autoContinue->show();
break;
case MAV_ACTION_LOITER:
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
break;
default:
std::cerr << "unknown action" << std::endl;
}
}
void WaypointView::changedFrame(int index)
{
// hide everything to start
m_ui->lonSpinBox->hide();
m_ui->latSpinBox->hide();
m_ui->altSpinBox->hide();
m_ui->posNSpinBox->hide();
m_ui->posESpinBox->hide();
m_ui->posDSpinBox->hide();
// set waypoint action
MAV_FRAME frame = (MAV_FRAME)m_ui->comboBox_frame->itemData(index).toUInt();
wp->setFrame(frame);
switch(frame)
{
case MAV_FRAME_GLOBAL:
m_ui->lonSpinBox->show();
m_ui->latSpinBox->show();
m_ui->altSpinBox->show();
break;
case MAV_FRAME_LOCAL:
m_ui->posNSpinBox->show();
m_ui->posESpinBox->show();
m_ui->posDSpinBox->show();
break;
default:
std::cerr << "unknown frame" << std::endl;
}
}
void WaypointView::changedCurrent(int state)
{
if (state == 0)
......@@ -121,9 +202,41 @@ void WaypointView::changedCurrent(int state)
void WaypointView::updateValues()
{
m_ui->xSpinBox->setValue(wp->getX());
m_ui->ySpinBox->setValue(wp->getY());
m_ui->zSpinBox->setValue(wp->getZ());
// update frame
MAV_FRAME frame = wp->getFrame();
changedFrame(m_ui->comboBox_frame->findData(frame));
switch(frame)
{
case(MAV_FRAME_LOCAL):
m_ui->posNSpinBox->setValue(wp->getX());
m_ui->posESpinBox->setValue(wp->getY());
m_ui->posDSpinBox->setValue(wp->getZ());
break;
case(MAV_FRAME_GLOBAL):
m_ui->lonSpinBox->setValue(wp->getX());
m_ui->latSpinBox->setValue(wp->getY());
m_ui->altSpinBox->setValue(wp->getZ());
break;
}
// update action
MAV_ACTION action = wp->getAction();
changedFrame(m_ui->comboBox_frame->findData(frame));
changedAction(m_ui->comboBox_action->findData(action));
switch(action)
{
case MAV_ACTION_TAKEOFF:
break;
case MAV_ACTION_LAND:
break;
case MAV_ACTION_NAVIGATE:
break;
case MAV_ACTION_LOITER:
break;
default:
std::cerr << "unknown action" << std::endl;
}
m_ui->yawSpinBox->setValue(wp->getYaw()/M_PI*180.);
m_ui->selectedBox->setChecked(wp->getCurrent());
m_ui->autoContinue->setChecked(wp->getAutoContinue());
......@@ -159,21 +272,3 @@ void WaypointView::changeEvent(QEvent *e)
break;
}
}
void WaypointView::changeOrbitalState(int state)
{
Q_UNUSED(state);
if(m_ui->orbitCheckBox->isChecked())
{
m_ui->orbitSpinBox->setEnabled(true);
m_ui->orbitSpinBox->show();
wp->setType(Waypoint::LOCAL_ORBIT);
}
else
{
m_ui->orbitSpinBox->setEnabled(false);
m_ui->orbitSpinBox->hide();
wp->setType(Waypoint::LOCAL);
}
}
......@@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include <QtGui/QWidget>
#include "Waypoint.h"
#include <iostream>
namespace Ui {
class WaypointView;
......@@ -56,7 +57,8 @@ public slots:
void moveDown();
void remove();
void changedAutoContinue(int);
void changeOrbitalState(int state);
void changedFrame(int state);
void changedAction(int state);
void changedCurrent(int);
void updateValues(void);
......
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