Browse Source

Added vehicle model selection to 3D view perspective.

QGC4.4
hengli 15 years ago
parent
commit
a3e9bcfab2
  1. 20522
      models/cessna.osg
  2. 9
      qgroundcontrol.pri
  3. 89
      src/input/Freenect.cc
  4. 13
      src/input/Freenect.h
  5. 8
      src/ui/MainWindow.cc
  6. 2
      src/ui/MainWindow.h
  7. 243
      src/ui/map3D/Pixhawk3DWidget.cc
  8. 23
      src/ui/map3D/Pixhawk3DWidget.h
  9. 1
      src/ui/map3D/PixhawkCheetahGeode.cc
  10. 11
      src/ui/map3D/Q3DWidgetFactory.cc
  11. 2
      src/ui/map3D/Q3DWidgetFactory.h

20522
models/cessna.osg

File diff suppressed because it is too large Load Diff

9
qgroundcontrol.pri

@ -86,7 +86,8 @@ macx { @@ -86,7 +86,8 @@ macx {
DEPENDENCIES_PRESENT += osgearth
# Include osgEarth libraries
LIBS += -losgViewer \
-losgEarth
-losgEarth \
-losgEarthUtil
DEFINES += QGC_OSGEARTH_ENABLED
}
@ -155,7 +156,8 @@ linux-g++ { @@ -155,7 +156,8 @@ linux-g++ {
DEPENDENCIES_PRESENT += osgearth
# Include osgEarth libraries
LIBS += -losgViewer \
-losgEarth
-losgEarth \
-losgEarthUtil
DEFINES += QGC_OSGEARTH_ENABLED
}
@ -227,7 +229,8 @@ linux-g++-64 { @@ -227,7 +229,8 @@ linux-g++-64 {
DEPENDENCIES_PRESENT += osgearth
# Include osgEarth libraries
LIBS += -losgViewer \
-losgEarth
-losgEarth \
-losgEarthUtil
DEFINES += QGC_OSGEARTH_ENABLED
}

89
src/input/Freenect.cc

@ -1,5 +1,6 @@ @@ -1,5 +1,6 @@
#include "Freenect.h"
#include <cmath>
#include <string.h>
#include <QDebug>
@ -8,7 +9,12 @@ Freenect::Freenect() @@ -8,7 +9,12 @@ Freenect::Freenect()
, device(NULL)
, tiltAngle(0)
{
for (int i = 0; i < 2048; ++i)
{
float v = static_cast<float>(i) / 2048.0f;
v = powf(v, 3.0f) * 6.0f;
gammaTable[i] = static_cast<unsigned short>(v * 6.0f * 256.0f);
}
}
Freenect::~Freenect()
@ -102,14 +108,33 @@ QSharedPointer<QByteArray> @@ -102,14 +108,33 @@ QSharedPointer<QByteArray>
Freenect::getRgbData(void)
{
QMutexLocker locker(&rgbMutex);
return QSharedPointer<QByteArray>(new QByteArray(rgb, FREENECT_RGB_SIZE));
return QSharedPointer<QByteArray>(
new QByteArray(rgb, FREENECT_RGB_SIZE));
}
QSharedPointer<QByteArray>
Freenect::getDepthData(void)
Freenect::getRawDepthData(void)
{
QMutexLocker locker(&depthMutex);
return QSharedPointer<QByteArray>(new QByteArray(depth, FREENECT_DEPTH_SIZE));
return QSharedPointer<QByteArray>(
new QByteArray(depth, FREENECT_DEPTH_SIZE));
}
QSharedPointer<QByteArray>
Freenect::getDistanceData(void)
{
QMutexLocker locker(&distanceMutex);
return QSharedPointer<QByteArray>(
new QByteArray(reinterpret_cast<char *>(distance),
FREENECT_FRAME_PIX * sizeof(float)));
}
QSharedPointer<QByteArray>
Freenect::getColoredDepthData(void)
{
QMutexLocker locker(&coloredDepthMutex);
return QSharedPointer<QByteArray>(
new QByteArray(coloredDepth, FREENECT_RGB_SIZE));
}
int
@ -165,6 +190,60 @@ Freenect::depthCallback(freenect_device* device, void* depth, @@ -165,6 +190,60 @@ Freenect::depthCallback(freenect_device* device, void* depth,
Freenect* freenect = static_cast<Freenect *>(freenect_get_user(device));
freenect_depth* data = reinterpret_cast<freenect_depth *>(depth);
QMutexLocker locker(&freenect->depthMutex);
QMutexLocker depthLocker(&freenect->depthMutex);
memcpy(freenect->depth, data, FREENECT_DEPTH_SIZE);
QMutexLocker distanceLocker(&freenect->distanceMutex);
for (int i = 0; i < FREENECT_FRAME_PIX; ++i)
{
freenect->distance[i] =
100.f / (-0.00307f * static_cast<float>(data[i]) + 3.33f);
}
QMutexLocker coloredDepthLocker(&freenect->coloredDepthMutex);
unsigned short* src = reinterpret_cast<unsigned short *>(data);
unsigned char* dst = reinterpret_cast<unsigned char *>(freenect->coloredDepth);
for (int i = 0; i < FREENECT_FRAME_PIX; ++i)
{
unsigned short pval = freenect->gammaTable[src[i]];
unsigned short lb = pval & 0xFF;
switch (pval >> 8)
{
case 0:
dst[3 * i] = 255;
dst[3 * i + 1] = 255 - lb;
dst[3 * i + 2] = 255 - lb;
break;
case 1:
dst[3 * i] = 255;
dst[3 * i + 1] = lb;
dst[3 * i + 2] = 0;
break;
case 2:
dst[3 * i] = 255 - lb;
dst[3 * i + 1] = 255;
dst[3 * i + 2] = 0;
break;
case 3:
dst[3 * i] = 0;
dst[3 * i + 1] = 255;
dst[3 * i + 2] = lb;
break;
case 4:
dst[3 * i] = 0;
dst[3 * i + 1] = 255 - lb;
dst[3 * i + 2] = 255;
break;
case 5:
dst[3 * i] = 0;
dst[3 * i + 1] = 0;
dst[3 * i + 2] = 255 - lb;
break;
default:
dst[3 * i] = 0;
dst[3 * i + 1] = 0;
dst[3 * i + 2] = 0;
break;
}
}
}

13
src/input/Freenect.h

@ -17,7 +17,9 @@ public: @@ -17,7 +17,9 @@ public:
bool process(void);
QSharedPointer<QByteArray> getRgbData(void);
QSharedPointer<QByteArray> getDepthData(void);
QSharedPointer<QByteArray> getRawDepthData(void);
QSharedPointer<QByteArray> getDistanceData(void);
QSharedPointer<QByteArray> getColoredDepthData(void);
int getTiltAngle(void) const;
void setTiltAngle(int angle);
@ -53,9 +55,18 @@ private: @@ -53,9 +55,18 @@ private:
char depth[FREENECT_DEPTH_SIZE];
QMutex depthMutex;
float distance[FREENECT_FRAME_PIX];
QMutex distanceMutex;
char coloredDepth[FREENECT_RGB_SIZE];
QMutex coloredDepthMutex;
// accelerometer data
short ax, ay, az;
double dx, dy, dz;
// gamma map
unsigned short gammaTable[2048];
};
#endif // FREENECT_H

8
src/ui/MainWindow.cc

@ -47,7 +47,7 @@ This file is part of the QGROUNDCONTROL project @@ -47,7 +47,7 @@ This file is part of the QGROUNDCONTROL project
#include "GAudioOutput.h"
#ifdef QGC_OSG_ENABLED
#include "QMap3D.h"
#include "Q3DWidgetFactory.h"
#endif
// FIXME Move
@ -136,8 +136,8 @@ void MainWindow::buildWidgets() @@ -136,8 +136,8 @@ void MainWindow::buildWidgets()
protocolWidget = new XMLCommProtocolWidget(this);
dataplotWidget = new QGCDataPlot2D(this);
#ifdef QGC_OSG_ENABLED
//_3DWidget = Q3DWidgetFactory::get(QGC_MAP3D_OSGEARTH);
_3DWidget = new QMap3D(this);
_3DWidget = Q3DWidgetFactory::get("PIXHAWK");
//_3DWidget = Q3DWidgetFactory::get("MAP3D");
#endif
// Dock widgets
@ -672,7 +672,7 @@ void MainWindow::loadPixhawkView() @@ -672,7 +672,7 @@ void MainWindow::loadPixhawkView()
clearView();
// Engineer view, used in EMAV2009
#ifdef QGC_OSG_ENABLED
#ifdef QGC_OSG_ENABLED
// 3D map
if (_3DWidget)
{

2
src/ui/MainWindow.h

@ -167,7 +167,7 @@ protected: @@ -167,7 +167,7 @@ protected:
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
#ifdef QGC_OSG_ENABLED
QPointer<QMap3D> _3DWidget;
QPointer<QWidget> _3DWidget;
#endif
// Dock widgets
QPointer<QDockWidget> controlDockWidget;

243
src/ui/map3D/Pixhawk3DWidget.cc

@ -61,7 +61,8 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) @@ -61,7 +61,8 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
init(15.0f);
// generate Pixhawk Cheetah model
egocentricMap->addChild(PixhawkCheetahGeode::instance());
vehicleModel = PixhawkCheetahGeode::instance();
egocentricMap->addChild(vehicleModel);
// generate grid model
gridNode = createGrid();
@ -85,16 +86,19 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) @@ -85,16 +86,19 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent)
rollingMap->addChild(waypointsNode);
#ifdef QGC_LIBFREENECT_ENABLED
// generate RGBD model
freenect.reset(new Freenect());
freenect->init();
rgbdNode = createRGBD();
egocentricMap->addChild(rgbdNode);
#endif
// generate RGBD model
rgbd3DNode = createRGBD3D();
egocentricMap->addChild(rgbd3DNode);
setupHUD();
// find available vehicle models in models folder
vehicleModels = findVehicleModels();
buildLayout();
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
@ -106,59 +110,6 @@ Pixhawk3DWidget::~Pixhawk3DWidget() @@ -106,59 +110,6 @@ Pixhawk3DWidget::~Pixhawk3DWidget()
}
void
Pixhawk3DWidget::buildLayout(void)
{
QCheckBox* gridCheckBox = new QCheckBox(this);
gridCheckBox->setText("Grid");
gridCheckBox->setChecked(displayGrid);
QCheckBox* trailCheckBox = new QCheckBox(this);
trailCheckBox->setText("Trail");
trailCheckBox->setChecked(displayTrail);
QCheckBox* waypointsCheckBox = new QCheckBox(this);
waypointsCheckBox->setText("Waypoints");
waypointsCheckBox->setChecked(displayWaypoints);
targetButton = new QPushButton(this);
targetButton->setCheckable(true);
targetButton->setChecked(false);
targetButton->setIcon(QIcon(QString::fromUtf8(":/images/status/weather-clear.svg")));
QPushButton* recenterButton = new QPushButton(this);
recenterButton->setText("Recenter Camera");
QCheckBox* followCameraCheckBox = new QCheckBox(this);
followCameraCheckBox->setText("Follow Camera");
followCameraCheckBox->setChecked(followCamera);
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
layout->setSpacing(2);
layout->addWidget(gridCheckBox, 1, 0);
layout->addWidget(trailCheckBox, 1, 1);
layout->addWidget(waypointsCheckBox, 1, 2);
layout->addItem(new QSpacerItem(20, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
layout->addWidget(targetButton, 1, 4);
layout->addItem(new QSpacerItem(20, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 5);
layout->addWidget(recenterButton, 1, 6);
layout->addWidget(followCameraCheckBox, 1, 7);
layout->setRowStretch(0, 100);
layout->setRowStretch(1, 1);
setLayout(layout);
connect(gridCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showGrid(int)));
connect(trailCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showTrail(int)));
connect(waypointsCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showWaypoints(int)));
connect(recenterButton, SIGNAL(clicked()), this, SLOT(recenter()));
connect(followCameraCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(toggleFollowCamera(int)));
}
/**
*
* @param uas the UAS/MAV to monitor/display with the HUD
@ -219,6 +170,12 @@ Pixhawk3DWidget::showWaypoints(int state) @@ -219,6 +170,12 @@ Pixhawk3DWidget::showWaypoints(int state)
}
void
Pixhawk3DWidget::selectVehicleModel(int index)
{
vehicleModel = vehicleModels.at(index);
}
void
Pixhawk3DWidget::recenter(void)
{
float robotX = 0.0f, robotY = 0.0f, robotZ = 0.0f;
@ -245,6 +202,92 @@ Pixhawk3DWidget::toggleFollowCamera(int32_t state) @@ -245,6 +202,92 @@ Pixhawk3DWidget::toggleFollowCamera(int32_t state)
}
}
QVector< osg::ref_ptr<osg::Node> >
Pixhawk3DWidget::findVehicleModels(void)
{
QDir directory("models");
QStringList files = directory.entryList(QStringList("*.osg"));
QVector< osg::ref_ptr<osg::Node> > nodes;
// add Pixhawk Bravo model
vehicleModels.push_back(PixhawkCheetahGeode::instance());
for (int i = 0; i < files.size(); ++i)
{
osg::ref_ptr<osg::Node> node =
osgDB::readNodeFile(directory.absoluteFilePath(files[i]).toStdString().c_str());
vehicleModels.push_back(node);
}
return nodes;
}
void
Pixhawk3DWidget::buildLayout(void)
{
QCheckBox* gridCheckBox = new QCheckBox(this);
gridCheckBox->setText("Grid");
gridCheckBox->setChecked(displayGrid);
QCheckBox* trailCheckBox = new QCheckBox(this);
trailCheckBox->setText("Trail");
trailCheckBox->setChecked(displayTrail);
QCheckBox* waypointsCheckBox = new QCheckBox(this);
waypointsCheckBox->setText("Waypoints");
waypointsCheckBox->setChecked(displayWaypoints);
QLabel* modelLabel = new QLabel("Vehicle Model", this);
QComboBox* modelComboBox = new QComboBox(this);
for (int i = 0; i < vehicleModels.size(); ++i)
{
modelComboBox->addItem(vehicleModels[i]->getName().c_str());
}
targetButton = new QPushButton(this);
targetButton->setCheckable(true);
targetButton->setChecked(false);
targetButton->setIcon(QIcon(QString::fromUtf8(":/images/status/weather-clear.svg")));
QPushButton* recenterButton = new QPushButton(this);
recenterButton->setText("Recenter Camera");
QCheckBox* followCameraCheckBox = new QCheckBox(this);
followCameraCheckBox->setText("Follow Camera");
followCameraCheckBox->setChecked(followCamera);
QGridLayout* layout = new QGridLayout(this);
layout->setMargin(0);
layout->setSpacing(2);
layout->addWidget(gridCheckBox, 1, 0);
layout->addWidget(trailCheckBox, 1, 1);
layout->addWidget(waypointsCheckBox, 1, 2);
layout->addItem(new QSpacerItem(20, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 3);
layout->addWidget(modelLabel, 1, 4);
layout->addWidget(modelComboBox, 1, 5);
layout->addWidget(targetButton, 1, 6);
layout->addItem(new QSpacerItem(20, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 7);
layout->addWidget(recenterButton, 1, 8);
layout->addWidget(followCameraCheckBox, 1, 9);
layout->setRowStretch(0, 100);
layout->setRowStretch(1, 1);
setLayout(layout);
connect(gridCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showGrid(int)));
connect(trailCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showTrail(int)));
connect(waypointsCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(showWaypoints(int)));
connect(modelComboBox, SIGNAL(currentIndexChanged(int)),
this, SLOT(selectVehicleModel(int)));
connect(recenterButton, SIGNAL(clicked()), this, SLOT(recenter()));
connect(followCameraCheckBox, SIGNAL(stateChanged(int)),
this, SLOT(toggleFollowCamera(int)));
}
void
Pixhawk3DWidget::display(void)
{
@ -298,6 +341,7 @@ Pixhawk3DWidget::display(void) @@ -298,6 +341,7 @@ Pixhawk3DWidget::display(void)
rollingMap->setChildValue(trailNode, displayTrail);
rollingMap->setChildValue(targetNode, displayTarget);
rollingMap->setChildValue(waypointsNode, displayWaypoints);
egocentricMap->setChildValue(rgbd3DNode, displayRGBD3D);
hudGroup->setChildValue(rgb2DGeode, displayRGBD2D);
hudGroup->setChildValue(depth2DGeode, displayRGBD2D);
@ -316,6 +360,9 @@ Pixhawk3DWidget::keyPressEvent(QKeyEvent* event) @@ -316,6 +360,9 @@ Pixhawk3DWidget::keyPressEvent(QKeyEvent* event)
case '1':
displayRGBD2D = !displayRGBD2D;
break;
case '2':
displayRGBD3D = !displayRGBD3D;
break;
}
}
@ -458,13 +505,26 @@ Pixhawk3DWidget::createWaypoints(void) @@ -458,13 +505,26 @@ Pixhawk3DWidget::createWaypoints(void)
return group;
}
#ifdef QGC_LIBFREENECT_ENABLED
osg::ref_ptr<osg::Geode>
Pixhawk3DWidget::createRGBD(void)
Pixhawk3DWidget::createRGBD3D(void)
{
return osg::ref_ptr<osg::Geode>(new osg::Geode);
int frameSize = 640 * 480;
osg::ref_ptr<osg::Geode> geode(new osg::Geode);
osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry);
osg::ref_ptr<osg::Vec3Array> vertices(new osg::Vec3Array(frameSize));
geometry->setVertexArray(vertices);
osg::ref_ptr<osg::Vec4Array> colors(new osg::Vec4Array(frameSize));
geometry->setColorArray(colors);
geometry->setColorBinding(osg::Geometry::BIND_PER_VERTEX);
geometry->setUseDisplayList(false);
geode->addDrawable(geometry);
return geode;
}
#endif
void
Pixhawk3DWidget::setupHUD(void)
@ -501,18 +561,10 @@ Pixhawk3DWidget::setupHUD(void) @@ -501,18 +561,10 @@ Pixhawk3DWidget::setupHUD(void)
hudGroup->addChild(rgb2DGeode);
depthImage = new osg::Image;
depthImage->allocateImage(640, 480, 1, GL_RGB, GL_UNSIGNED_BYTE);
depth2DGeode = new ImageWindowGeode("Depth Image",
osg::Vec4(0.0f, 0.0f, 0.1f, 1.0f),
depthImage);
hudGroup->addChild(depth2DGeode);
for (int i = 0; i < 2048; ++i)
{
float v = static_cast<float>(i) / 2048.0f;
v = powf(v, 3.0f) * 6.0f;
gammaLookup[i] = static_cast<unsigned short>(v * 6.0f * 256.0f);
}
}
void
@ -582,51 +634,10 @@ Pixhawk3DWidget::updateHUD(float robotX, float robotY, float robotZ, @@ -582,51 +634,10 @@ Pixhawk3DWidget::updateHUD(float robotX, float robotY, float robotZ,
osg::Image::NO_DELETE);
rgbImage->dirty();
unsigned short* src = reinterpret_cast<unsigned short *>(depth->data());
unsigned char* dst = depthImage->data();
for (int i = 0; i < depthImage->s() * depthImage->t(); ++i)
{
unsigned short pval = gammaLookup[src[i]];
unsigned short lb = pval & 0xFF;
switch (pval >> 8)
{
case 0:
dst[3 * i] = 255;
dst[3 * i + 1] = 255 - lb;
dst[3 * i + 2] = 255 - lb;
break;
case 1:
dst[3 * i] = 255;
dst[3 * i + 1] = lb;
dst[3 * i + 2] = 0;
break;
case 2:
dst[3 * i] = 255 - lb;
dst[3 * i + 1] = 255;
dst[3 * i + 2] = 0;
break;
case 3:
dst[3 * i] = 0;
dst[3 * i + 1] = 255;
dst[3 * i + 2] = lb;
break;
case 4:
dst[3 * i] = 0;
dst[3 * i + 1] = 255 - lb;
dst[3 * i + 2] = 255;
break;
case 5:
dst[3 * i] = 0;
dst[3 * i + 1] = 0;
dst[3 * i + 2] = 255 - lb;
break;
default:
dst[3 * i] = 0;
dst[3 * i + 1] = 0;
dst[3 * i + 2] = 0;
break;
}
}
depthImage->setImage(640, 480, 1,
GL_RGB, GL_RGB, GL_UNSIGNED_BYTE,
reinterpret_cast<unsigned char *>(coloredDepth->data()),
osg::Image::NO_DELETE);
depthImage->dirty();
}
}
@ -769,7 +780,7 @@ void @@ -769,7 +780,7 @@ void
Pixhawk3DWidget::updateRGBD(void)
{
rgb = freenect->getRgbData();
depth = freenect->getDepthData();
coloredDepth = freenect->getColoredDepthData();
}
#endif

23
src/ui/map3D/Pixhawk3DWidget.h

@ -37,9 +37,8 @@ @@ -37,9 +37,8 @@
#include <osgEarth/MapNode>
#endif
#ifdef QGC_OSG_ENABLED
#include "ImageWindowGeode.h"
#endif
#ifdef QGC_LIBFREENECT_ENABLED
#include "Freenect.h"
#endif
@ -59,10 +58,6 @@ public: @@ -59,10 +58,6 @@ public:
explicit Pixhawk3DWidget(QWidget* parent = 0);
~Pixhawk3DWidget();
void buildLayout(void);
double getTime(void) const;
public slots:
void setActiveUAS(UASInterface* uas);
@ -70,10 +65,13 @@ private slots: @@ -70,10 +65,13 @@ private slots:
void showGrid(int state);
void showTrail(int state);
void showWaypoints(int state);
void selectVehicleModel(int index);
void recenter(void);
void toggleFollowCamera(int state);
protected:
QVector< osg::ref_ptr<osg::Node> > findVehicleModels(void);
void buildLayout(void);
virtual void display(void);
virtual void keyPressEvent(QKeyEvent* event);
virtual void mousePressEvent(QMouseEvent* event);
@ -90,10 +88,7 @@ private: @@ -90,10 +88,7 @@ private:
osg::ref_ptr<osg::Node> createTarget(void);
osg::ref_ptr<osg::Group> createWaypoints(void);
#ifdef QGC_LIBFREENECT_ENABLED
osg::ref_ptr<osg::Geode> createRGBD(void);
#endif
osg::ref_ptr<osg::Geode> createRGBD3D(void);
void setupHUD(void);
void resizeHUD(void);
@ -121,6 +116,7 @@ private: @@ -121,6 +116,7 @@ private:
osg::ref_ptr<osg::Vec3Array> trailVertices;
QVarLengthArray<osg::Vec3, 10000> trail;
osg::ref_ptr<osg::Node> vehicleModel;
osg::ref_ptr<osg::Geometry> hudBackgroundGeometry;
osg::ref_ptr<osgText::Text> statusText;
osg::ref_ptr<ImageWindowGeode> rgb2DGeode;
@ -137,13 +133,14 @@ private: @@ -137,13 +133,14 @@ private:
osg::ref_ptr<osg::Geode> targetNode;
osg::ref_ptr<osg::PositionAttitudeTransform> targetPosition;
osg::ref_ptr<osg::Group> waypointsNode;
osg::ref_ptr<osg::Geode> rgbd3DNode;
#ifdef QGC_LIBFREENECT_ENABLED
osg::ref_ptr<osg::Geode> rgbdNode;
QScopedPointer<Freenect> freenect;
#endif
QSharedPointer<QByteArray> rgb;
QSharedPointer<QByteArray> depth;
unsigned short gammaLookup[2048];
QSharedPointer<QByteArray> coloredDepth;
QVector< osg::ref_ptr<osg::Node> > vehicleModels;
QPushButton* targetButton;

1
src/ui/map3D/PixhawkCheetahGeode.cc

@ -59358,6 +59358,7 @@ osg::ref_ptr<osg::Geode> @@ -59358,6 +59358,7 @@ osg::ref_ptr<osg::Geode>
PixhawkCheetahGeode::create(float red, float green, float blue)
{
osg::ref_ptr<osg::Geode> geode(new osg::Geode());
geode->setName("Pixhawk Bravo");
osg::ref_ptr<osg::Geometry> geometry(new osg::Geometry());
geode->addDrawable(geometry.get());

11
src/ui/map3D/Q3DWidgetFactory.cc

@ -32,16 +32,21 @@ This file is part of the QGROUNDCONTROL project @@ -32,16 +32,21 @@ This file is part of the QGROUNDCONTROL project
#include "Q3DWidgetFactory.h"
#include "Pixhawk3DWidget.h"
#include "QMap3D.h"
QPointer<Q3DWidget>
QPointer<QWidget>
Q3DWidgetFactory::get(const std::string& type)
{
if (type == "PIXHAWK")
{
return QPointer<Q3DWidget>(new Pixhawk3DWidget);
return QPointer<QWidget>(new Pixhawk3DWidget);
}
else if (type == "MAP3D")
{
return QPointer<QWidget>(new QMap3D);
}
else
{
return QPointer<Q3DWidget>(new Q3DWidget);
return QPointer<QWidget>(new Q3DWidget);
}
}

2
src/ui/map3D/Q3DWidgetFactory.h

@ -50,7 +50,7 @@ public: @@ -50,7 +50,7 @@ public:
* @return A smart pointer to the Q3DWidget instance.
*/
static QPointer<Q3DWidget> get(const std::string& type);
static QPointer<QWidget> get(const std::string& type);
};
#endif // Q3DWIDGETFACTORY_H

Loading…
Cancel
Save