Commit 398361d3 authored by pixhawk's avatar pixhawk

Added position control status

parent 275c3005
...@@ -9,6 +9,7 @@ namespace QGC ...@@ -9,6 +9,7 @@ namespace QGC
const QColor colorCyan(55, 154, 195); const QColor colorCyan(55, 154, 195);
const QColor colorRed(154, 20, 20); const QColor colorRed(154, 20, 20);
const QColor colorGreen(20, 200, 20); const QColor colorGreen(20, 200, 20);
const QColor colorYellow(195, 154, 55);
/** @brief Get the current ground time in microseconds */ /** @brief Get the current ground time in microseconds */
quint64 groundTimeUsecs(); quint64 groundTimeUsecs();
......
...@@ -63,12 +63,13 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile ...@@ -63,12 +63,13 @@ MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile
_isConnected = false; _isConnected = false;
onboardParams = QMap<QString, float>(); onboardParams = QMap<QString, float>();
onboardParams.insert("ROLL_K_P", 0.5f); onboardParams.insert("PID_ROLL_K_P", 0.5f);
onboardParams.insert("PITCH_K_P", 0.5f); onboardParams.insert("PID_PITCH_K_P", 0.5f);
onboardParams.insert("YAW_K_P", 0.5f); onboardParams.insert("PID_YAW_K_P", 0.5f);
onboardParams.insert("XY_K_P", 0.5f); onboardParams.insert("PID_XY_K_P", 0.5f);
onboardParams.insert("ALT_K_P", 0.5f); onboardParams.insert("PID_ALT_K_P", 0.5f);
onboardParams.insert("SYSTEM_TYPE", 1); onboardParams.insert("SYS_TYPE", 1);
onboardParams.insert("SYS_ID", systemId);
// Comments on the variables can be found in the header file // Comments on the variables can be found in the header file
...@@ -448,6 +449,22 @@ void MAVLinkSimulationLink::mainloop() ...@@ -448,6 +449,22 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength; streampointer += bufferlength;
// Send controller states
uint8_t attControl = 1;
uint8_t posXYControl = 1;
uint8_t posZControl = 0;
uint8_t posYawControl = 1;
uint8_t gpsLock = 2;
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
memcpy(stream+streampointer, buffer, bufferlength);
streampointer += bufferlength;
/* /*
// HEARTBEAT VEHICLE 2 // HEARTBEAT VEHICLE 2
......
...@@ -89,15 +89,15 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -89,15 +89,15 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
gpsFix(0), gpsFix(0),
visionFix(0), visionFix(0),
laserFix(0), laserFix(0),
mavInitialized(false) mavInitialized(false),
bottomMargin(3.0f),
topMargin(3.0f)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
refreshTimer->setInterval(60); refreshTimer->setInterval(60);
// FIXME
float bottomMargin = 3.0f;
xCenterPos = vwidth/2.0f; xCenterPos = vwidth/2.0f;
yCenterPos = vheight/2.0f - bottomMargin; yCenterPos = vheight/2.0f + topMargin - bottomMargin;
} }
void HSIDisplay::paintEvent(QPaintEvent * event) void HSIDisplay::paintEvent(QPaintEvent * event)
...@@ -118,7 +118,7 @@ void HSIDisplay::paintDisplay() ...@@ -118,7 +118,7 @@ void HSIDisplay::paintDisplay()
// Size of the ring instrument // Size of the ring instrument
const float margin = 0.1f; // 10% margin of total width on each side const float margin = 0.1f; // 10% margin of total width on each side
float baseRadius = (vheight - vheight * 2.0f * margin) / 2.0f - bottomMargin / 2.0f; float baseRadius = (vheight - topMargin - bottomMargin) / 2.0f - bottomMargin / 2.0f;
// Draw instruments // Draw instruments
// TESTING THIS SHOULD BE MOVED INTO A QGRAPHICSVIEW // TESTING THIS SHOULD BE MOVED INTO A QGRAPHICSVIEW
...@@ -139,11 +139,12 @@ void HSIDisplay::paintDisplay() ...@@ -139,11 +139,12 @@ void HSIDisplay::paintDisplay()
drawStatusFlag(2, 1, tr("ATT"), attControlEnabled, painter); drawStatusFlag(2, 1, tr("ATT"), attControlEnabled, painter);
drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled, painter); drawStatusFlag(22, 1, tr("PXY"), xyControlEnabled, painter);
drawStatusFlag(44, 1, tr("PZ"), zControlEnabled, painter); drawStatusFlag(44, 1, tr("PZ"), zControlEnabled, painter);
drawStatusFlag(66, 1, tr("YAW"), yawControlEnabled, painter);
// Draw position lock indicators // Draw position lock indicators
drawPositionLock(2, 5, tr("POS"), positionFix, painter); drawPositionLock(2, 5, tr("POS"), positionFix, painter);
drawPositionLock(22, 5, tr("VIS"), positionFix, painter); drawPositionLock(22, 5, tr("VIS"), visionFix, painter);
drawPositionLock(44, 5, tr("GPS"), positionFix, painter); drawPositionLock(44, 5, tr("GPS"), gpsFix, painter);
// Draw base instrument // Draw base instrument
...@@ -157,7 +158,7 @@ void HSIDisplay::paintDisplay() ...@@ -157,7 +158,7 @@ void HSIDisplay::paintDisplay()
const int ringCount = 2; const int ringCount = 2;
for (int i = 0; i < ringCount; i++) for (int i = 0; i < ringCount; i++)
{ {
float radius = (vwidth - vwidth * 2.0f * margin) / (2.0f * i+1) / 2.0f - bottomMargin / 2.0f; float radius = (vwidth - topMargin - bottomMargin) / (2.0f * i+1) / 2.0f - bottomMargin / 2.0f;
drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter); drawCircle(xCenterPos, yCenterPos, radius, 0.1f, ringColor, &painter);
} }
...@@ -241,11 +242,11 @@ void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, QP ...@@ -241,11 +242,11 @@ void HSIDisplay::drawStatusFlag(float x, float y, QString label, bool status, QP
QColor statusColor(250, 250, 250); QColor statusColor(250, 250, 250);
if(status) if(status)
{ {
painter.setBrush(QGC::colorRed); painter.setBrush(QGC::colorGreen);
} }
else else
{ {
painter.setBrush(QGC::colorRed); painter.setBrush(QGC::colorYellow);
} }
painter.setPen(Qt::NoPen); painter.setPen(Qt::NoPen);
painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f))); painter.drawRect(QRect(refToScreenX(x+7.3f), refToScreenY(y+0.05), refToScreenX(7.0f), refToScreenY(4.0f)));
...@@ -292,25 +293,21 @@ void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, Q ...@@ -292,25 +293,21 @@ void HSIDisplay::drawPositionLock(float x, float y, QString label, int status, Q
void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock) void HSIDisplay::updatePositionLock(UASInterface* uas, bool lock)
{ {
Q_UNUSED(uas);
positionLock = lock; positionLock = lock;
} }
void HSIDisplay::updateAttitudeControllerEnabled(UASInterface* uas, bool enabled) void HSIDisplay::updateAttitudeControllerEnabled(bool enabled)
{ {
Q_UNUSED(uas);
attControlEnabled = enabled; attControlEnabled = enabled;
} }
void HSIDisplay::updatePositionXYControllerEnabled(UASInterface* uas, bool enabled) void HSIDisplay::updatePositionXYControllerEnabled(bool enabled)
{ {
Q_UNUSED(uas);
xyControlEnabled = enabled; xyControlEnabled = enabled;
} }
void HSIDisplay::updatePositionZControllerEnabled(UASInterface* uas, bool enabled) void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
{ {
Q_UNUSED(uas);
zControlEnabled = enabled; zControlEnabled = enabled;
} }
...@@ -417,10 +414,10 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) ...@@ -417,10 +414,10 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64))); connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(UASInterface*,bool))); connect(uas, SIGNAL(attitudeControlEnabled(bool)), this, SLOT(updateAttitudeControllerEnabled(bool)));
connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(UASInterface*,bool))); connect(uas, SIGNAL(positionXYControlEnabled(bool)), this, SLOT(updatePositionXYControllerEnabled(bool)));
connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(UASInterface*,bool))); connect(uas, SIGNAL(positionZControlEnabled(bool)), this, SLOT(updatePositionZControllerEnabled(bool)));
connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(UASInterface*,bool))); connect(uas, SIGNAL(positionYawControlEnabled(bool)), this, SLOT(updatePositionYawControllerEnabled(bool)));
connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int))); connect(uas, SIGNAL(localizationChanged(UASInterface*,int)), this, SLOT(updateLocalization(UASInterface*,int)));
connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int))); connect(uas, SIGNAL(visionLocalizationChanged(UASInterface*,int)), this, SLOT(updateVisionLocalization(UASInterface*,int)));
......
...@@ -59,9 +59,9 @@ public slots: ...@@ -59,9 +59,9 @@ public slots:
void updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec); void updateGlobalPosition(UASInterface*, double lat, double lon, double alt, quint64 usec);
void updateSpeed(UASInterface* uas, double vx, double vy, double vz, quint64 time); void updateSpeed(UASInterface* uas, double vx, double vy, double vz, quint64 time);
void updatePositionLock(UASInterface* uas, bool lock); void updatePositionLock(UASInterface* uas, bool lock);
void updateAttitudeControllerEnabled(UASInterface* uas, bool enabled); void updateAttitudeControllerEnabled(bool enabled);
void updatePositionXYControllerEnabled(UASInterface* uas, bool enabled); void updatePositionXYControllerEnabled(bool enabled);
void updatePositionZControllerEnabled(UASInterface* uas, bool enabled); void updatePositionZControllerEnabled(bool enabled);
/** @brief Heading control enabled/disabled */ /** @brief Heading control enabled/disabled */
void updatePositionYawControllerEnabled(bool enabled); void updatePositionYawControllerEnabled(bool enabled);
...@@ -221,6 +221,8 @@ protected: ...@@ -221,6 +221,8 @@ protected:
int visionFix; int visionFix;
int laserFix; int laserFix;
bool mavInitialized; ///< The MAV is initialized once the setpoint has been received bool mavInitialized; ///< The MAV is initialized once the setpoint has been received
float bottomMargin; ///< Margin on the bottom of the page, in virtual coordinates
float topMargin; ///< Margin on top of the page, in virtual coordinates
private: private:
}; };
......
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