Commit b32df109 authored by LM's avatar LM

Merged dev-mac

parents a8fc216e e1bbb9f4
# Onboard parameters for system BRAVO
#
# 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
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 29760
42 200 CAL_GYRO_Y 29671
42 200 CAL_GYRO_Z 29572
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 29557
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.81099998951
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 1
42 200 MIX_POSITION 1
42 200 MIX_POS_YAW 1
42 200 MIX_REMOTE 0
42 200 MIX_Z_POSITION 1
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.20000004768
42 200 PID_POS_I 0.10000000149
42 200 PID_POS_LIM 0.20000000298
42 200 PID_POS_P 2
42 200 PID_POS_Z_AWU 3
42 200 PID_POS_Z_D 0.25
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_ESTIM_MODE 1
42 200 POS_HOV_TRUST 0.550000011921
42 200 POS_SON_MODE 0
42 200 POS_SON_SCALE 1
42 200 POS_SP_ACCEPT 1
42 200 POS_SP_X -0.0329026989639
42 200 POS_SP_Y -0.0478124991059
42 200 POS_SP_YAW 0
42 200 POS_SP_Z -0.643148005009
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 6
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 5
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 1
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_TKO_DIST 0.5
42 200 VICON_TKO_TIME 2
42 200 VIS_OUTL_TRESH 0.20000000298
# Onboard parameters for system BRAVO
#
# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)
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
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 29760
42 200 CAL_GYRO_Y 29671
42 200 CAL_GYRO_Z 29572
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 29557
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.898000001907
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 1
42 200 MIX_POSITION 1
42 200 MIX_POS_YAW 1
42 200 MIX_REMOTE 0
42 200 MIX_Z_POSITION 1
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 3.5
42 200 PID_POS_I 0.300000011921
42 200 PID_POS_LIM 0.20000000298
42 200 PID_POS_P 3
42 200 PID_POS_Z_AWU 3
42 200 PID_POS_Z_D 0.25
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_ESTIM_MODE 3
42 200 POS_HOV_TRUST 0.5
42 200 POS_SON_MODE 0
42 200 POS_SON_SCALE 1
42 200 POS_SP_ACCEPT 1
42 200 POS_SP_X 0.254168212414
42 200 POS_SP_Y -0.378409773111
42 200 POS_SP_YAW 0
42 200 POS_SP_Z -0.0880969688296
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 6
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 5
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 1
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_TKO_DIST 0.5
42 200 VICON_TKO_TIME 2
42 200 VIS_OUTL_TRESH 0.20000000298
...@@ -338,6 +338,7 @@ QProgressBar { ...@@ -338,6 +338,7 @@ QProgressBar {
padding: 2px; padding: 2px;
color: #DDDDDF; color: #DDDDDF;
background-color: #111118; background-color: #111118;
height: 10px;
} }
QProgressBar:horizontal { QProgressBar:horizontal {
...@@ -398,3 +399,28 @@ QDialog { ...@@ -398,3 +399,28 @@ QDialog {
QTabBar::tab:selected { QTabBar::tab:selected {
border: 2px solid #379AC3; border: 2px solid #379AC3;
} }
QLabel {
background-color: transparent;
}
QLabel#toolBarNameLabel {
font: bold 16px;
color: #3C7B9E;
}
QLabel#toolBarModeLabel {
font: 12px;
}
QLabel#toolBarStateLabel {
font: 12px;
color: #3C7B9E;
}
QLabel#toolBarMessageLabel {
font: 12px;
font-style: italic;
color: #3C7B9E;
}
...@@ -44,7 +44,7 @@ warnVoltage(9.5f), ...@@ -44,7 +44,7 @@ warnVoltage(9.5f),
warnLevelPercent(20.0f), warnLevelPercent(20.0f),
currentVoltage(12.0f), currentVoltage(12.0f),
lpVoltage(12.0f), lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false), batteryRemainingEstimateEnabled(true),
mode(-1), mode(-1),
status(-1), status(-1),
navMode(-1), navMode(-1),
...@@ -603,19 +603,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -603,19 +603,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command)); emit textMessageReceived(uasId, message.compid, 0, tr("FAILURE: Rejected CMD: %1").arg(ack.command));
} }
break; break;
case MAVLINK_MSG_ID_DEBUG:
// FIXME REMOVE LATER emit valueChanged(uasId, QString("debug ") + QString::number(mavlink_msg_debug_get_ind(&message)), "raw", mavlink_msg_debug_get_value(&message), MG::TIME::getGroundTimeNow());
break;
case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT: case MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT:
{ {
mavlink_roll_pitch_yaw_thrust_setpoint_t out; mavlink_roll_pitch_yaw_thrust_setpoint_t out;
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out); mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
quint64 time = getUnixTimeFromMs(out.time_boot_ms); quint64 time = getUnixTimeFromMs(out.time_boot_ms);
emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time); emit attitudeThrustSetPointChanged(this, out.roll, out.pitch, out.yaw, out.thrust, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "att control roll", "rad", out.roll, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "att control pitch", "rad", out.pitch, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "att control yaw", "rad", out.yaw, time);
// FIXME REMOVE LATER emit valueChanged(uasId, "att control thrust", "0-1", out.thrust, time);
} }
break; break;
case MAVLINK_MSG_ID_MISSION_COUNT: case MAVLINK_MSG_ID_MISSION_COUNT:
...@@ -877,6 +870,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -877,6 +870,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW: case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
case MAVLINK_MSG_ID_OPTICAL_FLOW: case MAVLINK_MSG_ID_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT: case MAVLINK_MSG_ID_DEBUG_VECT:
case MAVLINK_MSG_ID_DEBUG:
break; break;
default: default:
{ {
...@@ -1914,7 +1908,6 @@ void UAS::receiveButton(int buttonIndex) ...@@ -1914,7 +1908,6 @@ void UAS::receiveButton(int buttonIndex)
} }
void UAS::halt() void UAS::halt()
{ {
// FIXME MAVLINKV10PORTINGNEEDED // FIXME MAVLINKV10PORTINGNEEDED
......
...@@ -48,6 +48,8 @@ UASWaypointManager::UASWaypointManager(UAS &_uas) ...@@ -48,6 +48,8 @@ UASWaypointManager::UASWaypointManager(UAS &_uas)
protocol_timer(this) protocol_timer(this)
{ {
connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout())); connect(&protocol_timer, SIGNAL(timeout()), this, SLOT(timeout()));
connect(&uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(&uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(handleGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
} }
void UASWaypointManager::timeout() void UASWaypointManager::timeout()
...@@ -85,6 +87,25 @@ void UASWaypointManager::timeout() ...@@ -85,6 +87,25 @@ void UASWaypointManager::timeout()
} }
} }
void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time)
{
Q_UNUSED(mav);
Q_UNUSED(time);
if (waypoints.count() > 0 && (waypoints[current_wp_id]->getFrame() == MAV_FRAME_LOCAL || waypoints[current_wp_id]->getFrame() == MAV_FRAME_LOCAL_ENU))
{
double xdiff = x-waypoints[current_wp_id]->getX();
double ydiff = y-waypoints[current_wp_id]->getY();
double zdiff = z-waypoints[current_wp_id]->getZ();
double dist = sqrt(xdiff*xdiff + ydiff*ydiff + zdiff*zdiff);
emit waypointDistanceChanged(dist);
}
}
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time)
{
}
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count) void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
{ {
if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid) { if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid) {
......
...@@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include "Waypoint.h" #include "Waypoint.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
class UAS; class UAS;
class UASInterface;
/** /**
* @brief Implementation of the MAVLINK waypoint protocol * @brief Implementation of the MAVLINK waypoint protocol
...@@ -138,6 +139,8 @@ public slots: ...@@ -138,6 +139,8 @@ public slots:
void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile void loadWaypoints(const QString &loadFile); ///< loads a waypoint list from loadFile
void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint void notifyOfChange(Waypoint* wp); ///< Notifies manager to changes to a waypoint
/*@}*/ /*@}*/
void handleLocalPositionChanged(UASInterface* mav, double x, double y, double z, quint64 time);
void handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time);
signals: signals:
void waypointListChanged(void); ///< emits signal that the waypoint list has been changed void waypointListChanged(void); ///< emits signal that the waypoint list has been changed
...@@ -145,6 +148,7 @@ signals: ...@@ -145,6 +148,7 @@ signals:
void waypointChanged(int uasid, Waypoint* wp); ///< emits signal that waypoint 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 currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
void updateStatusString(const QString &); ///< emits the current status string void updateStatusString(const QString &); ///< emits the current status string
void waypointDistanceChanged(double distance); ///< Distance to next waypoint changed (in meters)
void loadWPFile(); ///< emits signal that a file wp has been load 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 readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS
......
...@@ -124,6 +124,15 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -124,6 +124,15 @@ MainWindow::MainWindow(QWidget *parent):
centerStack = new QStackedWidget(this); centerStack = new QStackedWidget(this);
setCentralWidget(centerStack); setCentralWidget(centerStack);
// Load Toolbar
toolBar = new QGCToolBar(this);
this->addToolBar(toolBar);
// Add actions
toolBar->addPerspectiveChangeAction(ui.actionOperatorsView);
toolBar->addPerspectiveChangeAction(ui.actionEngineersView);
toolBar->addPerspectiveChangeAction(ui.actionPilotsView);
toolBar->addPerspectiveChangeAction(ui.actionUnconnectedView);
buildCommonWidgets(); buildCommonWidgets();
connectCommonWidgets(); connectCommonWidgets();
...@@ -348,7 +357,9 @@ void MainWindow::buildCommonWidgets() ...@@ -348,7 +357,9 @@ void MainWindow::buildCommonWidgets()
if (!logPlayerDockWidget) if (!logPlayerDockWidget)
{ {
logPlayerDockWidget = new QDockWidget(tr("MAVLink Log Player"), this); logPlayerDockWidget = new QDockWidget(tr("MAVLink Log Player"), this);
logPlayerDockWidget->setWidget( new QGCMAVLinkLogPlayer(mavlink, this) ); logPlayer = new QGCMAVLinkLogPlayer(mavlink, this);
toolBar->setLogPlayer(logPlayer);
logPlayerDockWidget->setWidget(logPlayer);
logPlayerDockWidget->setObjectName("MAVLINK_LOG_PLAYER_DOCKWIDGET"); logPlayerDockWidget->setObjectName("MAVLINK_LOG_PLAYER_DOCKWIDGET");
addTool(logPlayerDockWidget, tr("MAVLink Log Replay"), Qt::RightDockWidgetArea); addTool(logPlayerDockWidget, tr("MAVLink Log Replay"), Qt::RightDockWidgetArea);
} }
......
...@@ -76,7 +76,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -76,7 +76,7 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsPadCameraControl.h" #include "SlugsPadCameraControl.h"
#include "UASControlParameters.h" #include "UASControlParameters.h"
#include "QGCMAVLinkInspector.h" #include "QGCMAVLinkInspector.h"
#include "QGCMAVLinkLogPlayer.h"
#include "MAVLinkDecoder.h" #include "MAVLinkDecoder.h"
class QGCMapTool; class QGCMapTool;
...@@ -213,6 +213,17 @@ public slots: ...@@ -213,6 +213,17 @@ public slots:
*/ */
void showCentralWidget(); void showCentralWidget();
public:
QGCMAVLinkLogPlayer* getLogPlayer()
{
return logPlayer;
}
MAVLinkProtocol* getMAVLink()
{
return mavlink;
}
protected: protected:
MainWindow(QWidget *parent = 0); MainWindow(QWidget *parent = 0);
...@@ -332,7 +343,7 @@ protected: ...@@ -332,7 +343,7 @@ protected:
QPointer<QDockWidget> mavlinkInspectorWidget; QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder; QPointer<MAVLinkDecoder> mavlinkDecoder;
QGCMAVLinkLogPlayer* logPlayer;
// Popup widgets // Popup widgets
JoystickWidget* joystickWidget; JoystickWidget* joystickWidget;
......
This diff is collapsed.
...@@ -27,8 +27,21 @@ class QGCMAVLinkLogPlayer : public QWidget ...@@ -27,8 +27,21 @@ class QGCMAVLinkLogPlayer : public QWidget
public: public:
explicit QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent = 0); explicit QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent = 0);
~QGCMAVLinkLogPlayer(); ~QGCMAVLinkLogPlayer();
bool isPlayingLogFile()
{
return isPlaying;
}
bool isLogFileSelected()
{
return logFile.isOpen();
}
public slots: public slots:
/** @brief Toggle between play and pause */
void playPauseToggle();
/** @brief Play / pause the log */
void playPause(bool play);
/** @brief Replay the logfile */ /** @brief Replay the logfile */
void play(); void play();
/** @brief Pause the logfile */ /** @brief Pause the logfile */
...@@ -36,9 +49,9 @@ public slots: ...@@ -36,9 +49,9 @@ public slots:
/** @brief Reset the logfile */ /** @brief Reset the logfile */
bool reset(int packetIndex=0); bool reset(int packetIndex=0);
/** @brief Select logfile */ /** @brief Select logfile */
void selectLogFile(); bool selectLogFile();
/** @brief Load log file */ /** @brief Load log file */
void loadLogFile(const QString& file); bool loadLogFile(const QString& file);
/** @brief Jump to a position in the logfile */ /** @brief Jump to a position in the logfile */
void jumpToSliderVal(int slidervalue); void jumpToSliderVal(int slidervalue);
/** @brief The logging mainloop */ /** @brief The logging mainloop */
...@@ -64,6 +77,7 @@ protected: ...@@ -64,6 +77,7 @@ protected:
int loopCounter; int loopCounter;
bool mavlinkLogFormat; bool mavlinkLogFormat;
int binaryBaudRate; int binaryBaudRate;
bool isPlaying;
static const int packetLen = MAVLINK_MAX_PACKET_LEN; static const int packetLen = MAVLINK_MAX_PACKET_LEN;
static const int timeLen = sizeof(quint64); static const int timeLen = sizeof(quint64);
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
......
...@@ -75,32 +75,6 @@ ...@@ -75,32 +75,6 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="5">
<widget class="QToolButton" name="pauseButton">
<property name="toolTip">
<string>Pause the logfile</string>
</property>
<property name="statusTip">
<string>Pause the logfile</string>
</property>
<property name="whatsThis">
<string>Pause the logfile</string>
</property>
<property name="text">
<string>...</string>
</property>
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/media-playback-pause.svg</normaloff>:/images/actions/media-playback-pause.svg</iconset>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="0"> <item row="1" column="0">
<widget class="QLabel" name="speedLabel"> <widget class="QLabel" name="speedLabel">
<property name="toolTip"> <property name="toolTip">
...@@ -117,7 +91,23 @@ ...@@ -117,7 +91,23 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="3" column="4"> <item row="4" column="0" colspan="6">
<widget class="QSlider" name="positionSlider">
<property name="maximum">
<number>10000</number>
</property>
<property name="pageStep">
<number>100</number>
</property>
<property name="tracking">
<bool>false</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="3" column="5">
<widget class="QToolButton" name="playButton"> <widget class="QToolButton" name="playButton">
<property name="toolTip"> <property name="toolTip">
<string>Start to replay the logfile</string> <string>Start to replay the logfile</string>
...@@ -132,7 +122,7 @@ ...@@ -132,7 +122,7 @@
<string>...</string> <string>...</string>
</property> </property>
<property name="icon"> <property name="icon">
<iconset resource="../../mavground.qrc"> <iconset resource="../../qgroundcontrol.qrc">
<normaloff>:/images/actions/media-playback-start.svg</normaloff>:/images/actions/media-playback-start.svg</iconset> <normaloff>:/images/actions/media-playback-start.svg</normaloff>:/images/actions/media-playback-start.svg</iconset>
</property> </property>
<property name="checkable"> <property name="checkable">
...@@ -140,26 +130,10 @@ ...@@ -140,26 +130,10 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="0" colspan="6">
<widget class="QSlider" name="positionSlider">
<property name="maximum">
<number>10000</number>
</property>
<property name="pageStep">
<number>100</number>
</property>
<property name="tracking">
<bool>false</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
</layout> </layout>
</widget> </widget>
<resources> <resources>
<include location="../../mavground.qrc"/> <include location="../../qgroundcontrol.qrc"/>
</resources> </resources>
<connections/> <connections/>
</ui> </ui>
This diff is collapsed.
...@@ -28,14 +28,16 @@ This file is part of the QGROUNDCONTROL project ...@@ -28,14 +28,16 @@ This file is part of the QGROUNDCONTROL project
#include <QAction> #include <QAction>
#include <QToolButton> #include <QToolButton>
#include <QLabel> #include <QLabel>
#include <QProgressBar>
#include "UASInterface.h" #include "UASInterface.h"
#include "QGCMAVLinkLogPlayer.h"
class QGCToolBar : public QToolBar class QGCToolBar : public QToolBar
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit QGCToolBar(QWidget *parent = 0); explicit QGCToolBar(QWidget* parent = 0);
void addPerspectiveChangeAction(QAction* action); void addPerspectiveChangeAction(QAction* action);
~QGCToolBar(); ~QGCToolBar();
...@@ -52,6 +54,18 @@ public slots: ...@@ -52,6 +54,18 @@ public slots:
void setSystemType(UASInterface* uas, unsigned int systemType); void setSystemType(UASInterface* uas, unsigned int systemType);
/** @brief Received system text message */ /** @brief Received system text message */
void receiveTextMessage(int uasid, int componentid, int severity, QString text); void receiveTextMessage(int uasid, int componentid, int severity, QString text);
/** @brief Start / stop logging */
void logging(bool enabled);
/** @brief Start playing logfile */
void playLogFile(bool enabled);
/** @brief Set log playing component */
void setLogPlayer(QGCMAVLinkLogPlayer* player);
/** @brief Update battery charge state */
void updateBatteryRemaining(UASInterface* uas, double voltage, double percent, int seconds);
/** @brief Update current waypoint */
void updateCurrentWaypoint(quint16 id);
/** @brief Update distance to current waypoint */
void updateWaypointDistance(double distance);
protected: protected:
void createCustomWidgets(); void createCustomWidgets();
...@@ -60,12 +74,15 @@ protected: ...@@ -60,12 +74,15 @@ protected:
QAction* logReplayAction; QAction* logReplayAction;
UASInterface* mav; UASInterface* mav;
QToolButton* symbolButton; QToolButton* symbolButton;
QLabel* nameLabel; QLabel* toolBarNameLabel;
QLabel* modeLabel; QLabel* toolBarModeLabel;
QLabel* stateLabel; QLabel* toolBarStateLabel;
QLabel* wpLabel; QLabel* toolBarWpLabel;
QLabel* distlabel; QLabel* toolBarDistLabel;
QLabel* messageLabel; QLabel* toolBarMessageLabel;
QProgressBar* toolBarBatteryBar;
QLabel* toolBarBatteryVoltageLabel;
QGCMAVLinkLogPlayer* player;
}; };
#endif // QGCTOOLBAR_H #endif // QGCTOOLBAR_H
...@@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas) ...@@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas)
void UASListWidget::removeUAS(UASInterface* uas) void UASListWidget::removeUAS(UASInterface* uas)
{ {
uasViews.remove(uas);
listLayout->removeWidget(uasViews.value(uas)); listLayout->removeWidget(uasViews.value(uas));
uasViews.value(uas)->deleteLater(); uasViews.value(uas)->deleteLater();
} }
......
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