Browse Source

Merged dev-mac

QGC4.4
LM 14 years ago
parent
commit
b32df109ac
  1. 119
      files/quadrotor/pixhawk/parameters/parameters-bravo-icra2012.txt
  2. 113
      files/quadrotor/pixhawk/parameters/parameters-bravo-vicon.txt
  3. 0
      files/quadrotor/pixhawk/parameters/parameters-bravo.txt
  4. 0
      files/quadrotor/pixhawk/widgets/pixhawk-widget.qgw
  5. 26
      images/style-mission.css
  6. 11
      src/uas/UAS.cc
  7. 21
      src/uas/UASWaypointManager.cc
  8. 4
      src/uas/UASWaypointManager.h
  9. 13
      src/ui/MainWindow.cc
  10. 15
      src/ui/MainWindow.h
  11. 172
      src/ui/QGCMAVLinkLogPlayer.cc
  12. 18
      src/ui/QGCMAVLinkLogPlayer.h
  13. 64
      src/ui/QGCMAVLinkLogPlayer.ui
  14. 185
      src/ui/QGCToolBar.cc
  15. 31
      src/ui/QGCToolBar.h
  16. 1
      src/ui/uas/UASListWidget.cc

119
files/quadrotor/pixhawk/parameters/parameters-bravo-icra2012.txt

@ -0,0 +1,119 @@ @@ -0,0 +1,119 @@
# 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

113
files/quadrotor/pixhawk/parameters/parameters-bravo-vicon.txt

@ -0,0 +1,113 @@ @@ -0,0 +1,113 @@
# 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

0
files/mav_type_quadrotor/mav_autopilot_pixhawk/parameters/parameters-bravo.txt → files/quadrotor/pixhawk/parameters/parameters-bravo.txt

0
files/mav_type_quadrotor/mav_autopilot_pixhawk/widgets/pixhawk-widget.qgw → files/quadrotor/pixhawk/widgets/pixhawk-widget.qgw

26
images/style-mission.css

