Commit e9637d5a authored by Mariano Lizarraga's avatar Mariano Lizarraga

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

Conflicts:
	src/ui/MainWindow.cc
parents 61c6b0af 0d1969c0
......@@ -192,40 +192,38 @@ function setViewRange(dist)
function addTrailPosition(id, lat, lon, alt)
{
trails[id].setExtrude(false);
trails[id].setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
trails[id].setAltitudeMode(ge.ALTITUDE_ABSOLUTE);
// Add LineString points
// Add LineString points
trails[id].getCoordinates().pushLatLngAlt(lat, lon, alt);
// Create a style and set width and color of line
trailPlacemarks[id].setStyleSelector(ge.createStyle(''));
lineStyle = trailPlacemarks[id].getStyleSelector().getLineStyle();
lineStyle.setWidth(5);
lineStyle.getColor().set(trailColors[id]);  // aabbggrr format
//lineStyle.getColor().set(color);  // aabbggrr format
// Create a style and set width and color of line
trailPlacemarks[id].setStyleSelector(ge.createStyle(''));
lineStyle = trailPlacemarks[id].getStyleSelector().getLineStyle();
lineStyle.setWidth(5);
lineStyle.getColor().set(trailColors[id]);  // aabbggrr format
//lineStyle.getColor().set(color);  // aabbggrr format
// Add the feature to Earth
if (trailsVisible[id] == true) ge.getFeatures().replaceChild(trailPlacemarks[id], trailPlacemarks[id]);
// Add the feature to Earth
if (trailsVisible[id] == true) ge.getFeatures().replaceChild(trailPlacemarks[id], trailPlacemarks[id]);
}
function initCallback(object)
{
ge = object;
ge.getWindow().setVisibility(true);
ge.getOptions().setStatusBarVisibility(true);
ge.getOptions().setScaleLegendVisibility(true);
ge.getOptions().setFlyToSpeed(5.0);
//ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
ge.getNavigationControl().setVisibility(ge.VISIBILITY_AUTO);
ge = object;
ge.getWindow().setVisibility(true);
ge.getOptions().setStatusBarVisibility(true);
ge.getOptions().setScaleLegendVisibility(true);
ge.getOptions().setFlyToSpeed(5.0);
//ge.getOptions().setFlyToSpeed(ge.SPEED_TELEPORT);
ge.getNavigationControl().setVisibility(ge.VISIBILITY_AUTO);
ge.getLayerRoot().enableLayerById(ge.LAYER_TERRAIN, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_BUILDINGS, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_TERRAIN, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_BUILDINGS, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_BORDERS, true);
ge.getLayerRoot().enableLayerById(ge.LAYER_TREES, true);
initialized = true;
initialized = true;
}
function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
......@@ -247,13 +245,12 @@ function setAircraftPositionAttitude(id, lat, lon, alt, roll, pitch, yaw)
planeOrient.setRoll(((roll/M_PI)+1.0)*360.0);
planeOrient.setTilt(((pitch/M_PI)+1.0)*360.0);
planeOrient.setHeading(((yaw/M_PI)+1.0)*360.0);
}
planeLoc.setLatitude(lat);
planeLoc.setLongitude(lon);
planeLoc.setAltitude(alt);
planeModel.setLocation(planeLoc);
}
}
function enableDaylight(enabled)
......
......@@ -17,14 +17,14 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 0.8.1 (Alpha)"
#define QGC_APPLICATION_VERSION "v. 0.8.3 (Alpha)"
namespace QGC
{
const QString APPNAME = "QGROUNDCONTROL";
const QString COMPANYNAME = "OPENMAV";
const int APPLICATIONVERSION = 80; // 0.8.0
const int APPLICATIONVERSION = 83; // 0.8.0
}
#endif // CONFIGURATION_H
......@@ -64,6 +64,15 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Temperature", "raw", raw.temp, time);
}
break;
case MAVLINK_MSG_ID_IMAGE_TRIGGERED:
{
// FIXME Kind of a hack to load data from disk
mavlink_image_triggered_t img;
mavlink_msg_image_triggered_decode(&message, &img);
qDebug() << "IMAGE AVAILABLE:" << img.timestamp;
emit imageStarted(img.timestamp);
}
break;
case MAVLINK_MSG_ID_PATTERN_DETECTED:
{
mavlink_pattern_detected_t detected;
......
......@@ -464,6 +464,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "latitude", "deg", pos.lat, time);
emit valueChanged(uasId, "longitude", "deg", pos.lon, time);
// FIXME REMOVE
longitude = pos.lon;
latitude = pos.lat;
altitude = pos.alt;
emit globalPositionChanged(this, longitude, latitude, altitude, time);
if (pos.fix_type > 0)
{
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
......
......@@ -169,7 +169,7 @@ public:
bool isAuto();
public:
UASWaypointManager &getWaypointManager(void) { return waypointManager; }
UASWaypointManager* getWaypointManager() { return &waypointManager; }
int getSystemType();
int getAutopilotType() {return autopilot;}
......@@ -303,6 +303,7 @@ signals:
void loadChanged(UASInterface* uas, double load);
/** @brief Propagate a heartbeat received from the system */
void heartbeat(UASInterface* uas);
void imageStarted(quint64 timestamp);
protected:
/** @brief Get the UNIX timestamp in microseconds */
......
......@@ -79,7 +79,7 @@ public:
virtual double getYaw() const = 0;
/** @brief Get reference to the waypoint manager **/
virtual UASWaypointManager &getWaypointManager(void) = 0;
virtual UASWaypointManager* getWaypointManager(void) = 0;
/* COMMUNICATION FLAGS */
......
......@@ -265,6 +265,13 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
}
}
void UASWaypointManager::notifyOfChange(Waypoint* wp)
{
Q_UNUSED(wp);
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
}
int UASWaypointManager::setCurrentWaypoint(quint16 seq)
{
if (seq < waypoints.size())
......@@ -313,6 +320,9 @@ void UASWaypointManager::addWaypoint(Waypoint *wp)
waypoints.insert(waypoints.size(), wp);
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
qDebug() << "ADDED WAYPOINT WITH ID:" << wp->getId();
}
}
......@@ -329,6 +339,7 @@ int UASWaypointManager::removeWaypoint(quint16 seq)
waypoints[i]->setId(i);
}
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
return 0;
}
return -1;
......@@ -359,6 +370,7 @@ void UASWaypointManager::moveWaypoint(quint16 cur_seq, quint16 new_seq)
//waypoints[new_seq]->setId(new_seq);
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
}
}
......@@ -425,21 +437,28 @@ void UASWaypointManager::loadWaypoints(const QString &loadFile)
emit loadWPFile();
emit waypointListChanged();
emit waypointListChanged(uas.getUASID());
}
void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
{
// FIXME Will be removed
Q_UNUSED(wp);
}
//void UASWaypointManager::globalAddWaypoint(Waypoint *wp)
//{
// // FIXME Will be removed
// Q_UNUSED(wp);
//}
int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
{
// FIXME Will be removed
Q_UNUSED(seq);
return 0;
}
//int UASWaypointManager::globalRemoveWaypoint(quint16 seq)
//{
// // FIXME Will be removed
// Q_UNUSED(seq);
// return 0;
//}
//void UASWaypointManager::waypointUpdated(Waypoint*)
//{
// // FIXME Add rate limiter
// emit waypointListChanged(uas.getUASID());
//}
void UASWaypointManager::clearWaypointList()
{
......@@ -457,6 +476,11 @@ void UASWaypointManager::clearWaypointList()
}
}
int UASWaypointManager::getIndexOf(Waypoint* wp)
{
return waypoints.indexOf(wp);
}
void UASWaypointManager::readWaypoints()
{
emit readGlobalWPFromUAS(true);
......
......@@ -86,25 +86,27 @@ public:
/** @name Waypoint list operations */
/*@{*/
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
void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint
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
int getIndexOf(Waypoint* wp); ///< Get the index of a waypoint in the list
/*@}*/
/** @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
/*@}*/
UAS& getUAS() { return this->uas; } ///< Returns the owning UAS
// /** @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
// /*@}*/
private:
/** @name Message send functions */
......@@ -120,14 +122,17 @@ private:
public slots:
void timeout(); ///< Called by the timer if a response times out. Handles send retries.
void addWaypoint(Waypoint *wp); ///< adds a new waypoint to the end of the list and changes its sequence number accordingly
signals:
void waypointListChanged(void); ///< emits signal that the local waypoint list has been changed
void waypointListChanged(void); ///< emits signal that the waypoint list has been changed
void waypointListChanged(int uasid); ///< Emits signal that list has been changed
void waypointChanged(int uasid, Waypoint* wp); ///< emits signal that waypoint has been changed
void currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string
void loadWPFile(); ///< emits signal that a file wp has been load
void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
void loadWPFile(); ///< emits signal that a file wp has been load
void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
private:
UAS &uas; ///< Reference to the corresponding UAS
......
......@@ -152,7 +152,7 @@ HDDisplay::~HDDisplay()
QSize HDDisplay::sizeHint() const
{
return QSize(400, 400.0f*(vwidth/vheight)*1.1f);
return QSize(400, 400.0f*(vwidth/vheight)*1.2f);
}
void HDDisplay::enableGLRendering(bool enable)
......
......@@ -678,7 +678,7 @@ void HSIDisplay::drawWaypoints(QPainter& painter)
{
if (uas)
{
const QVector<Waypoint*>& list = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint*>& list = uas->getWaypointManager()->getWaypointList();
// for (int i = 0; i < list.size(); i++)
// {
// QPointF in(list.at(i)->getX(), list.at(i)->getY());
......
This diff is collapsed.
......@@ -76,11 +76,19 @@ public slots:
void updateLoad(UASInterface*, double);
void selectWaypoint(int uasId, int id);
void startImage(quint64 timestamp);
void startImage(int imgid, int width, int height, int depth, int channels);
void setPixels(int imgid, const unsigned char* imageData, int length, int startIndex);
void finishImage();
void saveImage();
void saveImage(QString fileName);
/** @brief Select directory where to load the offline files from */
void selectOfflineDirectory();
/** @brief Enable the HUD instruments */
void enableHUDInstruments(bool enabled);
/** @brief Enable Video */
void enableVideo(bool enabled);
protected slots:
void paintCenterBackground(float roll, float pitch, float yaw);
......@@ -119,6 +127,8 @@ protected:
void showEvent(QShowEvent* event);
/** @brief Stop updating widget */
void hideEvent(QHideEvent* event);
void contextMenuEvent (QContextMenuEvent* event);
void createActions();
static const int updateInterval = 50;
......@@ -192,6 +202,16 @@ protected:
double lon;
double alt;
float load;
QString offlineDirectory;
QString nextOfflineImage;
bool hudInstrumentsEnabled;
bool videoEnabled;
float xImageFactor;
float yImageFactor;
QAction* enableHUDAction;
QAction* enableVideoAction;
QAction* selectOfflineDirectoryAction;
QAction* selectVideoChannelAction;
void paintEvent(QPaintEvent *event);
};
......
This diff is collapsed.
......@@ -112,6 +112,8 @@ public slots:
void stopVideoCapture();
void saveScreen();
/** @brief Load default view when no MAV is connected */
void loadUnconnectedView();
/** @brief Load view for pilot */
void loadPilotView();
/** @brief Load view for engineer */
......@@ -166,7 +168,7 @@ public slots:
* It shows the QDockedWidget based on the action sender
*
*/
void showToolWidget();
void showToolWidget(bool visible);
/**
* @brief Shows a Widget from the center stack based on the action sender
......@@ -177,8 +179,10 @@ public slots:
*/
void showCentralWidget();
/** @brief Change actively a QDockWidgets visibility by an action */
void showDockWidget(bool vis);
/** @brief Updates a QDockWidget's checked status based on its visibility */
void updateVisibilitySettings (bool vis);
void updateVisibilitySettings(bool vis);
/** @brief Updates a QDockWidget's location */
void updateLocationSettings (Qt::DockWidgetArea location);
......@@ -187,6 +191,9 @@ protected:
MainWindow(QWidget *parent = 0);
/** @brief Set default window settings for the current autopilot type */
void setDefaultSettingsForAp();
// These defines are used to save the settings when selecting with
// which widgets populate the views
// FIXME: DO NOT PUT CUSTOM VALUES IN THIS ENUM since it is iterated over
......@@ -212,6 +219,8 @@ protected:
MENU_SLUGS_HIL,
MENU_SLUGS_CAMERA,
MENU_MAVLINK_LOG_PLAYER,
MENU_VIDEO_STREAM_1,
MENU_VIDEO_STREAM_2,
CENTRAL_SEPARATOR= 255, // do not change
CENTRAL_LINECHART,
CENTRAL_PROTOCOL,
......@@ -238,6 +247,7 @@ protected:
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
} VIEW_SECTIONS;
......@@ -368,6 +378,8 @@ protected:
QPointer<QDockWidget> watchdogControlDockWidget;
QPointer<QDockWidget> headUpDockWidget;
QPointer<QDockWidget> video1DockWidget;
QPointer<QDockWidget> video2DockWidget;
QPointer<QDockWidget> logPlayerDockWidget;
QPointer<QDockWidget> hsiDockWidget;
......
......@@ -100,7 +100,7 @@
</widget>
<widget class="QMenu" name="menuTools">
<property name="title">
<string>Tools</string>
<string>Widgets</string>
</property>
<addaction name="actionNewCustomWidget"/>
</widget>
......@@ -121,11 +121,18 @@
<addaction name="actionPilotsView"/>
<addaction name="separator"/>
<addaction name="actionMavlinkView"/>
<addaction name="actionUnconnectedView"/>
</widget>
<widget class="QMenu" name="menuMain">
<property name="title">
<string>Main</string>
</property>
</widget>
<addaction name="menuMGround"/>
<addaction name="menuNetwork"/>
<addaction name="menuConnected_Systems"/>
<addaction name="menuUnmanned_System"/>
<addaction name="menuMain"/>
<addaction name="menuTools"/>
<addaction name="menuPerspectives"/>
<addaction name="menuHelp"/>
......@@ -296,6 +303,9 @@
<property name="text">
<string>Operator</string>
</property>
<property name="shortcut">
<string>Meta+O</string>
</property>
</action>
<action name="actionEngineersView">
<property name="checkable">
......@@ -308,6 +318,9 @@
<property name="text">
<string>Engineer</string>
</property>
<property name="shortcut">
<string>Meta+E</string>
</property>
</action>
<action name="actionMavlinkView">
<property name="checkable">
......@@ -320,6 +333,9 @@
<property name="text">
<string>Mavlink</string>
</property>
<property name="shortcut">
<string>Meta+M</string>
</property>
</action>
<action name="actionReloadStyle">
<property name="icon">
......@@ -341,6 +357,9 @@
<property name="text">
<string>Pilot</string>
</property>
<property name="shortcut">
<string>Meta+P</string>
</property>
</action>
<action name="actionNewCustomWidget">
<property name="icon">
......@@ -379,6 +398,21 @@
<string>QGroundControl global settings</string>
</property>
</action>
<action name="actionUnconnectedView">
<property name="checkable">
<bool>true</bool>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
</property>
<property name="text">
<string>Unconnected</string>
</property>
<property name="shortcut">
<string>Meta+U</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
This diff is collapsed.
......@@ -44,6 +44,8 @@ This file is part of the QGROUNDCONTROL project
class QMenu;
class Waypoint;
class Waypoint2DIcon;
namespace Ui {
class MapWidget;
......@@ -72,10 +74,18 @@ public slots:
QPointF getPointxBearing_Range(double lat1, double lon1, double bearing, double distance);
/** @brief Clear the waypoints overlay layer */
void clearWaypoints();
void clearWaypoints(int uas=0);
/** @brief Clear the UAV tracks on the map */
void clearPath();
void changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon);
void clearPath(int uas=0);
/** @brief Update waypoint list */
void updateWaypointList(int uas);
/** @brief Clear all waypoints and re-add them from updated list */
void redoWaypoints(int uas=0);
/** @brief Update waypoint */
void updateWaypoint(int uas, Waypoint* wp);
void drawBorderCamAtMap(bool status);
/** @brief Bring up dialog to go to a specific location */
void goTo();
......@@ -105,12 +115,12 @@ protected:
QMenu* mapMenu;
QPushButton* mapButton;
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::Layer* tracks; ///< Layer for UAV tracks
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
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::Layer* tracks; ///< Layer for UAV tracks
qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints
//only for experiment
qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
......@@ -124,6 +134,9 @@ protected:
QMap<int, qmapcontrol::Point*> uasIcons;
QMap<int, qmapcontrol::LineString*> uasTrails;
QMap<int, QPen*> mavPens;
//QMap<int, QList<qmapcontrol::Point*> > mavWps;
//QMap<int, qmapcontrol::LineString*> waypointPaths;
UASInterface* mav;
quint64 lastUpdate;
......@@ -135,21 +148,24 @@ protected:
void createPathButtonClicked(bool checked);
void createWaypointGraphAtMap (const QPointF coordinate);
/** @brief Create the graphic representation of the waypoint */
void createWaypointGraphAtMap(int id, const QPointF coordinate);
void mapproviderSelected(QAction* action);
signals:
//void movePoint(QPointF newCoord);
void captureMapCoordinateClick(const QPointF coordinate); //ROCA
void createGlobalWP(bool value, QPointF centerCoordinate);
//void captureMapCoordinateClick(const QPointF coordinate); //ROCA
//void createGlobalWP(bool value, QPointF centerCoordinate);
void waypointCreated(Waypoint* wp);
void sendGeometryEndDrag(const QPointF coordinate, const int index);
private:
Ui::MapWidget *m_ui;
QList<qmapcontrol::Point*> wps;
QList<Waypoint2DIcon*>wpIcons;
qmapcontrol::LineString* waypointPath;
QHash <QString, qmapcontrol::Point*> wpIndex;
//QHash <QString, qmapcontrol::Point*> wpIndex;
QPen* pointPen;
int wpExists(const QPointF coordinate);
bool waypointIsDrag;
......
......@@ -319,7 +319,7 @@ void QGCMAVLinkLogPlayer::logLoop()
//qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
if (nextExecutionTime < 5)
if (nextExecutionTime < 2)
{
logLoop();
}
......
This diff is collapsed.
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>1389</width>
<height>33</height>
<height>39</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -375,7 +375,7 @@ QProgressBar::chunk#thrustBar {
<string>m</string>
</property>
<property name="decimals">
<number>7</number>
<number>2</number>
</property>
<property name="minimum">
<double>-100000.000000000000000</double>
......
......@@ -483,7 +483,7 @@ void LinechartWidget::startLogging()
fileName.append(".csv");
}
while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")) && !abort)
while (!(fileName.endsWith(".txt") || fileName.endsWith(".csv")) && !abort && fileName != "")
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
......
......@@ -46,50 +46,50 @@ void MAV2DIcon::setYaw(float yaw)
void MAV2DIcon::drawIcon(QPen* pen)
{
// mypixmap = new QPixmap(radius+1, radius+1);
// mypixmap->fill(Qt::transparent);
// QPainter painter(mypixmap);
mypixmap = new QPixmap(radius+1, radius+1);
mypixmap->fill(Qt::transparent);
QPainter painter(mypixmap);
// // DRAW WAYPOINT
// QPointF p(radius/2, radius/2);
// DRAW WAYPOINT
QPointF p(radius/2, radius/2);
// float waypointSize = radius;
// QPolygonF poly(4);
// // Top point
// poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f));
// // Right point
// poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y()));
// // Bottom point
// poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f));
// poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));
float waypointSize = radius;
QPolygonF poly(4);
// Top point
poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f));
// Right point
poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y()));
// Bottom point
poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f));
poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y()));
//// // Select color based on if this is the current waypoint
//// if (list.at(i)->getCurrent())
//// {
//// color = QGC::colorCyan;//uas->getColor();
//// pen.setWidthF(refLineWidthToPen(0.8f));
//// }
//// else
//// {
//// color = uas->getColor();
//// pen.setWidthF(refLineWidthToPen(0.4f));
//// }
// //pen.setColor(color);
// if (pen)
// // Select color based on if this is the current waypoint
// if (list.at(i)->getCurrent())
// {
// pen->setWidthF(2);
// painter.setPen(*pen);
// color = QGC::colorCyan;//uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.8f));
// }
// else
// {
// QPen pen2(Qt::red);
// pen2.setWidth(2);
// painter.setPen(pen2);
// color = uas->getColor();
// pen.setWidthF(refLineWidthToPen(0.4f));
// }
// painter.setBrush(Qt::NoBrush);
// float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
// painter.drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * rad);
// painter.drawPolygon(poly);
//pen.setColor(color);
if (pen)
{
pen->setWidthF(2);
painter.setPen(*pen);
}
else
{
QPen pen2(Qt::red);
pen2.setWidth(2);
painter.setPen(pen2);
}
painter.setBrush(Qt::NoBrush);
float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f));
painter.drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * rad);
painter.drawPolygon(poly);
}
......@@ -308,7 +308,7 @@ Pixhawk3DWidget::insertWaypoint(void)
if (wp)
{
wp->setFrame(frame);
uas->getWaypointManager().addWaypoint(wp);
uas->getWaypointManager()->addWaypoint(wp);
}
}
}
......@@ -325,7 +325,7 @@ Pixhawk3DWidget::setWaypoint(void)
if (uas)
{
const QVector<Waypoint *> waypoints =
uas->getWaypointManager().getWaypointList();
uas->getWaypointManager()->getWaypointList();
Waypoint* waypoint = waypoints.at(selectedWpIndex);
if (frame == MAV_FRAME_GLOBAL)
......@@ -366,7 +366,7 @@ Pixhawk3DWidget::deleteWaypoint(void)
{
if (uas)
{
uas->getWaypointManager().removeWaypoint(selectedWpIndex);
uas->getWaypointManager()->removeWaypoint(selectedWpIndex);
}
}
......@@ -377,7 +377,7 @@ Pixhawk3DWidget::setWaypointAltitude(void)
{
bool ok;
const QVector<Waypoint *> waypoints =
uas->getWaypointManager().getWaypointList();
uas->getWaypointManager()->getWaypointList();
Waypoint* waypoint = waypoints.at(selectedWpIndex);
double altitude = waypoint->getZ();
......@@ -409,10 +409,10 @@ Pixhawk3DWidget::clearAllWaypoints(void)
if (uas)
{
const QVector<Waypoint *> waypoints =
uas->getWaypointManager().getWaypointList();
uas->getWaypointManager()->getWaypointList();
for (int i = waypoints.size() - 1; i >= 0; --i)
{
uas->getWaypointManager().removeWaypoint(i);
uas->getWaypointManager()->removeWaypoint(i);
}
}
}
......
......@@ -78,7 +78,7 @@ WaypointGroupNode::update(MAV_FRAME frame, UASInterface *uas)
removeChild(0, getNumChildren());
}
const QVector<Waypoint *>& list = uas->getWaypointManager().getWaypointList();
const QVector<Waypoint *>& list = uas->getWaypointManager()->getWaypointList();
for (int i = 0; i < list.size(); i++)
{
......
......@@ -83,7 +83,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
connect(uas, SIGNAL(heartbeatTimeout()), this, SLOT(heartbeatTimeout()));
connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int)));
connect(&(uas->getWaypointManager()), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
......
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