Commit ab3a1ec0 authored by hengli's avatar hengli

Added command to select target position for robot - command can be accessed...

Added command to select target position for robot - command can be accessed via a right-click in the 3D View perspective --Lionel
parents 57207de3 804d81cf
......@@ -43,9 +43,8 @@ DEPENDPATH += . \
INCLUDEPATH += . \
lib/QMapControl \
$$BASEDIR/../mavlink/contrib/slugs/include \
$$BASEDIR/../mavlink/include \
/usr/include/freetype2
LIBS += /usr/lib/libftgl.so /usr/lib/libglut.so
$$BASEDIR/../mavlink/include
LIBS += -lglut
# ../mavlink/include \
# MAVLink/include \
......@@ -160,7 +159,6 @@ HEADERS += src/MG.h \
src/ui/linechart/IncrementalPlot.h \
src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \
src/ui/map/QGC2DIcon.h \
src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \
......@@ -230,7 +228,6 @@ SOURCES += src/main.cc \
src/ui/linechart/IncrementalPlot.cc \
src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \
src/ui/map/QGC2DIcon.cc \
src/ui/QGCRemoteControlView.cc \
src/WaypointGlobal.cpp \
src/ui/WaypointGlobalView.cpp \
......
......@@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength;
// GPS RAW
mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0, 2.5f, 0.1f);
mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0, 2.5f, 0.1f);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength;
// GLOBAL POSITION
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0);
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream
memcpy(stream+streampointer,buffer, bufferlength);
......
This diff is collapsed.
......@@ -246,6 +246,29 @@ void OpalLink::getSignals()
values[OpalRT::B_W_2]
);
receiveMessage(bias);
/* send radio outputs */
mavlink_message_t rc;
mavlink_msg_rc_channels_pack(systemID, componentID, &rc,
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_1]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_2]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_3]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_4]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_5]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_6]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_7]),
duty2PulseMicros(values[OpalRT::RAW_CHANNEL_8]),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_1]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_2]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_3]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_4]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_5]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_6]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_7]*255),
static_cast<uint8_t>(values[OpalRT::NORM_CHANNEL_8]*255),
0 //rssi unused
);
receiveMessage(rc);
}
else if (returnVal != EAGAIN) // if returnVal == EAGAIN => data just wasn't ready
{
......@@ -294,6 +317,12 @@ bool OpalLink::isConnected() {
return connectState;
}
uint16_t OpalLink::duty2PulseMicros(double duty)
{
/* duty cycle assumed to be of a signal at 70 Hz */
return static_cast<uint16_t>(duty/70*1000000);
}
......
......@@ -151,6 +151,8 @@ protected:
OpalRT::ParameterList *params;
unsigned short opalInstID;
uint16_t duty2PulseMicros(double duty);
};
#endif // OPALLINK_H
......@@ -41,7 +41,7 @@ namespace OpalRT
Configuration info for the model
*/
const unsigned short NUM_OUTPUT_SIGNALS=39;
const unsigned short NUM_OUTPUT_SIGNALS=57;
/* ------------------------------ Outputs ------------------------------
*
......@@ -85,7 +85,25 @@ namespace OpalRT
B_F_2,
B_W_0,
B_W_1,
B_W_2
B_W_2,
RAW_CHANNEL_1 = 39,
RAW_CHANNEL_2,
RAW_CHANNEL_3,
RAW_CHANNEL_4,
RAW_CHANNEL_5,
RAW_CHANNEL_6,
RAW_CHANNEL_7,
RAW_CHANNEL_8,
NORM_CHANNEL_1,
NORM_CHANNEL_2,
NORM_CHANNEL_3,
NORM_CHANNEL_4,
NORM_CHANNEL_5,
NORM_CHANNEL_6,
NORM_CHANNEL_7,
NORM_CHANNEL_8,
CONTROLLER_AILERON,
CONTROLLER_ELEVATOR
};
/** Component IDs of the parameters. Currently they are all 1 becuase there is no advantage
......
......@@ -365,28 +365,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// only accept values in a realistic range
// quint64 time = getUnixTime(pos.usec);
quint64 time = MG::TIME::getGroundTimeNow();
emit valueChanged(uasId, "lat", pos.lat, time);
emit valueChanged(uasId, "lon", pos.lon, time);
// Check for NaN
int alt = pos.alt;
if (alt != alt)
{
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "alt", pos.alt, time);
// Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v)
{
emit valueChanged(uasId, "speed", pos.v, time);
//qDebug() << "GOT GPS RAW";
emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
if (pos.fix_type > 0)
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
// Check for NaN
int alt = pos.alt;
if (alt != alt)
{
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "alt", pos.alt, time);
// Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v)
{
emit valueChanged(uasId, "speed", pos.v, time);
//qDebug() << "GOT GPS RAW";
emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
}
}
emit globalPositionChanged(this, pos.lon, pos.lat, alt, time);
}
break;
case MAVLINK_MSG_ID_GPS_STATUS:
......
......@@ -100,7 +100,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
topMargin(3.0f)
{
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
refreshTimer->setInterval(60);
refreshTimer->setInterval(120);
// this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this));
......
......@@ -448,7 +448,7 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa
QFont font("Bitstream Vera Sans");
// Enforce minimum font size of 5 pixels
int fSize = qMax(1, (int)(fontSize*scalingFactor*1.26f));
int fSize = qMax(5, (int)(fontSize*scalingFactor*1.26f));
font.setPixelSize(fSize);
QFontMetrics metrics = QFontMetrics(font);
......
......@@ -657,14 +657,14 @@ void MainWindow::loadPixhawkView()
clearView();
// Engineer view, used in EMAV2009
// LINE CHART
if (linechartWidget)
// 3D map
if (map3DWidget)
{
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack)
{
linechartWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget);
//map3DWidget->setActive(true);
centerStack->setCurrentWidget(map3DWidget);
}
}
......@@ -675,6 +675,18 @@ void MainWindow::loadPixhawkView()
controlDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// UAS LIST
if (listDockWidget)
{
......@@ -696,18 +708,6 @@ void MainWindow::loadPixhawkView()
waypointsDockWidget->show();
}
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// DEBUG CONSOLE
if (debugConsoleDockWidget)
{
......@@ -715,13 +715,6 @@ void MainWindow::loadPixhawkView()
debugConsoleDockWidget->show();
}
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
// ONBOARD PARAMETERS
if (parametersDockWidget)
{
......@@ -981,6 +974,13 @@ void MainWindow::loadEngineerView()
parametersDockWidget->show();
}
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
this->show();
}
......
......@@ -37,6 +37,8 @@ This file is part of the QGROUNDCONTROL project
#include "ui_MapWidget.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "MAV2DIcon.h"
#include "Waypoint2DIcon.h"
#include "MG.h"
......@@ -53,7 +55,7 @@ MapWidget::MapWidget(QWidget *parent) :
this->setFocusPolicy(Qt::StrongFocus);
// create MapControl
mc = new MapControl(QSize(320, 240));
mc = new qmapcontrol::MapControl(QSize(320, 240));
mc->showScale(true);
mc->showCoord(true);
mc->enablePersistentCache();
......@@ -62,21 +64,21 @@ MapWidget::MapWidget(QWidget *parent) :
// create MapAdapter to get maps from
//TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17);
MapAdapter* mapadapter_overlay = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1");
// MAP BACKGROUND
mapadapter = new GoogleSatMapAdapter();
l = new MapLayer("Google Satellite", mapadapter);
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l = new qmapcontrol::MapLayer("Google Satellite", mapadapter);
mc->addLayer(l);
// STREET OVERLAY
overlay = new MapLayer("Overlay", mapadapter_overlay);
overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay);
overlay->setVisible(false);
mc->addLayer(overlay);
// WAYPOINT LAYER
// create a layer with the mapadapter and type GeometryLayer (for waypoints)
geomLayer = new GeometryLayer("Waypoints", mapadapter);
geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter);
mc->addLayer(geomLayer);
//
......@@ -188,6 +190,7 @@ MapWidget::MapWidget(QWidget *parent) :
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)),
this, SLOT(addUAS(UASInterface*)));
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*)));
connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)),
this, SLOT(captureMapClick(const QMouseEvent*, const QPointF)));
......@@ -208,7 +211,7 @@ MapWidget::MapWidget(QWidget *parent) :
pointPen = new QPen(QColor(0, 255,0));
pointPen->setWidth(3);
path = new LineString (wps, "UAV Path", pointPen);
path = new qmapcontrol::LineString (wps, "UAV Path", pointPen);
mc->layer("Waypoints")->addGeometry(path);
this->setVisible(false);
......@@ -224,7 +227,7 @@ void MapWidget::mapproviderSelected(QAction* action)
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new OSMMapAdapter();
mapadapter = new qmapcontrol::OSMMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
......@@ -240,7 +243,7 @@ void MapWidget::mapproviderSelected(QAction* action)
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new YahooMapAdapter();
mapadapter = new qmapcontrol::YahooMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
......@@ -256,7 +259,7 @@ void MapWidget::mapproviderSelected(QAction* action)
QPointF a = mc->currentCoordinate();
mc->setZoom(0);
mapadapter = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1");
l->setMapAdapter(mapadapter);
mc->updateRequestNew();
......@@ -267,7 +270,7 @@ void MapWidget::mapproviderSelected(QAction* action)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new GoogleMapAdapter();
mapadapter = new qmapcontrol::GoogleMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
......@@ -281,7 +284,7 @@ void MapWidget::mapproviderSelected(QAction* action)
{
int zoom = mapadapter->adaptedZoom();
mc->setZoom(0);
mapadapter = new GoogleSatMapAdapter();
mapadapter = new qmapcontrol::GoogleSatMapAdapter();
l->setMapAdapter(mapadapter);
geomLayer->setMapAdapter(mapadapter);
......@@ -342,10 +345,19 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
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);
Waypoint2DIcon* tempCirclePoint;
if (mav)
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor()));
}
else
{
tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle);
}
mc->layer("Waypoints")->addGeometry(tempCirclePoint);
Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str);
qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str);
wps.append(tempPoint);
path->addPoint(tempPoint);
......@@ -360,7 +372,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
}
}
void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
void MapWidget::captureGeometryClick(qmapcontrol::Geometry* geom, QPoint point){
Q_UNUSED(geom);
Q_UNUSED(point);
......@@ -369,29 +381,35 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){
}
void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){
void MapWidget::captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate){
Q_UNUSED(coordinate);
// Refresh the screen
mc->updateRequestNew();
int temp = 0;
Point* point2Find;
qmapcontrol::Point* point2Find;
point2Find = wpIndex[geom->name()];
point2Find->setCoordinate(coordinate);
point2Find = dynamic_cast <Point*> (geom);
point2Find->setCoordinate(coordinate);
if (point2Find)
{
point2Find->setCoordinate(coordinate);
// qDebug() << geom->name();
temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
point2Find = dynamic_cast <qmapcontrol::Point*> (geom);
if (point2Find)
{
point2Find->setCoordinate(coordinate);
// qDebug() << geom->name();
temp = geom->get_myIndex();
//qDebug() << temp;
emit sendGeometryEndDrag(coordinate,temp);
}
}
}
void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate)
void MapWidget::captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate)
{
mc->setMouseMode(qmapcontrol::MapControl::Panning);
......@@ -411,10 +429,18 @@ MapWidget::~MapWidget()
*/
void MapWidget::addUAS(UASInterface* uas)
{
mav = uas;
connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
}
void MapWidget::activeUASSet(UASInterface* uas)
{
if (uas)
{
mav = uas;
path->setPen(new QPen(mav->getColor()));
}
}
/**
* Updates the global position of one MAV and append the last movement to the trail
*
......@@ -446,19 +472,19 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Icon
QPen* pointpen = new QPen(uasColor);
CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen);
MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen);
uasIcons.insert(uas->getUASID(), p);
geomLayer->addGeometry(p);
// Line
// A QPen also can use transparency
QList<Point*> points;
points.append(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QList<qmapcontrol::Point*> points;
points.append(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
QPen* linepen = new QPen(uasColor.darker());
linepen->setWidth(2);
// Add the Points and the QPen to a LineString
LineString* ls = new LineString(points, uas->getUASName(), linepen);
qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen);
uasTrails.insert(uas->getUASID(), ls);
// Add the LineString to the layer
......@@ -466,10 +492,14 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
}
else
{
CirclePoint* p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
MAV2DIcon* p = dynamic_cast<MAV2DIcon*>(uasIcons.value(uas->getUASID()));
if (p)
{
p->setCoordinate(QPointF(lat, lon));
p->setYaw(uas->getYaw());
}
// Extend trail
uasTrails.value(uas->getUASID())->addPoint(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon)));
}
// points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen));
......
......@@ -44,8 +44,6 @@ namespace Ui {
class MapWidget;
}
using namespace qmapcontrol;
/**
* @brief 2D Moving map
*
......@@ -60,6 +58,7 @@ public:
public slots:
void addUAS(UASInterface* uas);
void activeUASSet(UASInterface* uas);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
void updatePosition(float time, double lat, double lon);
......@@ -86,8 +85,8 @@ protected:
QMenu* mapMenu;
QPushButton* mapButton;
MapControl* mc; ///< QMapControl widget
MapAdapter* mapadapter; ///< Adapter to load the map data
qmapcontrol::MapControl* mc; ///< QMapControl widget
qmapcontrol::MapAdapter* mapadapter; ///< Adapter to load the map data
qmapcontrol::Layer* l; ///< Current map layer (background)
qmapcontrol::Layer* overlay; ///< Street overlay (foreground)
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
......@@ -98,18 +97,18 @@ protected:
//Layer* gSatLayer;
QMap<int, CirclePoint*> uasIcons;
QMap<int, LineString*> uasTrails;
QMap<int, qmapcontrol::Point*> uasIcons;
QMap<int, qmapcontrol::LineString*> uasTrails;
UASInterface* mav;
quint64 lastUpdate;
protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
void createPathButtonClicked(bool checked);
void captureGeometryClick(Geometry*, QPoint);
void captureGeometryClick(qmapcontrol::Geometry*, QPoint);
void mapproviderSelected(QAction* action);
void captureGeometryDrag(Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(Geometry* geom, QPointF coordinate);
void captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate);
void captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate);
......@@ -122,9 +121,9 @@ protected:
private:
Ui::MapWidget *m_ui;
QList<Point*> wps;
QHash <QString, Point*> wpIndex;
LineString* path;
QList<qmapcontrol::Point*> wps;
QHash <QString, qmapcontrol::Point*> wpIndex;
qmapcontrol::LineString* path;
QPen* pointPen;
};
......
......@@ -13,7 +13,16 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout">
<layout class="QGridLayout" name="gridLayout" rowstretch="2,10,5">
<property name="horizontalSpacing">
<number>5</number>
</property>
<property name="verticalSpacing">
<number>2</number>
</property>
<property name="margin">
<number>6</number>
</property>
<item row="0" column="0">
<widget class="QLabel" name="label">
<property name="text">
......@@ -30,6 +39,9 @@
<string>Onboard Parameters</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="margin">
<number>3</number>
</property>
<item>
<widget class="QStackedWidget" name="stackedWidget">
<property name="currentIndex">
......
......@@ -45,6 +45,7 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
channelLayout(new QVBoxLayout()),
ui(new Ui::QGCRemoteControlView)
{
//ui->setupUi(this);
QGridLayout* layout = new QGridLayout(this);
layout->addLayout(channelLayout, 1, 0, 1, 2);
......
......@@ -6,135 +6,152 @@
<rect>
<x>0</x>
<y>0</y>
<width>350</width>
<height>545</height>
<width>319</width>
<height>221</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<layout class="QGridLayout" name="gridLayout_4" rowstretch="10,0">
<property name="margin">
<number>0</number>
</property>
<item row="0" column="0">
<widget class="QGroupBox" name="groupBox">
<item row="1" column="0">
<widget class="QGroupBox" name="groupBox_3">
<property name="title">
<string>Activate Extended Output</string>
<string>Calibration Wizards</string>
</property>
<layout class="QGridLayout" name="gridLayout_2">
<property name="margin">
<layout class="QGridLayout" name="gridLayout" columnstretch="5,5">
<property name="leftMargin">
<number>6</number>
</property>
<property name="topMargin">
<number>2</number>
</property>
<property name="rightMargin">
<number>6</number>
</property>
<property name="bottomMargin">
<number>2</number>
</property>
<property name="horizontalSpacing">
<number>12</number>
</property>
<property name="verticalSpacing">
<number>6</number>
</property>
<item row="0" column="0">
<widget class="QCheckBox" name="sendRawCheckBox">
<widget class="QPushButton" name="rcCalButton">
<property name="text">
<string>Send RAW Sensor data</string>
<string>RC Calibration</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QCheckBox" name="sendExtendedCheckBox">
<item row="0" column="1">
<widget class="QPushButton" name="magCalButton">
<property name="text">
<string>Send extended status</string>
<string>Mag. Calibration</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QCheckBox" name="sendRCCheckBox">
<item row="1" column="1">
<widget class="QPushButton" name="gyroCalButton">
<property name="text">
<string>Send RC-values</string>
<string>Gyro Calibration</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QCheckBox" name="sendControllerCheckBox">
<item row="1" column="0">
<widget class="QPushButton" name="pressureCalButton">
<property name="text">
<string>Send raw controller outputs</string>
<string>Pressure Calibration</string>