@ -338,6 +338,7 @@ QProgressBar { @@ -338,6 +338,7 @@ QProgressBar {
padding: 2px;
color: #DDDDDF;
background-color: #111118;
height: 10px;
}
QProgressBar:horizontal {
@ -398,3 +399,28 @@ QDialog { @@ -398,3 +399,28 @@ QDialog {
QTabBar::tab:selected {
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;
}

11
src/uas/UAS.cc

@ -44,7 +44,7 @@ warnVoltage(9.5f), @@ -44,7 +44,7 @@ warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
batteryRemainingEstimateEnabled(true),
mode(-1),
status(-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));
}
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:
{
mavlink_roll_pitch_yaw_thrust_setpoint_t out;
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&message, &out);
quint64 time = getUnixTimeFromMs(out.time_boot_ms);
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;
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_OPTICAL_FLOW:
case MAVLINK_MSG_ID_DEBUG_VECT:
case MAVLINK_MSG_ID_DEBUG:
break;
default:
{
@ -1914,7 +1908,6 @@ void UAS::receiveButton(int buttonIndex) @@ -1914,7 +1908,6 @@ void UAS::receiveButton(int buttonIndex)
}
void UAS::halt()
{
// FIXME MAVLINKV10PORTINGNEEDED

21
src/uas/UASWaypointManager.cc

@ -48,6 +48,8 @@ UASWaypointManager::UASWaypointManager(UAS &_uas) @@ -48,6 +48,8 @@ UASWaypointManager::UASWaypointManager(UAS &_uas)
protocol_timer(this)
{
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()
@ -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)
{
if (current_state == WP_GETLIST && systemId == current_partner_systemid && compId == current_partner_compid) {

4
src/uas/UASWaypointManager.h

@ -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 "QGCMAVLink.h"
class UAS;
class UASInterface;
/**
* @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 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:
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 currentWaypointChanged(quint16); ///< emits the new current waypoint sequence number
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 readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS

13
src/ui/MainWindow.cc

@ -124,6 +124,15 @@ MainWindow::MainWindow(QWidget *parent): @@ -124,6 +124,15 @@ MainWindow::MainWindow(QWidget *parent):
centerStack = new QStackedWidget(this);
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();
connectCommonWidgets();
@ -348,7 +357,9 @@ void MainWindow::buildCommonWidgets() @@ -348,7 +357,9 @@ void MainWindow::buildCommonWidgets()
if (!logPlayerDockWidget)
{
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");
addTool(logPlayerDockWidget, tr("MAVLink Log Replay"), Qt::RightDockWidgetArea);
}

15
src/ui/MainWindow.h

@ -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 "UASControlParameters.h"
#include "QGCMAVLinkInspector.h"
#include "QGCMAVLinkLogPlayer.h"
#include "MAVLinkDecoder.h"
class QGCMapTool;
@ -213,6 +213,17 @@ public slots: @@ -213,6 +213,17 @@ public slots:
*/
void showCentralWidget();
public:
QGCMAVLinkLogPlayer* getLogPlayer()
{
return logPlayer;
}
MAVLinkProtocol* getMAVLink()
{
return mavlink;
}
protected:
MainWindow(QWidget *parent = 0);
@ -332,7 +343,7 @@ protected: @@ -332,7 +343,7 @@ protected:
QPointer<QDockWidget> mavlinkInspectorWidget;
QPointer<MAVLinkDecoder> mavlinkDecoder;
QGCMAVLinkLogPlayer* logPlayer;
// Popup widgets
JoystickWidget* joystickWidget;

172
src/ui/QGCMAVLinkLogPlayer.cc

@ -20,6 +20,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare @@ -20,6 +20,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
loopCounter(0),
mavlinkLogFormat(true),
binaryBaudRate(57600),
isPlaying(false),
ui(new Ui::QGCMAVLinkLogPlayer)
{
ui->setupUi(this);
@ -33,8 +34,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare @@ -33,8 +34,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
// Setup buttons
connect(ui->selectFileButton, SIGNAL(clicked()), this, SLOT(selectLogFile()));
connect(ui->pauseButton, SIGNAL(clicked()), this, SLOT(pause()));
connect(ui->playButton, SIGNAL(clicked()), this, SLOT(play()));
connect(ui->playButton, SIGNAL(clicked()), this, SLOT(playPauseToggle()));
connect(ui->speedSlider, SIGNAL(valueChanged(int)), this, SLOT(setAccelerationFactorInt(int)));
connect(ui->positionSlider, SIGNAL(valueChanged(int)), this, SLOT(jumpToSliderVal(int)));
connect(ui->positionSlider, SIGNAL(sliderPressed()), this, SLOT(pause()));
@ -49,12 +49,37 @@ QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer() @@ -49,12 +49,37 @@ QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
delete ui;
}
void QGCMAVLinkLogPlayer::playPause(bool enabled)
{
if (enabled)
{
play();
}
else
{
pause();
}
}
void QGCMAVLinkLogPlayer::playPauseToggle()
{
if (isPlaying)
{
pause();
}
else
{
play();
}
}
void QGCMAVLinkLogPlayer::play()
{
if (logFile.isOpen()) {
ui->pauseButton->setChecked(false);
if (logFile.isOpen())
{
ui->selectFileButton->setEnabled(false);
if (logLink) {
if (logLink)
{
logLink->disconnect();
LinkManager::instance()->removeLink(logLink);
delete logLink;
@ -62,9 +87,12 @@ void QGCMAVLinkLogPlayer::play() @@ -62,9 +87,12 @@ void QGCMAVLinkLogPlayer::play()
logLink = new MAVLinkSimulationLink("");
// Start timer
if (mavlinkLogFormat) {
if (mavlinkLogFormat)
{
loopTimer.start(1);
} else {
}
else
{
// Read len bytes at a time
int len = 100;
// Calculate the number of times to read 100 bytes per second
@ -73,7 +101,11 @@ void QGCMAVLinkLogPlayer::play() @@ -73,7 +101,11 @@ void QGCMAVLinkLogPlayer::play()
int interval = 1000 / ((binaryBaudRate / 10) / len);
loopTimer.start(interval*accelerationFactor);
}
} else {
isPlaying = true;
ui->playButton->setIcon(QIcon(":images/actions/media-playback-pause.svg"));
}
else
{
ui->playButton->setChecked(false);
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Information);
@ -87,10 +119,12 @@ void QGCMAVLinkLogPlayer::play() @@ -87,10 +119,12 @@ void QGCMAVLinkLogPlayer::play()
void QGCMAVLinkLogPlayer::pause()
{
isPlaying = false;
loopTimer.stop();
ui->playButton->setChecked(false);
ui->playButton->setIcon(QIcon(":images/actions/media-playback-start.svg"));
ui->selectFileButton->setEnabled(true);
if (logLink) {
if (logLink)
{
logLink->disconnect();
LinkManager::instance()->removeLink(logLink);
delete logLink;
@ -101,36 +135,48 @@ void QGCMAVLinkLogPlayer::pause() @@ -101,36 +135,48 @@ void QGCMAVLinkLogPlayer::pause()
bool QGCMAVLinkLogPlayer::reset(int packetIndex)
{
// Reset only for valid values
if (packetIndex >= 0 && packetIndex <= logFile.size() - (packetLen+timeLen)) {
const unsigned int packetSize = timeLen + packetLen;
if (packetIndex >= 0 && packetIndex*packetSize <= logFile.size() - packetSize)
{
bool result = true;
pause();
loopCounter = 0;
logFile.reset();
if (!logFile.seek(packetIndex*(timeLen + packetLen))) {
if (!logFile.seek(packetIndex*packetSize))
{
// Fallback: Start from scratch
logFile.reset();
ui->logStatsLabel->setText(tr("Changing packet index failed, back to start."));
result = false;
}
ui->pauseButton->setChecked(true);
ui->playButton->setIcon(QIcon(":images/actions/media-playback-start.svg"));
ui->positionSlider->blockSignals(true);
int sliderVal = (packetIndex / (double)(logFile.size()/(packetLen+timeLen))) * (ui->positionSlider->maximum() - ui->positionSlider->minimum());
int sliderVal = (packetIndex / (double)(logFile.size()/packetSize)) * (ui->positionSlider->maximum() - ui->positionSlider->minimum());
ui->positionSlider->setValue(sliderVal);
ui->positionSlider->blockSignals(false);
startTime = 0;
return result;
} else {
}
else
{
return false;
}
}
void QGCMAVLinkLogPlayer::selectLogFile()
bool QGCMAVLinkLogPlayer::selectLogFile()
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink or Binary Logfile (*.mavlink *.bin)"));
QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name to replay"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink or Binary Logfile (*.mavlink *.bin *.log)"));
loadLogFile(fileName);
if (fileName == "")
{
return false;
}
else
{
return loadLogFile(fileName);
}
}
/**
@ -141,14 +187,18 @@ void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor) @@ -141,14 +187,18 @@ void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
float f = factor+1.0f;
f -= 50.0f;
if (f < 0.0f) {
if (f < 0.0f)
{
accelerationFactor = 1.0f / (-f/2.0f);
} else {
}
else
{
accelerationFactor = 1+(f/2.0f);
}
// Update timer interval
if (!mavlinkLogFormat) {
if (!mavlinkLogFormat)
{
// Read len bytes at a time
int len = 100;
// Calculate the number of times to read 100 bytes per second
@ -164,25 +214,31 @@ void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor) @@ -164,25 +214,31 @@ void QGCMAVLinkLogPlayer::setAccelerationFactorInt(int factor)
ui->speedLabel->setText(tr("Speed: %1X").arg(accelerationFactor, 5, 'f', 2, '0'));
}
void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
bool QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
{
// Check if logging is still enabled
if (mavlink->loggingEnabled()) {
if (mavlink->loggingEnabled())
{
mavlink->enableLogging(false);
MainWindow::instance()->showInfoMessage(tr("MAVLink Logging Stopped during Replay"), tr("MAVLink logging has been stopped during the log replay. To re-enable logging, use the link properties in the communication menu."));
}
// Ensure that the playback process is stopped
if (logFile.isOpen()) {
if (logFile.isOpen())
{
pause();
logFile.close();
}
logFile.setFileName(file);
if (!logFile.open(QFile::ReadOnly)) {
if (!logFile.open(QFile::ReadOnly))
{
MainWindow::instance()->showCriticalMessage(tr("The selected logfile is unreadable"), tr("Please make sure that the file %1 is readable or select a different file").arg(file));
logFile.setFileName("");
} else {
return false;
}
else
{
QFileInfo logFileInfo(file);
logFile.reset();
startTime = 0;
@ -191,7 +247,8 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file) @@ -191,7 +247,8 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
// Select if binary or MAVLink log format is used
mavlinkLogFormat = file.endsWith(".mavlink");
if (mavlinkLogFormat) {
if (mavlinkLogFormat)
{
// Get the time interval from the logfile
QByteArray timestamp = logFile.read(timeLen);
@ -216,17 +273,21 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file) @@ -216,17 +273,21 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
ui->logStatsLabel->setText(tr("%2 MB, %3 packets, %4").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(logFileInfo.size()/(MAVLINK_MAX_PACKET_LEN+sizeof(quint64))).arg(timelabel));
} else {
}
else
{
// Load in binary mode
// Set baud rate if any present
QStringList parts = logFileInfo.baseName().split("_");
if (parts.count() > 1) {
if (parts.count() > 1)
{
bool ok;
int rate = parts.last().toInt(&ok);
// 9600 baud to 100 MBit
if (ok && (rate > 9600 && rate < 100000000)) {
if (ok && (rate > 9600 && rate < 100000000))
{
// Accept this as valid baudrate
binaryBaudRate = rate;
}
@ -241,6 +302,7 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file) @@ -241,6 +302,7 @@ void QGCMAVLinkLogPlayer::loadLogFile(const QString& file)
QString timelabel = tr("%1h:%2m:%3s").arg(hours, 2).arg(minutes, 2).arg(seconds, 2);
ui->logStatsLabel->setText(tr("%2 MB, %4 at %5 KB/s").arg(logFileInfo.size()/1000000.0f, 0, 'f', 2).arg(timelabel).arg(binaryBaudRate/10.0f/1024.0f, 0, 'f', 2));
}
return true;
}
}
@ -256,8 +318,10 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue) @@ -256,8 +318,10 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
int packetIndex = (packetCount - 1) * (slidervalue / (double)(ui->positionSlider->maximum() - ui->positionSlider->minimum()));
// Do only accept valid jumps
if (reset(packetIndex)) {
if (mavlinkLogFormat) {
if (reset(packetIndex))
{
if (mavlinkLogFormat)
{
ui->logStatsLabel->setText(tr("Jumped to packet %1").arg(packetIndex));
}
}
@ -273,15 +337,18 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue) @@ -273,15 +337,18 @@ void QGCMAVLinkLogPlayer::jumpToSliderVal(int slidervalue)
*/
void QGCMAVLinkLogPlayer::logLoop()
{
if (mavlinkLogFormat) {
if (mavlinkLogFormat)
{
bool ok;
// First check initialization
if (startTime == 0) {
if (startTime == 0)
{
QByteArray startBytes = logFile.read(timeLen);
// Check if the correct number of bytes could be read
if (startBytes.length() != timeLen) {
if (startBytes.length() != timeLen)
{
ui->logStatsLabel->setText(tr("Error reading first %1 bytes").arg(timeLen));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Error reading first %1 bytes from logfile. Got %2 instead of %1 bytes. Is the logfile readable?").arg(timeLen).arg(startBytes.length()));
reset();
@ -296,7 +363,8 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -296,7 +363,8 @@ void QGCMAVLinkLogPlayer::logLoop()
//qDebug() << "START TIME: " << startTime;
// Check if these bytes could be correctly decoded
if (!ok) {
if (!ok)
{
ui->logStatsLabel->setText(tr("Error decoding first timestamp, aborting."));
MainWindow::instance()->showCriticalMessage(tr("Failed loading MAVLink Logfile"), tr("Could not load initial timestamp from file %1. Is the file corrupted?").arg(logFile.fileName()));
reset();
@ -313,7 +381,8 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -313,7 +381,8 @@ void QGCMAVLinkLogPlayer::logLoop()
emit bytesReady(logLink, packet);
// Check if reached end of file before reading next timestamp
if (chunk.length() < timeLen+packetLen || logFile.atEnd()) {
if (chunk.length() < timeLen+packetLen || logFile.atEnd())
{
// Reached end of file
reset();
@ -329,12 +398,15 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -329,12 +398,15 @@ void QGCMAVLinkLogPlayer::logLoop()
// This is the timestamp of the next packet
quint64 time = *((quint64*)(rawTime.constData()));
ok = true;
if (!ok) {
if (!ok)
{
// Convert it to 64bit number
QString status = tr("Time conversion error during log replay. Continuing..");
ui->logStatsLabel->setText(status);
MainWindow::instance()->showStatusMessage(status);
} else {
}
else
{
// Normal processing, passed all checks
// start timer to match time offset between
// this and next packet
@ -350,13 +422,18 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -350,13 +422,18 @@ void QGCMAVLinkLogPlayer::logLoop()
//qDebug() << "nextExecutionTime:" << nextExecutionTime << "QGC START TIME:" << currentStartTime << "LOG START TIME:" << startTime;
if (nextExecutionTime < 2) {
if (nextExecutionTime < 2)
{
logLoop();
} else {
}
else
{
loopTimer.start(nextExecutionTime);
}
}
} else {
}
else
{
// Binary format - read at fixed rate
const int len = 100;
QByteArray chunk = logFile.read(len);
@ -365,7 +442,8 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -365,7 +442,8 @@ void QGCMAVLinkLogPlayer::logLoop()
emit bytesReady(logLink, chunk);
// Check if reached end of file before reading next timestamp
if (chunk.length() < len || logFile.atEnd()) {
if (chunk.length() < len || logFile.atEnd())
{
// Reached end of file
reset();
@ -380,7 +458,8 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -380,7 +458,8 @@ void QGCMAVLinkLogPlayer::logLoop()
// Update status label
// Update progress bar
if (loopCounter % 40 == 0) {
if (loopCounter % 40 == 0)
{
QFileInfo logFileInfo(logFile);
int progress = (ui->positionSlider->maximum()-ui->positionSlider->minimum())*(logFile.pos()/static_cast<float>(logFileInfo.size()));
//qDebug() << "Progress:" << progress;
@ -394,7 +473,8 @@ void QGCMAVLinkLogPlayer::logLoop() @@ -394,7 +473,8 @@ void QGCMAVLinkLogPlayer::logLoop()
void QGCMAVLinkLogPlayer::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
switch (e->type())
{
case QEvent::LanguageChange:
ui->retranslateUi(this);
break;

18
src/ui/QGCMAVLinkLogPlayer.h

@ -27,8 +27,21 @@ class QGCMAVLinkLogPlayer : public QWidget @@ -27,8 +27,21 @@ class QGCMAVLinkLogPlayer : public QWidget
public:
explicit QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *parent = 0);
~QGCMAVLinkLogPlayer();
bool isPlayingLogFile()
{
return isPlaying;
}
bool isLogFileSelected()
{
return logFile.isOpen();
}
public slots:
/** @brief Toggle between play and pause */
void playPauseToggle();
/** @brief Play / pause the log */
void playPause(bool play);
/** @brief Replay the logfile */
void play();
/** @brief Pause the logfile */
@ -36,9 +49,9 @@ public slots: @@ -36,9 +49,9 @@ public slots:
/** @brief Reset the logfile */
bool reset(int packetIndex=0);
/** @brief Select logfile */
void selectLogFile();
bool selectLogFile();
/** @brief Load log file */
void loadLogFile(const QString& file);
bool loadLogFile(const QString& file);
/** @brief Jump to a position in the logfile */
void jumpToSliderVal(int slidervalue);
/** @brief The logging mainloop */
@ -64,6 +77,7 @@ protected: @@ -64,6 +77,7 @@ protected:
int loopCounter;
bool mavlinkLogFormat;
int binaryBaudRate;
bool isPlaying;
static const int packetLen = MAVLINK_MAX_PACKET_LEN;
static const int timeLen = sizeof(quint64);
void changeEvent(QEvent *e);

64
src/ui/QGCMAVLinkLogPlayer.ui

@ -75,32 +75,6 @@ @@ -75,32 +75,6 @@
</property>
</widget>
</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">
<widget class="QLabel" name="speedLabel">
<property name="toolTip">
@ -117,7 +91,23 @@ @@ -117,7 +91,23 @@
</property>
</widget>
</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">
<property name="toolTip">
<string>Start to replay the logfile</string>
@ -132,7 +122,7 @@ @@ -132,7 +122,7 @@
<string>...</string>
</property>
<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>
</property>
<property name="checkable">
@ -140,26 +130,10 @@ @@ -140,26 +130,10 @@
</property>
</widget>
</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>
</widget>
<resources>
<include location="../../mavground.qrc"/>
<include location="../../qgroundcontrol.qrc"/>
</resources>
<connections/>
</ui>

185
src/ui/QGCToolBar.cc

@ -25,22 +25,134 @@ This file is part of the QGROUNDCONTROL project @@ -25,22 +25,134 @@ This file is part of the QGROUNDCONTROL project
#include <QLabel>
#include "QGCToolBar.h"
#include "UASManager.h"
#include "MainWindow.h"
QGCToolBar::QGCToolBar(QWidget *parent) :
QToolBar(parent),
toggleLoggingAction(NULL),
logReplayAction(NULL),
mav(NULL)
mav(NULL),
player(NULL)
{
setObjectName("QGC_TOOLBAR");
createCustomWidgets();
toggleLoggingAction = new QAction(QIcon(":"), "Logging", this);
toggleLoggingAction->setCheckable(true);
logReplayAction = new QAction(QIcon(":"), "Replay", this);
logReplayAction->setCheckable(true);
addSeparator();
addAction(toggleLoggingAction);
addAction(logReplayAction);
// CREATE TOOLBAR ITEMS
// Add internal actions
// Add MAV widget
symbolButton = new QToolButton(this);
toolBarNameLabel = new QLabel("------", this);
toolBarModeLabel = new QLabel("------", this);
toolBarModeLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #3C7B9E; }");
toolBarStateLabel = new QLabel("------", this);
toolBarStateLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #FEC654; }");
toolBarWpLabel = new QLabel("WP--", this);
toolBarWpLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 18px; color: #3C7B9E; }");
toolBarDistLabel = new QLabel("--- ---- m", this);
toolBarMessageLabel = new QLabel("No system messages.", this);
toolBarMessageLabel->setStyleSheet("QLabel { margin: 0px 4px; font: 12px; font-style: italic; color: #3C7B9E; }");
toolBarBatteryBar = new QProgressBar(this);
toolBarBatteryBar->setStyleSheet("QProgressBar:horizontal { margin: 0px 4px 0px 0px; border: 1px solid #4A4A4F; border-radius: 4px; text-align: center; padding: 2px; color: #111111; background-color: #111118; height: 10px; } QProgressBar:horizontal QLabel { font-size: 9px; color: #111111; } QProgressBar::chunk { background-color: green; }");
toolBarBatteryBar->setMinimum(0);
toolBarBatteryBar->setMaximum(100);
toolBarBatteryBar->setMinimumWidth(200);
toolBarBatteryBar->setMaximumWidth(200);
toolBarBatteryVoltageLabel = new QLabel("xx.x V");
toolBarBatteryVoltageLabel->setStyleSheet(QString("QLabel { margin: 0px 0px 0px 4px; font: 14px; color: %1; }").arg(QColor(Qt::green).name()));
//symbolButton->setIcon(":");
symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 0px 0px 20px; background-color: none; }");
addWidget(symbolButton);
addWidget(toolBarNameLabel);
addWidget(toolBarModeLabel);
addWidget(toolBarStateLabel);
addWidget(toolBarBatteryBar);
addWidget(toolBarBatteryVoltageLabel);
addWidget(toolBarWpLabel);
addWidget(toolBarDistLabel);
addWidget(toolBarMessageLabel);
//addWidget(new QSpacerItem(20, 0, QSizePolicy::Expanding));
// DONE INITIALIZING BUTTONS
setActiveUAS(UASManager::instance()->getActiveUAS());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
}
void QGCToolBar::setLogPlayer(QGCMAVLinkLogPlayer* player)
{
this->player = player;
connect(toggleLoggingAction, SIGNAL(triggered(bool)), this, SLOT(playLogFile(bool)));
connect(logReplayAction, SIGNAL(triggered(bool)), this, SLOT(logging(bool)));
}
void QGCToolBar::playLogFile(bool enabled)
{
// Check if player exists
if (player)
{
// If a logfile is already replayed, stop the replay
// and select a new logfile
if (player->isPlayingLogFile())
{
player->playPause(false);
if (enabled)
{
if (!player->selectLogFile()) return;
}
}
// If no replaying happens already, start it
else
{
if (!player->selectLogFile()) return;
}
player->playPause(enabled);
}
}
void QGCToolBar::logging(bool enabled)
{
// Stop logging in any case
MainWindow::instance()->getMAVLink()->enableLogging(false);
if (enabled)
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file to save to"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink *.log *.bin);;"));
if (!fileName.endsWith(".mavlink"))
{
fileName.append(".mavlink");
}
QFileInfo file(fileName);
if (file.exists() && !file.isWritable())
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText(tr("The selected logfile is not writable"));
msgBox.setInformativeText(tr("Please make sure that the file %1 is writable or select a different file").arg(fileName));
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
}
else
{
MainWindow::instance()->getMAVLink()->setLogfileName(fileName);
MainWindow::instance()->getMAVLink()->enableLogging(true);
}
}
}
void QGCToolBar::addPerspectiveChangeAction(QAction* action)
{
addAction(action);
insertAction(toggleLoggingAction, action);
}
void QGCToolBar::setActiveUAS(UASInterface* active)
@ -56,6 +168,12 @@ void QGCToolBar::setActiveUAS(UASInterface* active) @@ -56,6 +168,12 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect(mav, SIGNAL(nameChanged(QString)), this, SLOT(updateName(QString)));
disconnect(mav, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
disconnect(mav, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
if (mav->getWaypointManager())
{
disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(int)), this, SLOT(updateCurrentWaypoint(int)));
disconnect(mav->getWaypointManager(), SIGNAL(waypointDistanceChanged(double)), this, SLOT(updateWaypointDistance(double)));
}
}
// Connect new system
@ -65,61 +183,62 @@ void QGCToolBar::setActiveUAS(UASInterface* active) @@ -65,61 +183,62 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect(active, SIGNAL(nameChanged(QString)), this, SLOT(updateName(QString)));
connect(active, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(active, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
if (active->getWaypointManager())
{
connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
connect(active->getWaypointManager(), SIGNAL(waypointDistanceChanged(double)), this, SLOT(updateWaypointDistance(double)));
}
// Update all values once
nameLabel->setText(mav->getUASName());
modeLabel->setText(mav->getShortMode());
stateLabel->setText(mav->getShortState());
toolBarNameLabel->setText(mav->getUASName());
toolBarNameLabel->setStyleSheet(QString("QLabel { font: bold 16px; color: %1; }").arg(mav->getColor().name()));
symbolButton->setStyleSheet(QString("QWidget { background-color: %1; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 4px 0px 20px; background-color: none; }").arg(mav->getColor().name()));
toolBarModeLabel->setText(mav->getShortMode());
toolBarStateLabel->setText(mav->getShortState());
setSystemType(mav, mav->getSystemType());
}
void QGCToolBar::createCustomWidgets()
{
// Add internal actions
// Add MAV widget
symbolButton = new QToolButton(this);
nameLabel = new QLabel("------", this);
modeLabel = new QLabel("------", this);
stateLabel = new QLabel("------", this);
wpLabel = new QLabel("---", this);
distlabel = new QLabel("--- ---- m", this);
messageLabel = new QLabel("No system messages.", this);
//symbolButton->setIcon(":");
symbolButton->setStyleSheet("QWidget { background-color: #050508; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px; background-color: none; }");
addWidget(symbolButton);
addWidget(nameLabel);
addWidget(modeLabel);
addWidget(stateLabel);
addWidget(wpLabel);
addWidget(distlabel);
addWidget(messageLabel);
toggleLoggingAction = new QAction(QIcon(":"), "Start Logging", this);
logReplayAction = new QAction(QIcon(":"), "Start Replay", this);
}
void QGCToolBar::updateWaypointDistance(double distance)
{
toolBarDistLabel->setText(tr("%1 m").arg(distance, 6, 'f', 2, '0'));
}
//addAction(toggleLoggingAction);
//addAction(logReplayAction);
void QGCToolBar::updateCurrentWaypoint(quint16 id)
{
toolBarWpLabel->setText(tr("WP%1").arg(id));
}
addSeparator();
void QGCToolBar::updateBatteryRemaining(UASInterface* uas, double voltage, double percent, int seconds)
{
Q_UNUSED(uas);
Q_UNUSED(seconds);
toolBarBatteryBar->setValue(percent);
toolBarBatteryVoltageLabel->setText(tr("%1 V").arg(voltage, 4, 'f', 1, ' '));
}
void QGCToolBar::updateState(UASInterface* system, QString name, QString description)
{
Q_UNUSED(system);
Q_UNUSED(description);
stateLabel->setText(tr(" State: %1").arg(name));
toolBarStateLabel->setText(tr("%1").arg(name));
}
void QGCToolBar::updateMode(int system, QString name, QString description)
{
Q_UNUSED(system);
Q_UNUSED(description);
modeLabel->setText(tr(" Mode: %1").arg(name));
toolBarModeLabel->setText(tr("%1").arg(name));
}
void QGCToolBar::updateName(const QString& name)
{
nameLabel->setText(name);
toolBarNameLabel->setText(name);
}
/**
@ -163,7 +282,7 @@ void QGCToolBar::receiveTextMessage(int uasid, int componentid, int severity, QS @@ -163,7 +282,7 @@ void QGCToolBar::receiveTextMessage(int uasid, int componentid, int severity, QS
Q_UNUSED(uasid);
Q_UNUSED(componentid);
Q_UNUSED(severity);
messageLabel->setText(text);
toolBarMessageLabel->setText(text);
}
QGCToolBar::~QGCToolBar()

31
src/ui/QGCToolBar.h

@ -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 <QToolButton>
#include <QLabel>
#include <QProgressBar>
#include "UASInterface.h"
#include "QGCMAVLinkLogPlayer.h"
class QGCToolBar : public QToolBar
{
Q_OBJECT
public:
explicit QGCToolBar(QWidget *parent = 0);
explicit QGCToolBar(QWidget* parent = 0);
void addPerspectiveChangeAction(QAction* action);
~QGCToolBar();
@ -52,6 +54,18 @@ public slots: @@ -52,6 +54,18 @@ public slots:
void setSystemType(UASInterface* uas, unsigned int systemType);
/** @brief Received system text message */
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:
void createCustomWidgets();
@ -60,12 +74,15 @@ protected: @@ -60,12 +74,15 @@ protected:
QAction* logReplayAction;
UASInterface* mav;
QToolButton* symbolButton;
QLabel* nameLabel;
QLabel* modeLabel;
QLabel* stateLabel;
QLabel* wpLabel;
QLabel* distlabel;
QLabel* messageLabel;
QLabel* toolBarNameLabel;
QLabel* toolBarModeLabel;
QLabel* toolBarStateLabel;
QLabel* toolBarWpLabel;
QLabel* toolBarDistLabel;
QLabel* toolBarMessageLabel;
QProgressBar* toolBarBatteryBar;
QLabel* toolBarBatteryVoltageLabel;
QGCMAVLinkLogPlayer* player;
};
#endif // QGCTOOLBAR_H

1
src/ui/uas/UASListWidget.cc

@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas) @@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas)
void UASListWidget::removeUAS(UASInterface* uas)
{
uasViews.remove(uas);
listLayout->removeWidget(uasViews.value(uas));
uasViews.value(uas)->deleteLater();
}

Loading…
Cancel
Save