Commit 86c7e134 authored by lm's avatar lm
Browse files

Merged with 0.9 dev branches

parents 5d57365a 7f9de5e1
# Onboard parameters for system MAV 042
#
# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)
42 1 HANDLEWPDELAY 0.20000000298
42 1 POSFILTER 1
42 1 PROTDELAY 40
42 1 PROTTIMEOUT 2
42 1 SETPOINTDELAY 1
42 1 YAWTOLERANCE 0.174500003457
42 200 ACC_NAV_OFFS_X 0
42 200 ACC_NAV_OFFS_Y 0
42 200 ACC_NAV_OFFS_Z -1000
42 200 ATT_KAL_KACC 0.00329999998212
42 200 ATT_KAL_YAWMOD 3
42 200 ATT_OFFSET_X 0
42 200 ATT_OFFSET_Y 0
42 200 ATT_OFFSET_Z -0.0799999982119
42 200 CAL_ACC_X 0
42 200 CAL_ACC_Y 0
42 200 CAL_ACC_Z 0
42 200 CAL_FIT_ACTIVE 0
42 200 CAL_FIT_GYRO_X 31496.8007812
42 200 CAL_FIT_GYRO_Y 29383.4003906
42 200 CAL_FIT_GYRO_Z 30151.0996094
42 200 CAL_GYRO_X 29767
42 200 CAL_GYRO_Y 29654
42 200 CAL_GYRO_Z 29570
42 200 CAL_MAG_X 375
42 200 CAL_MAG_Y -25
42 200 CAL_MAG_Z -1000
42 200 CAL_PRES_DIFF 10000
42 200 CAL_TEMP 29051
42 200 CAM_ANG_X_FAC 0
42 200 CAM_ANG_X_OFF 0
42 200 CAM_ANG_Y_FAC 0
42 200 CAM_ANG_Y_OFF 0.428000003099
42 200 CAM_EXP 1000
42 200 CAM_INTERVAL 200000
42 200 DEBUG_1 0
42 200 DEBUG_2 0
42 200 DEBUG_3 0
42 200 DEBUG_4 0
42 200 DEBUG_5 1
42 200 DEBUG_6 0
42 200 GPS_MODE 0
42 200 KAL_VEL_AX 1
42 200 KAL_VEL_AY 1
42 200 KAL_VEL_BX 0
42 200 KAL_VEL_BY 0
42 200 MIX_OFFSET 0
42 200 MIX_POSITION 0
42 200 MIX_POS_YAW 0
42 200 MIX_REMOTE 0
42 200 MIX_Z_POSITION 0
42 200 PID_ATT_AWU 0.300000011921
42 200 PID_ATT_D 30
42 200 PID_ATT_I 60
42 200 PID_ATT_LIM 100
42 200 PID_ATT_P 90
42 200 PID_POS_AWU 5
42 200 PID_POS_D 2
42 200 PID_POS_I 0.20000000298
42 200 PID_POS_LIM 0.20000000298
42 200 PID_POS_P 1.79999995232
42 200 PID_POS_Z_AWU 3
42 200 PID_POS_Z_D 0.20000000298
42 200 PID_POS_Z_I 0.300000011921
42 200 PID_POS_Z_LIM 0.300000011921
42 200 PID_POS_Z_P 0.25
42 200 PID_YAWPOS_AWU 1
42 200 PID_YAWPOS_D 1
42 200 PID_YAWPOS_I 0.10000000149
42 200 PID_YAWPOS_LIM 3
42 200 PID_YAWPOS_P 5
42 200 PID_YAWSPEED_D 0
42 200 PID_YAWSPEED_I 5
42 200 PID_YAWSPEED_P 15
42 200 PID_YAWSPE_AWU 1
42 200 PID_YAWSPE_LIM 50
42 200 POS_HOV_TRUST 0.300000011921
42 200 POS_SON_MODE 0
42 200 POS_SON_SCALE 1
42 200 POS_SP_ACCEPT 1
42 200 POS_SP_X 0
42 200 POS_SP_Y 0
42 200 POS_SP_YAW 0
42 200 POS_SP_Z -0.213201999664
42 200 POS_TIMEOUT 2000000
42 200 POS_YAW_TRACK 0
42 200 RC_NICK_CHAN 1
42 200 RC_ROLL_CHAN 2
42 200 RC_SAFETY_CHAN 5
42 200 RC_THRUST_CHAN 3
42 200 RC_TRIM_CHAN 0
42 200 RC_TUNE_CHAN1 5
42 200 RC_TUNE_CHAN2 6
42 200 RC_TUNE_CHAN3 7
42 200 RC_TUNE_CHAN4 8
42 200 RC_YAW_CHAN 4
42 200 SEND_DEBUGCHAN 0
42 200 SLOT_ATTITUDE 1
42 200 SLOT_CONTROL 0
42 200 SLOT_RAW_IMU 0
42 200 SLOT_RC 0
42 200 SYS_COMP_ID 200
42 200 SYS_ID 42
42 200 SYS_IMU_RESET 0
42 200 SYS_SW_VER 2000
42 200 SYS_TYPE 2
42 200 UART_0_BAUD 115200
42 200 UART_1_BAUD 115200
42 200 VEL_DAMP 0.949999988079
42 200 VEL_OFFSET_X 0
42 200 VEL_OFFSET_Y 0
42 200 VEL_OFFSET_Z 0
42 200 VICON_MODE 0
42 200 VICON_TKO_DIST 0.5
42 200 VICON_TKO_TIME 2
42 200 VIS_OUTL_TRESH 0.20000000298
[PIXHAWK%20Quadrotor%20Commands]
QGC_TOOL_WIDGET_ITEMS\1\TYPE=BUTTON
QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_DESCRIPTION=CALIBRATE GYRO
QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_BUTTONTEXT=Calibrate
QGC_TOOL_WIDGET_ITEMS\1\QGC_ACTION_BUTTON_ACTIONID=17
QGC_TOOL_WIDGET_ITEMS\2\TYPE=BUTTON
QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_DESCRIPTION=Record logfile and images
QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_BUTTONTEXT=Start
QGC_TOOL_WIDGET_ITEMS\2\QGC_ACTION_BUTTON_ACTIONID=21
QGC_TOOL_WIDGET_ITEMS\3\TYPE=BUTTON
QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_DESCRIPTION=Stop recording
QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_BUTTONTEXT=Stop
QGC_TOOL_WIDGET_ITEMS\3\QGC_ACTION_BUTTON_ACTIONID=23
QGC_TOOL_WIDGET_ITEMS\size=3
......@@ -84,6 +84,8 @@ macx {
# Copy audio files if needed
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy contributed files
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy google earth starter file
QMAKE_POST_LINK += && cp -f $$BASEDIR/images/earth.html $$TARGETDIR/qgroundcontrol.app/Contents/MacOS
# Copy CSS stylesheets
......@@ -221,7 +223,10 @@ message("Compiling for linux 32")
DEFINES += QGC_LIBFREENECT_ENABLED
}
# Validated copy commands
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
QMAKE_POST_LINK += && cp -rf $$BASEDIR/images/Vera.ttf $$DESTDIR/images/Vera.ttf
......@@ -295,6 +300,8 @@ linux-g++-64 {
DEFINES += QGC_LIBFREENECT_ENABLED
}
# Validated copy commands
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/files $$DESTDIR
QMAKE_POST_LINK += && cp -rf $$BASEDIR/data $$DESTDIR
QMAKE_POST_LINK += && mkdir -p $$DESTDIR/images
......@@ -371,6 +378,7 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/debug) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\debug\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\debug\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\debug\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\thirdParty\\libxbee\\lib\\libxbee.dll" "$$TARGETDIR_WIN\\debug"$$escape_expand(\\n))
......@@ -391,6 +399,7 @@ DEFINES += QGC_OSG_ENABLED
exists($$TARGETDIR/release) {
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\lib\\sdl\\win32\\SDL.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\audio" "$$TARGETDIR_WIN\\release\\audio" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\files" "$$TARGETDIR_WIN\\release\\files" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(xcopy /Y "$$BASEDIR_WIN\\models" "$$TARGETDIR_WIN\\release\\models" /E /I $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\images\\earth.html" "$$TARGETDIR_WIN\\release\\earth.html" $$escape_expand(\\n))
QMAKE_POST_LINK += $$quote(copy /Y "$$BASEDIR_WIN\\thirdParty\\libxbee\\lib\\libxbee.dll" "$$TARGETDIR_WIN\\release"$$escape_expand(\\n))
......
......@@ -137,12 +137,12 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
}
}
GAudioOutput::~GAudioOutput()
{
#ifdef _MSC_VER2
::CoUninitialize();
#endif
}
//GAudioOutput::~GAudioOutput()
//{
//#ifdef _MSC_VER2
// ::CoUninitialize();
//#endif
//}
void GAudioOutput::mute(bool mute)
{
......
......@@ -124,7 +124,7 @@ protected:
bool muted;
private:
GAudioOutput(QObject* parent=NULL);
~GAudioOutput();
// ~GAudioOutput();
};
#endif // AUDIOOUTPUT_H
......@@ -49,28 +49,28 @@ quint64 groundTimeMilliseconds()
float limitAngleToPMPIf(float angle)
{
while (angle > ((float)M_PI+FLT_EPSILON)) {
angle -= 2.0f * (float)M_PI;
}
// while (angle > ((float)M_PI+FLT_EPSILON)) {
// angle -= 2.0f * (float)M_PI;
// }
while (angle <= -((float)M_PI+FLT_EPSILON)) {
angle += 2.0f * (float)M_PI;
}
// while (angle <= -((float)M_PI+FLT_EPSILON)) {
// angle += 2.0f * (float)M_PI;
// }
return angle;
}
double limitAngleToPMPId(double angle)
{
if (angle < -M_PI) {
while (angle < -M_PI) {
angle += M_PI;
}
} else if (angle > M_PI) {
while (angle > M_PI) {
angle -= M_PI;
}
}
// if (angle < -M_PI) {
// while (angle < -M_PI) {
// angle += M_PI;
// }
// } else if (angle > M_PI) {
// while (angle > M_PI) {
// angle -= M_PI;
// }
// }
return angle;
}
......
......@@ -203,7 +203,7 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv)
QGCCore::~QGCCore()
{
//mainWindow->storeSettings();
mainWindow->hide();
mainWindow->close();
mainWindow->deleteLater();
// Delete singletons
delete LinkManager::instance();
......
......@@ -66,6 +66,22 @@ protected:
DomModel* model;
void changeEvent(QEvent *e);
signals:
void visibilityChanged(bool visible);
protected:
void showEvent(QShowEvent* event)
{
QWidget::showEvent(event);
emit visibilityChanged(true);
}
void hideEvent(QHideEvent* event)
{
QWidget::hideEvent(event);
emit visibilityChanged(false);
}
private:
Ui::XMLCommProtocolWidget *m_ui;
};
......
......@@ -56,7 +56,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
// 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;
......
......@@ -77,7 +77,9 @@ attitudeKnown(false),
paramManager(NULL),
attitudeStamped(false),
lastAttitude(0),
simulation(new QGCFlightGearLink(this))
simulation(new QGCFlightGearLink(this)),
isLocalPositionKnown(false),
isGlobalPositionKnown(false)
{
color = UASInterface::getNextColor();
setBattery(LIPOLY, 3);
......@@ -343,40 +345,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f);
}
break;
case MAVLINK_MSG_ID_RAW_IMU:
{
//mavlink_raw_imu_t raw;
//mavlink_msg_raw_imu_decode(&message, &raw);
//quint64 time = getUnixTime(raw.time_usec);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel x", "raw", static_cast<double>(raw.xacc), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel y", "raw", static_cast<double>(raw.yacc), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel z", "raw", static_cast<double>(raw.zacc), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro roll", "raw", static_cast<double>(raw.xgyro), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro pitch", "raw", static_cast<double>(raw.ygyro), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro yaw", "raw", static_cast<double>(raw.zgyro), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag x", "raw", static_cast<double>(raw.xmag), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag y", "raw", static_cast<double>(raw.ymag), time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag z", "raw", static_cast<double>(raw.zmag), time);
}
break;
case MAVLINK_MSG_ID_SCALED_IMU:
{
//mavlink_scaled_imu_t scaled;
//mavlink_msg_scaled_imu_decode(&message, &scaled);
//quint64 time = getUnixTime(scaled.time_boot_ms);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel x", "g", scaled.xacc/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel y", "g", scaled.yacc/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "accel z", "g", scaled.zacc/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro roll", "rad/s", scaled.xgyro/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro pitch", "rad/s", scaled.ygyro/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gyro yaw", "rad/s", scaled.zgyro/1000.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag x", "uTesla", scaled.xmag/100.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag y", "uTesla", scaled.ymag/100.0f, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "mag z", "uTesla", scaled.zmag/100.0f, time);
}
break;
case MAVLINK_MSG_ID_ATTITUDE:
{
mavlink_attitude_t attitude;
......@@ -386,31 +354,20 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
roll = QGC::limitAngleToPMPIf(attitude.roll);
pitch = QGC::limitAngleToPMPIf(attitude.pitch);
yaw = QGC::limitAngleToPMPIf(attitude.yaw);
// FIXME REMOVE LATER emit valueChanged(uasId, "roll", "rad", roll, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "pitch", "rad", pitch, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "yaw", "rad", yaw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rollspeed", "rad/s", attitude.rollspeed, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "pitchspeed", "rad/s", attitude.pitchspeed, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "yawspeed", "rad/s", attitude.yawspeed, time);
// Emit in angles
// Convert yaw angle to compass value
// in 0 - 360 deg range
float compass = (yaw/M_PI)*180.0+360.0f;
while (compass > 360.0f) {
compass -= 360.0f;
if (compass > -10000 && compass < 10000)
{
while (compass > 360.0f) {
compass -= 360.0f;
}
}
attitudeKnown = true;
// FIXME REMOVE LATER emit valueChanged(uasId, "roll deg", "deg", (roll/M_PI)*180.0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "pitch deg", "deg", (pitch/M_PI)*180.0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "heading deg", "deg", compass, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rollspeed d/s", "deg/s", (attitude.rollspeed/M_PI)*180.0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "pitchspeed d/s", "deg/s", (attitude.pitchspeed/M_PI)*180.0, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "yawspeed d/s", "deg/s", (attitude.yawspeed/M_PI)*180.0, time);
emit attitudeChanged(this, roll, pitch, yaw, time);
emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
}
......@@ -428,12 +385,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_vfr_hud_decode(&message, &hud);
quint64 time = getUnixTime();
// Display updated values
// FIXME REMOVE LATER emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", hud.alt, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "heading", "deg", hud.heading, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "throttle", "%", hud.throttle, time);
emit thrustChanged(this, hud.throttle/100.0);
if (!attitudeKnown)
......@@ -443,26 +394,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
emit altitudeChanged(uasId, hud.alt);
//yaw = (hud.heading-180.0f/360.0f)*M_PI;
emit speedChanged(this, hud.airspeed, 0.0f, hud.climb, time);
}
break;
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
{
//mavlink_nav_controller_output_t nav;
//mavlink_msg_nav_controller_output_decode(&message, &nav);
//quint64 time = getUnixTime();
// Update UI
// FIXME REMOVE LATER emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
......@@ -473,25 +407,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
localX = pos.x;
localY = pos.y;
localZ = pos.z;
// FIXME REMOVE LATER emit valueChanged(uasId, "x", "m", pos.x, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "y", "m", pos.y, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "z", "m", pos.z, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "x speed", "m/s", pos.vx, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "y speed", "m/s", pos.vy, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "z speed", "m/s", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state
if (!positionLock) {
// If position was not locked before, notify positive
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
isLocalPositionKnown = true;
}
break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
......@@ -507,11 +432,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
speedX = pos.vx/100.0;
speedY = pos.vy/100.0;
speedZ = pos.vz/100.0;
// FIXME REMOVE LATER emit valueChanged(uasId, "latitude", "deg", latitude, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "longitude", "deg", longitude, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "altitude", "m", altitude, time);
// double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
......@@ -520,6 +440,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
GAudioOutput::instance()->notifyPositive();
}
positionLock = true;
isGlobalPositionKnown = true;
//TODO fix this hack for forwarding of global position for patch antenna tracking
forwardMessage(message);
}
......@@ -534,14 +455,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// quint64 time = getUnixTime(pos.time_usec);
quint64 time = getUnixTime(pos.time_usec);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps latitude", "deg", pos.lat/(double)1E7, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps longitude", "deg", pos.lon/(double)1E7, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps speed", "m/s", pos.vel, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps eph", "m", pos.eph/(double)1E2, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps epv", "m", pos.eph/(double)1E2, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps fix", "raw", pos.fix_type, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "gps course", "raw", pos.cog, time);
if (pos.fix_type > 2) {
emit globalPositionChanged(this, pos.lat/(double)1E7, pos.lon/(double)1E7, pos.alt/1000.0, time);
latitude = pos.lat/(double)1E7;
......@@ -587,29 +500,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit homePositionChanged(uasId, pos.latitude, pos.longitude, pos.altitude);
}
break;
case MAVLINK_MSG_ID_RAW_PRESSURE:
{
//mavlink_raw_pressure_t pressure;
//mavlink_msg_raw_pressure_decode(&message, &pressure);
//quint64 time = this->getUnixTime(pressure.time_usec);
// FIXME REMOVE LATER emit valueChanged(uasId, "abs pressure", "raw", pressure.press_abs, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure 1", "raw", pressure.press_diff1, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure 2", "raw", pressure.press_diff2, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "temperature", "raw", pressure.temperature, time);
}
break;
case MAVLINK_MSG_ID_SCALED_PRESSURE:
{
//mavlink_scaled_pressure_t pressure;
//mavlink_msg_scaled_pressure_decode(&message, &pressure);
//quint64 time = this->getUnixTime(pressure.time_boot_ms);
// FIXME REMOVE LATER emit valueChanged(uasId, "abs pressure", "hPa", pressure.press_abs, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "diff pressure", "hPa", pressure.press_diff, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "temperature", "C", pressure.temperature/100.0, time);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
{
mavlink_rc_channels_raw_t channels;
......@@ -623,15 +513,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit remoteControlChannelRawChanged(5, channels.chan6_raw);
emit remoteControlChannelRawChanged(6, channels.chan7_raw);
emit remoteControlChannelRawChanged(7, channels.chan8_raw);
// quint64 time = getUnixTime();
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #1", "us", channels.chan1_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #2", "us", channels.chan2_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #3", "us", channels.chan3_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #4", "us", channels.chan4_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #5", "us", channels.chan5_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #6", "us", channels.chan6_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #7", "us", channels.chan7_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "rc in #8", "us", channels.chan8_raw, time);
}
break;
case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
......@@ -820,34 +701,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit positionSetPointsChanged(uasId, p.x, p.y, p.z, p.yaw, QGC::groundTimeUsecs());
}
break;
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
{
//mavlink_servo_output_raw_t servos;
//mavlink_msg_servo_output_raw_decode(&message, &servos);
//quint64 time = getUnixTime();
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #1", "us", servos.servo1_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #2", "us", servos.servo2_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #3", "us", servos.servo3_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #4", "us", servos.servo4_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #5", "us", servos.servo5_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #6", "us", servos.servo6_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #7", "us", servos.servo7_raw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "servo #8", "us", servos.servo8_raw, time);
}
break;
case MAVLINK_MSG_ID_OPTICAL_FLOW:
{
//mavlink_optical_flow_t flow;
//mavlink_msg_optical_flow_decode(&message, &flow);
//quint64 time = getUnixTime(flow.time_usec);
// FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.x").arg(flow.sensor_id), "Pixel", flow.flow_x, time);
// FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.y").arg(flow.sensor_id), "Pixel", flow.flow_y, time);
// FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.qual").arg(flow.sensor_id), "0-255", flow.quality, time);
// FIXME REMOVE LATER emit valueChanged(uasId, QString("opt_flow_%1.dist").arg(flow.sensor_id), "m", flow.ground_distance, time);
}
break;
case MAVLINK_MSG_ID_STATUSTEXT:
{
QByteArray b;
......@@ -912,17 +765,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
break;
#endif
case MAVLINK_MSG_ID_DEBUG_VECT:
{
//mavlink_debug_vect_t vect;
//mavlink_msg_debug_vect_decode(&message, &vect);
//QString str((const char*)vect.name);
//quint64 time = getUnixTime(vect.time_usec);
// FIXME REMOVE LATER emit valueChanged(uasId, str+".x", "raw", vect.x, time);
// FIXME REMOVE LATER emit valueChanged(uasId, str+".y", "raw", vect.y, time);
// FIXME REMOVE LATER emit valueChanged(uasId, str+".z", "raw", vect.z, time);
}
break;
// case MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT:
// {
// mavlink_object_detection_event_t event;
......@@ -1027,6 +869,14 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
#endif
// Messages to ignore
case MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT:
case MAVLINK_MSG_ID_RAW_IMU:
case MAVLINK_MSG_ID_SCALED_IMU:
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
case MAVLINK_MSG_ID_RAW_PRESSURE:
case MAVLINK_MSG_ID_SCALED_PRESSURE:
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT:
break;
default:
{
......
......@@ -108,6 +108,14 @@ public:
double getAltitude() const {
return altitude;
}
virtual bool localPositionKnown() const
{
return isLocalPositionKnown;
}
virtual bool globalPositionKnown() const
{
return isGlobalPositionKnown;
}
double getRoll() const {
return roll;
......@@ -201,15 +209,17 @@ protected: //COMMENTS FOR TEST UNIT
quint64 imageStart;
QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
bool paramsOnceRequested; ///< If the parameter list has been read at least once
int airframe; ///< The airframe type
bool attitudeKnown; ///< True if attitude was received, false else
QGCUASParamManager* paramManager; ///< Parameter manager class
QString shortStateText; ///< Short textual state description
QString shortModeText; ///< Short textual mode description
bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
quint64 lastAttitude; ///< Timestamp of last attitude measurement
QGCFlightGearLink* simulation; ///< Hardware in the loop simulation link
QString shortStateText; ///< Short textual state description
QString shortModeText; ///< Short textual mode description
bool attitudeStamped; ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
quint64 lastAttitude; ///< Timestamp of last attitude measurement
QGCFlightGearLink* simulation; ///< Hardware in the loop simulation link
bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
public:
/** @brief Set the current battery type */
......
......@@ -76,10 +76,12 @@ public:
virtual double getLocalX() const = 0;
virtual double getLocalY() const = 0;
virtual double getLocalZ() const = 0;
virtual bool localPositionKnown() const = 0;
virtual double getLatitude() const = 0;
virtual double getLongitude() const = 0;
virtual double getAltitude() const = 0;
virtual bool globalPositionKnown() const = 0;
virtual double getRoll() const = 0;
virtual double getPitch() const = 0;
......@@ -181,15 +183,15 @@ public:
/** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/
virtual int getSystemType() = 0;
virtual QString getSystemTypeName() = 0;
/** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */
virtual int getAutopilotType() = 0;
virtual QString getAutopilotTypeName() = 0;
virtual void setAutopilotType(int apType)= 0;
QColor getColor() {
return color;
}
virtual int getAutopilotType() = 0;
virtual QString getAutopilotTypeName() = 0;
virtual void setAutopilotType(int apType)= 0;
public slots:
/** @brief Set a new name for the system */
......@@ -490,6 +492,6 @@ protected:
};
Q_DECLARE_INTERFACE(UASInterface, "org.qgroundcontrol/1.0");
Q_DECLARE_INTERFACE(UASInterface, "org.qgroundcontrol/1.0")
#endif // _UASINTERFACE_H_
......@@ -267,7 +267,7 @@ void CommConfigurationWindow::setLinkType(int linktype)
foreach (QAction* act, actions)
{
if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(tmpLink))
{
{
act->trigger();
break;
}
......
......@@ -58,8 +58,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
posXSet(0.0f),
posYSet(0.0f),
posZSet(0.0f),
attXSaturation(0.5f),
attYSaturation(0.5f),
attXSaturation(0.2f),
attYSaturation(0.2f),
attYawSaturation(0.5f),
posXSaturation(0.05f),
posYSaturation(0.05f),
......@@ -474,7 +474,7 @@ QPointF HSIDisplay::metricWorldToBody(QPointF world)
{
// First translate to body-centered coordinates
// Rotate around -yaw
float angle = yaw + M_PI;
float angle = -yaw - M_PI;
QPointF result(cos(angle) * (x - world.x()) - sin(angle) * (y - world.y()), sin(angle) * (x - world.x()) + cos(angle) * (y - world.y()));
return result;
}
......@@ -945,7 +945,7 @@ void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, con
{
if (xyControlKnown && xyControlEnabled) {
// Draw the needle
const float maxWidth = radius / 10.0f;
const float maxWidth = radius / 5.0f;
const float minWidth = maxWidth * 0.3f;
float angle = atan2(posXSet, -posYSet);
......@@ -985,10 +985,9 @@ void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, con
const float maxWidth = radius / 10.0f;
const float minWidth = maxWidth * 0.3f;
float angle = atan2(attXSet, attYSet);
angle -= (float)M_PI/2.0f;
float angle = atan2(attYSet, -attXSet);
radius *= sqrt(pow(attXSet, 2) + pow(attYSet, 2)) / sqrt(attXSaturation + attYSaturation);
radius *= sqrt(attXSet*attXSet + attYSet*attYSet) / sqrt(attXSaturation*attXSaturation + attYSaturation*attYSaturation);
QPolygonF p(6);
......
......@@ -200,14 +200,16 @@ void HUD::showEvent(QShowEvent* event)
// events
QGLWidget::showEvent(event);
refreshTimer->start(updateInterval);
emit visibilityChanged(true);
}
void HUD::hideEvent(QHideEvent* event)
{
// React only to internal (pre-display)
// events
QGLWidget::hideEvent(event);
refreshTimer->stop();
QGLWidget::hideEvent(event);
emit visibilityChanged(false);
}
void HUD::contextMenuEvent (QContextMenuEvent* event)
......@@ -1047,10 +1049,10 @@ void HUD::paintPitchLines(float pitch, QPainter* painter)
float offset = pitch;
if (offset < 0) offset = -offset;
int offsetCount = 0;
while (offset > lineDistance) {
offset -= lineDistance;
offsetCount++;
}
// while (offset > lineDistance) {
// offset -= lineDistance;
// offsetCount++;
// }
int iPos = (int)(0.5f + lineDistance); ///< The first line
int iNeg = (int)(-0.5f - lineDistance); ///< The first line
......
......@@ -113,6 +113,9 @@ protected slots:
void drawPolygon(QPolygonF refPolygon, QPainter* painter);
signals:
void visibilityChanged(bool visible);
protected:
void commitRawDataToGL();
/** @brief Convert reference coordinates to screen coordinates */
......
This diff is collapsed.
......@@ -113,9 +113,9 @@ public:
return lowPowerMode;
}
QList<QAction*> listLinkMenuActions(void);
public slots:
// /** @brief Store the mainwindow settings */
// void storeSettings();
/** @brief Shows a status message on the bottom status bar */
void showStatusMessage(const QString& status, int timeout);
......@@ -161,9 +161,6 @@ public slots:
/** @brief Show the project roadmap */
void showRoadMap();
/** @brief Shows the widgets based on configuration and current view and autopilot */
void presentView();
/** @brief Reload the CSS style sheet */
void reloadStylesheet();
/** @brief Let the user select the CSS style sheet */
......@@ -184,9 +181,15 @@ public slots:
/** @brief Add a custom tool widget */
void createCustomWidget();
/** @brief Load a custom tool widget from a file */
/** @brief Load a custom tool widget from a file chosen by user (QFileDialog) */
void loadCustomWidget();
/** @brief Load a custom tool widget from a file */
void loadCustomWidget(const QString& fileName, bool singleinstance=false);
/** @brief Load custom widgets from default file */
void loadCustomWidgetsFromDefaults(const QString& systemType, const QString& autopilotType);
void closeEvent(QCloseEvent* event);
/** @brief Load data view, allowing to plot flight data */
......@@ -195,100 +198,37 @@ public slots:
/**
* @brief Shows a Docked Widget based on the action sender
*
* This slot is written to be used in conjunction with the addToToolsMenu function
* This slot is written to be used in conjunction with the addTool() function
* It shows the QDockedWidget based on the action sender
*
*/
void showToolWidget(bool visible);
void showTool(bool visible);
/**
* @brief Shows a Widget from the center stack based on the action sender
*
* This slot is written to be used in conjunction with the addToCentralWidgetsMenu function
* This slot is written to be used in conjunction with the addCentralWidget() function
* It shows the Widget based on the action sender
*
*/
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);
/** @brief Updates a QDockWidget's location */
void updateLocationSettings (Qt::DockWidgetArea location);
public:
QList<QAction*> listLinkMenuActions(void);
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
// this will be fixed in a future release.
typedef enum _TOOLS_WIDGET_NAMES {
MENU_UAS_CONTROL_PARAM,
MENU_UAS_CONTROL,
MENU_UAS_INFO,
MENU_CAMERA,
MENU_UAS_LIST,
MENU_WAYPOINTS,
MENU_STATUS,
MENU_DETECTION,
MENU_DEBUG_CONSOLE,
MENU_PARAMETERS,
MENU_HDD_1,
MENU_HDD_2,
MENU_WATCHDOG,
MENU_HUD,
MENU_HSI,
MENU_RC_VIEW,
MENU_SLUGS_DATA,
MENU_SLUGS_PID,
MENU_SLUGS_HIL,
MENU_SLUGS_CAMERA,
MENU_MAVLINK_LOG_PLAYER,
MENU_VIDEO_STREAM_1,
MENU_VIDEO_STREAM_2,
MENU_MAVLINK_INSPECTOR,
CENTRAL_SEPARATOR= 255, // do not change
CENTRAL_LINECHART,
CENTRAL_PROTOCOL,
CENTRAL_MAP,
CENTRAL_3D_LOCAL,
CENTRAL_3D_MAP,
CENTRAL_OSGEARTH,
CENTRAL_GOOGLE_EARTH,
CENTRAL_HUD,
CENTRAL_DATA_PLOT,
} TOOLS_WIDGET_NAMES;
typedef enum _SETTINGS_SECTIONS {
SECTION_MENU,
SUB_SECTION_CHECKED,
SUB_SECTION_LOCATION
} SETTINGS_SECTIONS;
typedef enum _VIEW_SECTIONS {
typedef enum _VIEW_SECTIONS
{
VIEW_ENGINEER,
VIEW_OPERATOR,
VIEW_PILOT,
VIEW_MAVLINK,
VIEW_UNCONNECTED, ///< View in unconnected mode, when no UAS is available
VIEW_FULL ///< All widgets, mostly intended for multi-screen setups
VIEW_FULL ///< All widgets shown at once
} VIEW_SECTIONS;
QHash<int, QAction*> toolsMenuActions; // Holds ptr to the Menu Actions
QHash<int, QWidget*> dockWidgets; // Holds ptr to the Actual Dock widget
QHash<int, Qt::DockWidgetArea> dockWidgetLocations; // Holds the location
// QHash<int, QAction*> toolsMenuActions; // Holds ptr to the Menu Actions
// QHash<int, QWidget*> dockWidgets; // Holds ptr to the Actual Dock widget
/**
* @brief Adds an already instantiated QDockedWidget to the Tools Menu
......@@ -297,24 +237,11 @@ protected:
* tools menu and connects the QMenuAction to a slot that shows the widget and
* checks/unchecks the tools menu item
*
* @param widget The QDockedWidget being added
* @param widget The QDockWidget being added
* @param title The entry that will appear in the Menu and in the QDockedWidget title bar
* @param slotName The slot to which the triggered() signal of the menu action will be connected.
* @param tool The ENUM defined in MainWindow.h that is associated to the widget
* @param location The default location for the QDockedWidget in case there is no previous key in the settings
*/
void addToToolsMenu (QWidget* widget, const QString title, const char * slotName, TOOLS_WIDGET_NAMES tool, Qt::DockWidgetArea location=Qt::RightDockWidgetArea);
/**
* @brief Determines if a QDockWidget needs to be show and if so, shows it
*
* Based on the the autopilot and the current view it queries the settings and shows the
* widget if necessary
*
* @param widget The QDockWidget requested to be shown
* @param view The view for which the QDockWidget is requested
*/
void showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view = VIEW_MAVLINK);
void addTool(QDockWidget* widget, const QString& title, Qt::DockWidgetArea location=Qt::RightDockWidgetArea);
/**
* @brief Adds an already instantiated QWidget to the center stack
......@@ -326,21 +253,8 @@ protected:
*
* @param widget The QWidget being added
* @param title The entry that will appear in the Menu
* @param slotName The slot to which the triggered() signal of the menu action will be connected.
* @param centralWidget The ENUM defined in MainWindow.h that is associated to the widget
*/
void addToCentralWidgetsMenu ( QWidget* widget, const QString title,const char * slotName, TOOLS_WIDGET_NAMES centralWidget);
/**
* @brief Determines if a QWidget needs to be show and if so, shows it
*
* Based on the the autopilot and the current view it queries the settings and shows the
* widget if necessary
*
* @param centralWidget The QWidget requested to be shown
* @param view The view for which the QWidget is requested
*/
void showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SECTIONS view);
void addCentralWidget(QWidget* widget, const QString& title);
/** @brief Catch window resize events */
void resizeEvent(QResizeEvent * event);
......@@ -350,25 +264,13 @@ protected:
bool aboutToCloseFlag;
bool changingViewsFlag;
void clearView();
void storeViewState();
void loadViewState();
void buildCustomWidget();
void buildCommonWidgets();
void buildPxWidgets();
void buildSlugsWidgets();
void connectCommonWidgets();
void connectPxWidgets();
void connectSlugsWidgets();
void arrangeCommonCenterStack();
void arrangePxCenterStack();
void arrangeSlugsCenterStack();
void connectCommonActions();
void connectPxActions();
void connectSlugsActions();
void configureWindowName();
void loadSettings();
......@@ -382,12 +284,11 @@ protected:
QSettings settings;
QStackedWidget *centerStack;
QActionGroup centerStackActionGroup;
// Center widgets
QPointer<Linecharts> linechartWidget;
QPointer<HUD> hudWidget;
QPointer<QGCMapTool> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget;
......@@ -400,6 +301,7 @@ protected:
#if (defined _MSC_VER) || (defined Q_OS_MAC)
QPointer<QGCGoogleEarthView> gEarthWidget;
#endif
// Dock widgets
QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> controlParameterWidget;
......@@ -460,7 +362,6 @@ protected:
private:
Ui::MainWindow ui;
QString buildMenuKey (SETTINGS_SECTIONS section , TOOLS_WIDGET_NAMES tool, VIEW_SECTIONS view);
QString getWindowStateKey();
QString getWindowGeometryKey();
......
......@@ -51,7 +51,7 @@
<x>0</x>
<y>0</y>
<width>800</width>
<height>22</height>
<height>25</height>
</rect>
</property>
<widget class="QMenu" name="menuMGround">
......
......@@ -46,7 +46,22 @@ public slots:
/** @brief Calculate and display regression function*/
bool calculateRegression();
signals:
void visibilityChanged(bool visible);
protected:
void showEvent(QShowEvent* event)
{
QWidget::showEvent(event);
emit visibilityChanged(true);
}
void hideEvent(QHideEvent* event)
{
QWidget::hideEvent(event);
emit visibilityChanged(false);
}
void changeEvent(QEvent *e);
IncrementalPlot* plot;
LogCompressor* compressor;
......
Supports Markdown
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