Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
31a118ce
Commit
31a118ce
authored
Jul 17, 2013
by
Michael Carpenter
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
First round of fixes per Bill's git commit comments
parent
8a8e6339
Changes
38
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
38 changed files
with
490 additions
and
613 deletions
+490
-613
MainWindow.cc
src/ui/MainWindow.cc
+0
-1
MainWindow.h
src/ui/MainWindow.h
+0
-1
AP2ConfigWidget.cc
src/ui/configuration/AP2ConfigWidget.cc
+7
-1
AP2ConfigWidget.h
src/ui/configuration/AP2ConfigWidget.h
+1
-0
AccelCalibrationConfig.cc
src/ui/configuration/AccelCalibrationConfig.cc
+30
-24
AccelCalibrationConfig.h
src/ui/configuration/AccelCalibrationConfig.h
+4
-2
AdvParameterList.cc
src/ui/configuration/AdvParameterList.cc
+9
-11
AdvParameterList.h
src/ui/configuration/AdvParameterList.h
+3
-3
AdvancedParamConfig.cc
src/ui/configuration/AdvancedParamConfig.cc
+4
-4
AdvancedParamConfig.h
src/ui/configuration/AdvancedParamConfig.h
+1
-1
AirspeedConfig.cc
src/ui/configuration/AirspeedConfig.cc
+2
-2
ApmHardwareConfig.cc
src/ui/configuration/ApmHardwareConfig.cc
+42
-42
ApmHardwareConfig.h
src/ui/configuration/ApmHardwareConfig.h
+14
-14
ApmPlaneLevel.cc
src/ui/configuration/ApmPlaneLevel.cc
+13
-7
ApmSoftwareConfig.cc
src/ui/configuration/ApmSoftwareConfig.cc
+35
-139
ApmSoftwareConfig.h
src/ui/configuration/ApmSoftwareConfig.h
+11
-11
ArduCopterPidConfig.cc
src/ui/configuration/ArduCopterPidConfig.cc
+108
-122
ArduCopterPidConfig.h
src/ui/configuration/ArduCopterPidConfig.h
+3
-4
ArduPlanePidConfig.cc
src/ui/configuration/ArduPlanePidConfig.cc
+56
-54
ArduPlanePidConfig.h
src/ui/configuration/ArduPlanePidConfig.h
+1
-1
ArduRoverPidConfig.cc
src/ui/configuration/ArduRoverPidConfig.cc
+2
-0
BatteryMonitorConfig.cc
src/ui/configuration/BatteryMonitorConfig.cc
+42
-34
BatteryMonitorConfig.h
src/ui/configuration/BatteryMonitorConfig.h
+2
-0
BatteryMonitorConfig.ui
src/ui/configuration/BatteryMonitorConfig.ui
+1
-1
CameraGimbalConfig.cc
src/ui/configuration/CameraGimbalConfig.cc
+46
-62
CameraGimbalConfig.h
src/ui/configuration/CameraGimbalConfig.h
+4
-4
CompassConfig.cc
src/ui/configuration/CompassConfig.cc
+1
-14
CompassConfig.h
src/ui/configuration/CompassConfig.h
+2
-2
FailSafeConfig.cc
src/ui/configuration/FailSafeConfig.cc
+23
-5
FlightModeConfig.cc
src/ui/configuration/FlightModeConfig.cc
+6
-6
FlightModeConfig.h
src/ui/configuration/FlightModeConfig.h
+3
-2
FrameTypeConfig.cc
src/ui/configuration/FrameTypeConfig.cc
+1
-14
FrameTypeConfig.h
src/ui/configuration/FrameTypeConfig.h
+2
-2
OsdConfig.cc
src/ui/configuration/OsdConfig.cc
+1
-1
RadioCalibrationConfig.cc
src/ui/configuration/RadioCalibrationConfig.cc
+7
-12
RadioCalibrationConfig.h
src/ui/configuration/RadioCalibrationConfig.h
+3
-2
StandardParamConfig.cc
src/ui/configuration/StandardParamConfig.cc
+0
-7
StandardParamConfig.h
src/ui/configuration/StandardParamConfig.h
+0
-1
No files found.
src/ui/MainWindow.cc
View file @
31a118ce
...
...
@@ -1527,7 +1527,6 @@ void MainWindow::connectCommonActions()
connect
(
ui
.
actionEngineersView
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
loadEngineerView
()));
connect
(
ui
.
actionMissionView
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
loadOperatorView
()));
connect
(
ui
.
actionUnconnectedView
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
loadUnconnectedView
()));
//connect(ui.actionConfiguration_2,SIGNAL(triggered()),this,SLOT(loadConfigurationView()));
connect
(
ui
.
actionHardwareConfig
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
loadHardwareConfigView
()));
connect
(
ui
.
actionSoftwareConfig
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
loadSoftwareConfigView
()));
...
...
src/ui/MainWindow.h
View file @
31a118ce
...
...
@@ -30,7 +30,6 @@ This file is part of the QGROUNDCONTROL project
#ifndef _MAINWINDOW_H_
#define _MAINWINDOW_H_
#include <QtGui/QMainWindow>
#include <QStatusBar>
#include <QStackedWidget>
...
...
src/ui/configuration/AP2ConfigWidget.cc
View file @
31a118ce
#include <QMessageBox>
#include "AP2ConfigWidget.h"
AP2ConfigWidget
::
AP2ConfigWidget
(
QWidget
*
parent
)
:
QWidget
(
parent
)
...
...
@@ -8,11 +9,12 @@ AP2ConfigWidget::AP2ConfigWidget(QWidget *parent) : QWidget(parent)
}
void
AP2ConfigWidget
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
return
;
if
(
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
m_uas
=
0
;
}
if
(
!
uas
)
return
;
m_uas
=
uas
;
connect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
...
...
@@ -21,3 +23,7 @@ void AP2ConfigWidget::parameterChanged(int uas, int component, QString parameter
{
}
void
AP2ConfigWidget
::
showNullMAVErrorMessageBox
()
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
));
}
src/ui/configuration/AP2ConfigWidget.h
View file @
31a118ce
...
...
@@ -11,6 +11,7 @@ public:
explicit
AP2ConfigWidget
(
QWidget
*
parent
=
0
);
protected:
UASInterface
*
m_uas
;
void
showNullMAVErrorMessageBox
();
signals:
public
slots
:
...
...
src/ui/configuration/AccelCalibrationConfig.cc
View file @
31a118ce
#include "AccelCalibrationConfig.h"
AccelCalibrationConfig
::
AccelCalibrationConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
AccelCalibrationConfig
::
AccelCalibrationConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
m_uas
=
0
;
ui
.
setupUi
(
this
);
...
...
@@ -9,7 +9,7 @@ AccelCalibrationConfig::AccelCalibrationConfig(QWidget *parent) : QWidget(parent
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
activeUASSet
(
UASManager
::
instance
()
->
getActiveUAS
());
accelAckCount
=
0
;
m_
accelAckCount
=
0
;
}
AccelCalibrationConfig
::~
AccelCalibrationConfig
()
...
...
@@ -17,42 +17,48 @@ AccelCalibrationConfig::~AccelCalibrationConfig()
}
void
AccelCalibrationConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
if
(
m_
uas
)
{
return
;
disconnect
(
m_uas
,
SIGNAL
(
textMessageReceived
(
int
,
int
,
int
,
QString
)),
this
,
SLOT
(
uasTextMessageReceived
(
int
,
int
,
int
,
QString
)))
;
}
if
(
m_uas
)
AP2ConfigWidget
::
activeUASSet
(
uas
);
if
(
!
uas
)
{
return
;
}
m_uas
=
uas
;
connect
(
m_uas
,
SIGNAL
(
textMessageReceived
(
int
,
int
,
int
,
QString
)),
this
,
SLOT
(
uasTextMessageReceived
(
int
,
int
,
int
,
QString
)));
}
void
AccelCalibrationConfig
::
calibrateButtonClicked
()
{
if
(
accelAckCount
==
0
)
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
m_accelAckCount
==
0
)
{
MAV_CMD
command
=
MAV_CMD_PREFLIGHT_CALIBRATION
;
int
confirm
=
0
;
float
param1
=
0
;
float
param2
=
0
;
float
param3
=
0
;
float
param4
=
0
;
float
param5
=
1
;
float
param6
=
0
;
float
param7
=
0
;
float
param1
=
0
.0
;
float
param2
=
0
.0
;
float
param3
=
0
.0
;
float
param4
=
0
.0
;
float
param5
=
1
.0
;
float
param6
=
0
.0
;
float
param7
=
0
.0
;
int
component
=
1
;
m_uas
->
executeCommand
(
command
,
confirm
,
param1
,
param2
,
param3
,
param4
,
param5
,
param6
,
param7
,
component
);
}
else
if
(
accelAckCount
<=
5
)
else
if
(
m_
accelAckCount
<=
5
)
{
m_uas
->
executeCommandAck
(
accelAckCount
++
,
true
);
m_uas
->
executeCommandAck
(
m_
accelAckCount
++
,
true
);
}
else
{
m_uas
->
executeCommandAck
(
accelAckCount
++
,
true
);
m_uas
->
executeCommandAck
(
m_
accelAckCount
++
,
true
);
ui
.
calibrateAccelButton
->
setText
(
"Calibrate
\n
Accelerometer"
);
//accelAckCount = 0;
}
}
...
...
@@ -63,24 +69,24 @@ void AccelCalibrationConfig::uasTextMessageReceived(int uasid, int componentid,
if
(
severity
==
5
)
{
//This is a calibration instruction
if
(
accelAckCount
==
0
)
if
(
m_
accelAckCount
==
0
)
{
//Calibration Sucessful\r"
ui
.
calibrateAccelButton
->
setText
(
"Any
\n
Key"
);
accelAckCount
++
;
m_
accelAckCount
++
;
}
if
(
accelAckCount
==
7
)
if
(
m_
accelAckCount
==
7
)
{
//All finished
//ui.outputLabel->setText(ui.outputLabel->text() + "\n" + text);
ui
.
outputLabel
->
setText
(
text
);
accelAckCount
++
;
m_
accelAckCount
++
;
}
if
(
accelAckCount
==
8
)
if
(
m_
accelAckCount
==
8
)
{
if
(
text
.
contains
(
"Calibration"
)
&&
text
.
contains
(
"successful"
))
{
accelAckCount
=
0
;
m_
accelAckCount
=
0
;
}
ui
.
outputLabel
->
setText
(
ui
.
outputLabel
->
text
()
+
"
\n
"
+
text
);
}
...
...
src/ui/configuration/AccelCalibrationConfig.h
View file @
31a118ce
...
...
@@ -5,7 +5,9 @@
#include "ui_AccelCalibrationConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class
AccelCalibrationConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
class
AccelCalibrationConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
...
...
@@ -17,7 +19,7 @@ private slots:
void
calibrateButtonClicked
();
void
uasTextMessageReceived
(
int
uasid
,
int
componentid
,
int
severity
,
QString
text
);
private:
int
accelAckCount
;
int
m_
accelAckCount
;
Ui
::
AccelCalibrationConfig
ui
;
UASInterface
*
m_uas
;
};
...
...
src/ui/configuration/AdvParameterList.cc
View file @
31a118ce
...
...
@@ -7,8 +7,6 @@ AdvParameterList::AdvParameterList(QWidget *parent) : AP2ConfigWidget(parent)
ui
.
tableWidget
->
setColumnCount
(
4
);
ui
.
tableWidget
->
horizontalHeader
()
->
hide
();
ui
.
tableWidget
->
verticalHeader
()
->
hide
();
//ui.tableWidget->setHorizontalHeader(0);
//ui.tableWidget->setVerticalHeader(0);
ui
.
tableWidget
->
setColumnWidth
(
0
,
200
);
ui
.
tableWidget
->
setColumnWidth
(
1
,
100
);
ui
.
tableWidget
->
setColumnWidth
(
2
,
200
);
...
...
@@ -21,19 +19,19 @@ AdvParameterList::~AdvParameterList()
}
void
AdvParameterList
::
setParameterMetaData
(
QString
name
,
QString
humanname
,
QString
description
)
{
paramToNameMap
[
name
]
=
humanname
;
paramToDescriptionMap
[
name
]
=
description
;
m_
paramToNameMap
[
name
]
=
humanname
;
m_
paramToDescriptionMap
[
name
]
=
description
;
}
void
AdvParameterList
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
!
paramValueMap
.
contains
(
parameterName
))
if
(
!
m_
paramValueMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setRowCount
(
ui
.
tableWidget
->
rowCount
()
+
1
);
if
(
paramToNameMap
.
contains
(
parameterName
))
if
(
m_
paramToNameMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
0
,
new
QTableWidgetItem
(
paramToNameMap
[
parameterName
]));
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
0
,
new
QTableWidgetItem
(
m_
paramToNameMap
[
parameterName
]));
}
else
{
...
...
@@ -41,15 +39,15 @@ void AdvParameterList::parameterChanged(int uas, int component, QString paramete
}
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
1
,
new
QTableWidgetItem
(
QString
::
number
(
value
.
toFloat
(),
'f'
,
2
)));
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
2
,
new
QTableWidgetItem
(
parameterName
));
if
(
paramToDescriptionMap
.
contains
(
parameterName
))
if
(
m_
paramToDescriptionMap
.
contains
(
parameterName
))
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
3
,
new
QTableWidgetItem
(
paramToDescriptionMap
[
parameterName
]));
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
3
,
new
QTableWidgetItem
(
m_
paramToDescriptionMap
[
parameterName
]));
}
else
{
ui
.
tableWidget
->
setItem
(
ui
.
tableWidget
->
rowCount
()
-
1
,
3
,
new
QTableWidgetItem
(
"Unknown"
));
}
paramValueMap
[
parameterName
]
=
ui
.
tableWidget
->
item
(
ui
.
tableWidget
->
rowCount
()
-
1
,
1
);
m_
paramValueMap
[
parameterName
]
=
ui
.
tableWidget
->
item
(
ui
.
tableWidget
->
rowCount
()
-
1
,
1
);
}
paramValueMap
[
parameterName
]
->
setText
(
QString
::
number
(
value
.
toFloat
(),
'f'
,
2
));
m_
paramValueMap
[
parameterName
]
->
setText
(
QString
::
number
(
value
.
toFloat
(),
'f'
,
2
));
}
src/ui/configuration/AdvParameterList.h
View file @
31a118ce
...
...
@@ -16,9 +16,9 @@ public:
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
QTableWidgetItem
*>
paramValueMap
;
QMap
<
QString
,
QString
>
paramToNameMap
;
QMap
<
QString
,
QString
>
paramToDescriptionMap
;
QMap
<
QString
,
QTableWidgetItem
*>
m_
paramValueMap
;
QMap
<
QString
,
QString
>
m_
paramToNameMap
;
QMap
<
QString
,
QString
>
m_
paramToDescriptionMap
;
Ui
::
AdvParameterList
ui
;
};
...
...
src/ui/configuration/AdvancedParamConfig.cc
View file @
31a118ce
...
...
@@ -12,7 +12,7 @@ AdvancedParamConfig::~AdvancedParamConfig()
void
AdvancedParamConfig
::
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
m_
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupDouble
(
title
+
"("
+
param
+
")"
,
description
,
0
,
min
,
max
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
...
...
@@ -21,15 +21,15 @@ void AdvancedParamConfig::addRange(QString title,QString description,QString par
void
AdvancedParamConfig
::
addCombo
(
QString
title
,
QString
description
,
QString
param
,
QList
<
QPair
<
int
,
QString
>
>
valuelist
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
paramToWidgetMap
[
param
]
=
widget
;
m_
paramToWidgetMap
[
param
]
=
widget
;
widget
->
setupCombo
(
title
+
"("
+
param
+
")"
,
description
,
valuelist
);
ui
.
verticalLayout
->
addWidget
(
widget
);
widget
->
show
();
}
void
AdvancedParamConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
paramToWidgetMap
.
contains
(
parameterName
))
if
(
m_
paramToWidgetMap
.
contains
(
parameterName
))
{
paramToWidgetMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
m_
paramToWidgetMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
}
src/ui/configuration/AdvancedParamConfig.h
View file @
31a118ce
...
...
@@ -17,7 +17,7 @@ public:
private
slots
:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
ParamWidget
*>
paramToWidgetMap
;
QMap
<
QString
,
ParamWidget
*>
m_
paramToWidgetMap
;
Ui
::
AdvancedParamConfig
ui
;
};
...
...
src/ui/configuration/AirspeedConfig.cc
View file @
31a118ce
...
...
@@ -51,7 +51,7 @@ void AirspeedConfig::useCheckBoxClicked(bool checked)
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
if
(
checked
)
...
...
@@ -68,7 +68,7 @@ void AirspeedConfig::enableCheckBoxClicked(bool checked)
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
if
(
checked
)
...
...
src/ui/configuration/ApmHardwareConfig.cc
View file @
31a118ce
...
...
@@ -62,73 +62,73 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
QWidget
*
widget
=
new
QWidget
(
this
);
ui
.
stackedWidget
->
addWidget
(
widget
);
//Firmware placeholder.
buttonToConfigWidgetMap
[
ui
.
firmwareButton
]
=
widget
;
m_
buttonToConfigWidgetMap
[
ui
.
firmwareButton
]
=
widget
;
connect
(
ui
.
firmwareButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
frameConfig
=
new
FrameTypeConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
frameConfig
);
buttonToConfigWidgetMap
[
ui
.
frameTypeButton
]
=
frameConfig
;
m_
frameConfig
=
new
FrameTypeConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
frameConfig
);
m_buttonToConfigWidgetMap
[
ui
.
frameTypeButton
]
=
m_
frameConfig
;
connect
(
ui
.
frameTypeButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
compassConfig
=
new
CompassConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
compassConfig
);
buttonToConfigWidgetMap
[
ui
.
compassButton
]
=
compassConfig
;
m_
compassConfig
=
new
CompassConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
compassConfig
);
m_buttonToConfigWidgetMap
[
ui
.
compassButton
]
=
m_
compassConfig
;
connect
(
ui
.
compassButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
accelConfig
=
new
AccelCalibrationConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
accelConfig
);
buttonToConfigWidgetMap
[
ui
.
accelCalibrateButton
]
=
accelConfig
;
m_
accelConfig
=
new
AccelCalibrationConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
accelConfig
);
m_buttonToConfigWidgetMap
[
ui
.
accelCalibrateButton
]
=
m_
accelConfig
;
connect
(
ui
.
accelCalibrateButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
planeLevel
=
new
ApmPlaneLevel
(
this
);
ui
.
stackedWidget
->
addWidget
(
planeLevel
);
buttonToConfigWidgetMap
[
ui
.
arduPlaneLevelButton
]
=
planeLevel
;
m_
planeLevel
=
new
ApmPlaneLevel
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
planeLevel
);
m_buttonToConfigWidgetMap
[
ui
.
arduPlaneLevelButton
]
=
m_
planeLevel
;
connect
(
ui
.
arduPlaneLevelButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
radioConfig
=
new
RadioCalibrationConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
radioConfig
);
buttonToConfigWidgetMap
[
ui
.
radioCalibrateButton
]
=
radioConfig
;
m_
radioConfig
=
new
RadioCalibrationConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
radioConfig
);
m_buttonToConfigWidgetMap
[
ui
.
radioCalibrateButton
]
=
m_
radioConfig
;
connect
(
ui
.
radioCalibrateButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
radio3drConfig
=
new
Radio3DRConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
radio3drConfig
);
buttonToConfigWidgetMap
[
ui
.
radio3DRButton
]
=
radio3drConfig
;
m_
radio3drConfig
=
new
Radio3DRConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
radio3drConfig
);
m_buttonToConfigWidgetMap
[
ui
.
radio3DRButton
]
=
m_
radio3drConfig
;
connect
(
ui
.
radio3DRButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
batteryConfig
=
new
BatteryMonitorConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
batteryConfig
);
buttonToConfigWidgetMap
[
ui
.
batteryMonitorButton
]
=
batteryConfig
;
m_
batteryConfig
=
new
BatteryMonitorConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
batteryConfig
);
m_buttonToConfigWidgetMap
[
ui
.
batteryMonitorButton
]
=
m_
batteryConfig
;
connect
(
ui
.
batteryMonitorButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
sonarConfig
=
new
SonarConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
sonarConfig
);
buttonToConfigWidgetMap
[
ui
.
sonarButton
]
=
sonarConfig
;
m_
sonarConfig
=
new
SonarConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
sonarConfig
);
m_buttonToConfigWidgetMap
[
ui
.
sonarButton
]
=
m_
sonarConfig
;
connect
(
ui
.
sonarButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
airspeedConfig
=
new
AirspeedConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
airspeedConfig
);
buttonToConfigWidgetMap
[
ui
.
airspeedButton
]
=
airspeedConfig
;
m_
airspeedConfig
=
new
AirspeedConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
airspeedConfig
);
m_buttonToConfigWidgetMap
[
ui
.
airspeedButton
]
=
m_
airspeedConfig
;
connect
(
ui
.
airspeedButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
opticalFlowConfig
=
new
OpticalFlowConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
opticalFlowConfig
);
buttonToConfigWidgetMap
[
ui
.
opticalFlowButton
]
=
opticalFlowConfig
;
m_
opticalFlowConfig
=
new
OpticalFlowConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
opticalFlowConfig
);
m_buttonToConfigWidgetMap
[
ui
.
opticalFlowButton
]
=
m_
opticalFlowConfig
;
connect
(
ui
.
opticalFlowButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
osdConfig
=
new
OsdConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
osdConfig
);
buttonToConfigWidgetMap
[
ui
.
osdButton
]
=
osdConfig
;
m_
osdConfig
=
new
OsdConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
osdConfig
);
m_buttonToConfigWidgetMap
[
ui
.
osdButton
]
=
m_
osdConfig
;
connect
(
ui
.
osdButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
cameraGimbalConfig
=
new
CameraGimbalConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
cameraGimbalConfig
);
buttonToConfigWidgetMap
[
ui
.
cameraGimbalButton
]
=
cameraGimbalConfig
;
m_
cameraGimbalConfig
=
new
CameraGimbalConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
cameraGimbalConfig
);
m_buttonToConfigWidgetMap
[
ui
.
cameraGimbalButton
]
=
m_
cameraGimbalConfig
;
connect
(
ui
.
cameraGimbalButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
antennaTrackerConfig
=
new
AntennaTrackerConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
antennaTrackerConfig
);
buttonToConfigWidgetMap
[
ui
.
antennaTrackerButton
]
=
antennaTrackerConfig
;
m_
antennaTrackerConfig
=
new
AntennaTrackerConfig
(
this
);
ui
.
stackedWidget
->
addWidget
(
m_
antennaTrackerConfig
);
m_buttonToConfigWidgetMap
[
ui
.
antennaTrackerButton
]
=
m_
antennaTrackerConfig
;
connect
(
ui
.
antennaTrackerButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
activateStackedWidget
()));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
...
...
@@ -139,9 +139,9 @@ ApmHardwareConfig::ApmHardwareConfig(QWidget *parent) : QWidget(parent)
}
void
ApmHardwareConfig
::
activateStackedWidget
()
{
if
(
buttonToConfigWidgetMap
.
contains
(
sender
()))
if
(
m_
buttonToConfigWidgetMap
.
contains
(
sender
()))
{
ui
.
stackedWidget
->
setCurrentWidget
(
buttonToConfigWidgetMap
[
sender
()]);
ui
.
stackedWidget
->
setCurrentWidget
(
m_
buttonToConfigWidgetMap
[
sender
()]);
}
}
...
...
src/ui/configuration/ApmHardwareConfig.h
View file @
31a118ce
...
...
@@ -58,20 +58,20 @@ public:
explicit
ApmHardwareConfig
(
QWidget
*
parent
=
0
);
~
ApmHardwareConfig
();
private:
FrameTypeConfig
*
frameConfig
;
CompassConfig
*
compassConfig
;
AccelCalibrationConfig
*
accelConfig
;
RadioCalibrationConfig
*
radioConfig
;
FrameTypeConfig
*
m_
frameConfig
;
CompassConfig
*
m_
compassConfig
;
AccelCalibrationConfig
*
m_
accelConfig
;
RadioCalibrationConfig
*
m_
radioConfig
;
Radio3DRConfig
*
radio3drConfig
;
BatteryMonitorConfig
*
batteryConfig
;
SonarConfig
*
sonarConfig
;
AirspeedConfig
*
airspeedConfig
;
OpticalFlowConfig
*
opticalFlowConfig
;
OsdConfig
*
osdConfig
;
CameraGimbalConfig
*
cameraGimbalConfig
;
AntennaTrackerConfig
*
antennaTrackerConfig
;
ApmPlaneLevel
*
planeLevel
;
Radio3DRConfig
*
m_
radio3drConfig
;
BatteryMonitorConfig
*
m_
batteryConfig
;
SonarConfig
*
m_
sonarConfig
;
AirspeedConfig
*
m_
airspeedConfig
;
OpticalFlowConfig
*
m_
opticalFlowConfig
;
OsdConfig
*
m_
osdConfig
;
CameraGimbalConfig
*
m_
cameraGimbalConfig
;
AntennaTrackerConfig
*
m_
antennaTrackerConfig
;
ApmPlaneLevel
*
m_
planeLevel
;
private
slots
:
void
activeUASSet
(
UASInterface
*
uas
);
void
activateStackedWidget
();
...
...
@@ -79,7 +79,7 @@ private:
Ui
::
ApmHardwareConfig
ui
;
//This is a map between the buttons, and the widgets they should be displying
QMap
<
QObject
*
,
QWidget
*>
buttonToConfigWidgetMap
;
QMap
<
QObject
*
,
QWidget
*>
m_
buttonToConfigWidgetMap
;
};
#endif // APMHARDWARECONFIG_H
src/ui/configuration/ApmPlaneLevel.cc
View file @
31a118ce
...
...
@@ -13,16 +13,21 @@ ApmPlaneLevel::~ApmPlaneLevel()
}
void
ApmPlaneLevel
::
levelClicked
()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
QMessageBox
::
information
(
0
,
"Warning"
,
"Be sure the plane is completly level, then click ok"
);
MAV_CMD
command
=
MAV_CMD_PREFLIGHT_CALIBRATION
;
int
confirm
=
0
;
float
param1
=
1
;
float
param2
=
0
;
float
param3
=
1
;
float
param4
=
0
;
float
param5
=
0
;
float
param6
=
0
;
float
param7
=
0
;
float
param1
=
1
.0
;
float
param2
=
0
.0
;
float
param3
=
1
.0
;
float
param4
=
0
.0
;
float
param5
=
0
.0
;
float
param6
=
0
.0
;
float
param7
=
0
.0
;
int
component
=
1
;
m_uas
->
executeCommand
(
command
,
confirm
,
param1
,
param2
,
param3
,
param4
,
param5
,
param6
,
param7
,
component
);
QMessageBox
::
information
(
0
,
"Warning"
,
"Leveling completed"
);
...
...
@@ -32,6 +37,7 @@ void ApmPlaneLevel::manualCheckBoxToggled(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
src/ui/configuration/ApmSoftwareConfig.cc
View file @
31a118ce
This diff is collapsed.
Click to expand it.
src/ui/configuration/ApmSoftwareConfig.h
View file @
31a118ce
...
...
@@ -28,17 +28,17 @@ private slots:
void
activeUASSet
(
UASInterface
*
uas
);
private:
Ui
::
ApmSoftwareConfig
ui
;
BasicPidConfig
*
basicPidConfig
;
FlightModeConfig
*
flightConfig
;
StandardParamConfig
*
standardParamConfig
;
GeoFenceConfig
*
geoFenceConfig
;
FailSafeConfig
*
failSafeConfig
;
AdvancedParamConfig
*
advancedParamConfig
;
ArduCopterPidConfig
*
arduCopterPidConfig
;
ArduPlanePidConfig
*
arduPlanePidConfig
;
ArduRoverPidConfig
*
arduRoverPidConfig
;
AdvParameterList
*
advParameterList
;
QMap
<
QObject
*
,
QWidget
*>
buttonToConfigWidgetMap
;
BasicPidConfig
*
m_
basicPidConfig
;
FlightModeConfig
*
m_
flightConfig
;
StandardParamConfig
*
m_
standardParamConfig
;
GeoFenceConfig
*
m_
geoFenceConfig
;
FailSafeConfig
*
m_
failSafeConfig
;
AdvancedParamConfig
*
m_
advancedParamConfig
;
ArduCopterPidConfig
*
m_
arduCopterPidConfig
;
ArduPlanePidConfig
*
m_
arduPlanePidConfig
;
ArduRoverPidConfig
*
m_
arduRoverPidConfig
;
AdvParameterList
*
m_
advParameterList
;
QMap
<
QObject
*
,
QWidget
*>
m_
buttonToConfigWidgetMap
;
};
#endif // APMSOFTWARECONFIG_H
src/ui/configuration/ArduCopterPidConfig.cc
View file @
31a118ce
This diff is collapsed.
Click to expand it.
src/ui/configuration/ArduCopterPidConfig.h
View file @
31a118ce
...
...
@@ -18,10 +18,9 @@ private slots:
void
refreshButtonClicked
();
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QList
<
QPair
<
int
,
QString
>
>
ch6ValueToTextList
;
QList
<
QPair
<
int
,
QString
>
>
ch7ValueToTextList
;
QList
<
QPair
<
int
,
QString
>
>
ch8ValueToTextList
;
QMap
<
QString
,
QDoubleSpinBox
*>
nameToBoxMap
;
QList
<
QPair
<
int
,
QString
>
>
m_ch6ValueToTextList
;
QList
<
QPair
<
int
,
QString
>
>
m_ch78ValueToTextList
;
QMap
<
QString
,
QDoubleSpinBox
*>
m_nameToBoxMap
;
Ui
::
ArduCopterPidConfig
ui
;
};
...
...
src/ui/configuration/ArduPlanePidConfig.cc
View file @
31a118ce
...
...
@@ -5,56 +5,56 @@ ArduPlanePidConfig::ArduPlanePidConfig(QWidget *parent) : AP2ConfigWidget(parent
{
ui
.
setupUi
(
this
);
nameToBoxMap
[
"RLL2SRV_P"
]
=
ui
.
servoRollPSpinBox
;
nameToBoxMap
[
"RLL2SRV_I"
]
=
ui
.
servoRollISpinBox
;
nameToBoxMap
[
"RLL2SRV_D"
]
=
ui
.
servoRollDSpinBox
;
nameToBoxMap
[
"RLL2SRV_IMAX"
]
=
ui
.
servoRollIMAXSpinBox
;
nameToBoxMap
[
"PTCH2SRV_P"
]
=
ui
.
servoPitchPSpinBox
;
nameToBoxMap
[
"PTCH2SRV_I"
]
=
ui
.
servoPitchISpinBox
;
nameToBoxMap
[
"PTCH2SRV_D"
]
=
ui
.
servoPitchDSpinBox
;
nameToBoxMap
[
"PTCH2SRV_IMAX"
]
=
ui
.
servoPitchIMAXSpinBox
;
nameToBoxMap
[
"YW2SRV_P"
]
=
ui
.
servoYawPSpinBox
;
nameToBoxMap
[
"YW2SRV_I"
]
=
ui
.
servoYawISpinBox
;
nameToBoxMap
[
"YW2SRV_D"
]
=
ui
.
servoYawDSpinBox
;
nameToBoxMap
[
"YW2SRV_IMAX"
]
=
ui
.
servoYawIMAXSpinBox
;
nameToBoxMap
[
"ALT2PTCH_P"
]
=
ui
.
navAltPSpinBox
;
nameToBoxMap
[
"ALT2PTCH_I"
]
=
ui
.
navAltISpinBox
;
nameToBoxMap
[
"ALT2PTCH_D"
]
=
ui
.
navAltDSpinBox
;
nameToBoxMap
[
"ALT2PTCH_IMAX"
]
=
ui
.
navAltIMAXSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_P"
]
=
ui
.
navASPSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_I"
]
=
ui
.
navASISpinBox
;
nameToBoxMap
[
"ARSP2PTCH_D"
]
=
ui
.
navASDSpinBox
;
nameToBoxMap
[
"ARSP2PTCH_IMAX"
]
=
ui
.
navASIMAXSpinBox
;
nameToBoxMap
[
"ENRGY2THR_P"
]
=
ui
.
energyPSpinBox
;
nameToBoxMap
[
"ENRGY2THR_I"
]
=
ui
.
energyISpinBox
;
nameToBoxMap
[
"ENRGY2THR_D"
]
=
ui
.
energyDSpinBox
;
nameToBoxMap
[
"ENRGY2THR_IMAX"
]
=
ui
.
energyIMAXSpinBox
;
nameToBoxMap
[
"KFF_PTCH2THR"
]
=
ui
.
otherPitchCompSpinBox
;
nameToBoxMap
[
"KFF_PTCHCOMP"
]
=
ui
.
otherPtTSpinBox
;
nameToBoxMap
[
"KFF_RDDRMIX"
]
=
ui
.
otherRudderMixSpinBox
;
nameToBoxMap
[
"TRIM_THROTTLE"
]
=
ui
.
throttleCruiseSpinBox
;
nameToBoxMap
[
"THR_FS_VALUE"
]
=
ui
.
throttleFSSpinBox
;
nameToBoxMap
[
"THR_MAX"
]
=
ui
.
throttleMaxSpinBox
;
nameToBoxMap
[
"THR_MIN"
]
=
ui
.
throttleMinSpinBox
;
nameToBoxMap
[
"TRIM_ARSPD_CM"
]
=
ui
.
airspeedCruiseSpinBox
;
nameToBoxMap
[
"ARSPD_FBW_MAX"
]
=
ui
.
airspeedFBWMaxSpinBox
;
nameToBoxMap
[
"ARSPD_FBW_MIN"
]
=
ui
.
airspeedFBWMinSpinBox
;
nameToBoxMap
[
"ARSPD_RATIO"
]
=
ui
.
airspeedRatioSpinBox
;
nameToBoxMap
[
"NAVL1_DAMPING"
]
=
ui
.
l1DampingSpinBox
;
nameToBoxMap
[
"NAVL1_PERIOD"
]
=
ui
.
l1PeriodSpinBox
;
nameToBoxMap
[
"LIM_ROLL_CD"
]
=
ui
.
navBankMaxSpinBox
;
nameToBoxMap
[
"LIM_PITCH_MAX"
]
=
ui
.
navPitchMaxSpinBox
;
nameToBoxMap
[
"LIM_PITCH_MIN"
]
=
ui
.
navPitchMinSpinBox
;
m_
nameToBoxMap
[
"RLL2SRV_P"
]
=
ui
.
servoRollPSpinBox
;
m_
nameToBoxMap
[
"RLL2SRV_I"
]
=
ui
.
servoRollISpinBox
;
m_
nameToBoxMap
[
"RLL2SRV_D"
]
=
ui
.
servoRollDSpinBox
;
m_
nameToBoxMap
[
"RLL2SRV_IMAX"
]
=
ui
.
servoRollIMAXSpinBox
;
m_
nameToBoxMap
[
"PTCH2SRV_P"
]
=
ui
.
servoPitchPSpinBox
;
m_
nameToBoxMap
[
"PTCH2SRV_I"
]
=
ui
.
servoPitchISpinBox
;
m_
nameToBoxMap
[
"PTCH2SRV_D"
]
=
ui
.
servoPitchDSpinBox
;
m_
nameToBoxMap
[
"PTCH2SRV_IMAX"
]
=
ui
.
servoPitchIMAXSpinBox
;
m_
nameToBoxMap
[
"YW2SRV_P"
]
=
ui
.
servoYawPSpinBox
;
m_
nameToBoxMap
[
"YW2SRV_I"
]
=
ui
.
servoYawISpinBox
;
m_
nameToBoxMap
[
"YW2SRV_D"
]
=
ui
.
servoYawDSpinBox
;
m_
nameToBoxMap
[
"YW2SRV_IMAX"
]
=
ui
.
servoYawIMAXSpinBox
;
m_
nameToBoxMap
[
"ALT2PTCH_P"
]
=
ui
.
navAltPSpinBox
;
m_
nameToBoxMap
[
"ALT2PTCH_I"
]
=
ui
.
navAltISpinBox
;
m_
nameToBoxMap
[
"ALT2PTCH_D"
]
=
ui
.
navAltDSpinBox
;
m_
nameToBoxMap
[
"ALT2PTCH_IMAX"
]
=
ui
.
navAltIMAXSpinBox
;
m_
nameToBoxMap
[
"ARSP2PTCH_P"
]
=
ui
.
navASPSpinBox
;
m_
nameToBoxMap
[
"ARSP2PTCH_I"
]
=
ui
.
navASISpinBox
;
m_
nameToBoxMap
[
"ARSP2PTCH_D"
]
=
ui
.
navASDSpinBox
;
m_
nameToBoxMap
[
"ARSP2PTCH_IMAX"
]
=
ui
.
navASIMAXSpinBox
;
m_
nameToBoxMap
[
"ENRGY2THR_P"
]
=
ui
.
energyPSpinBox
;
m_
nameToBoxMap
[
"ENRGY2THR_I"
]
=
ui
.
energyISpinBox
;
m_
nameToBoxMap
[
"ENRGY2THR_D"
]
=
ui
.
energyDSpinBox
;
m_
nameToBoxMap
[
"ENRGY2THR_IMAX"
]
=
ui
.
energyIMAXSpinBox
;
m_
nameToBoxMap
[
"KFF_PTCH2THR"
]
=
ui
.
otherPitchCompSpinBox
;
m_
nameToBoxMap
[
"KFF_PTCHCOMP"
]
=
ui
.
otherPtTSpinBox
;
m_
nameToBoxMap
[
"KFF_RDDRMIX"
]
=
ui
.
otherRudderMixSpinBox
;
m_
nameToBoxMap
[
"TRIM_THROTTLE"
]
=
ui
.
throttleCruiseSpinBox
;
m_
nameToBoxMap
[
"THR_FS_VALUE"
]
=
ui
.
throttleFSSpinBox
;
m_
nameToBoxMap
[
"THR_MAX"
]
=
ui
.
throttleMaxSpinBox
;
m_
nameToBoxMap
[
"THR_MIN"
]
=
ui
.
throttleMinSpinBox
;
m_
nameToBoxMap
[
"TRIM_ARSPD_CM"
]
=
ui
.
airspeedCruiseSpinBox
;
m_
nameToBoxMap
[
"ARSPD_FBW_MAX"
]
=
ui
.
airspeedFBWMaxSpinBox
;
m_
nameToBoxMap
[
"ARSPD_FBW_MIN"
]
=
ui
.
airspeedFBWMinSpinBox
;
m_
nameToBoxMap
[
"ARSPD_RATIO"
]
=
ui
.
airspeedRatioSpinBox
;
m_
nameToBoxMap
[
"NAVL1_DAMPING"
]
=
ui
.
l1DampingSpinBox
;
m_
nameToBoxMap
[
"NAVL1_PERIOD"
]
=
ui
.
l1PeriodSpinBox
;
m_
nameToBoxMap
[
"LIM_ROLL_CD"
]
=
ui
.
navBankMaxSpinBox
;
m_
nameToBoxMap
[
"LIM_PITCH_MAX"
]
=
ui
.
navPitchMaxSpinBox
;
m_
nameToBoxMap
[
"LIM_PITCH_MIN"
]
=
ui
.
navPitchMinSpinBox
;
connect
(
ui
.
writePushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
writeButtonClicked
()));
connect
(
ui
.
refreshPushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
refreshButtonClicked
()));
...
...
@@ -66,18 +66,19 @@ ArduPlanePidConfig::~ArduPlanePidConfig()
}
void
ArduPlanePidConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
nameToBoxMap
.
contains
(
parameterName
))
if
(
m_
nameToBoxMap
.
contains
(
parameterName
))
{
nameToBoxMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
m_
nameToBoxMap
[
parameterName
]
->
setValue
(
value
.
toDouble
());
}
}
void
ArduPlanePidConfig
::
writeButtonClicked
()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
nameToBoxMap
.
constBegin
();
i
!=
nameToBoxMap
.
constEnd
();
i
++
)
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
m_nameToBoxMap
.
constBegin
();
i
!=
m_
nameToBoxMap
.
constEnd
();
i
++
)
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
i
.
key
(),
i
.
value
()
->
value
());
}
...
...
@@ -87,9 +88,10 @@ void ArduPlanePidConfig::refreshButtonClicked()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
nameToBoxMap
.
constBegin
();
i
!=
nameToBoxMap
.
constEnd
();
i
++
)
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
m_nameToBoxMap
.
constBegin
();
i
!=
m_
nameToBoxMap
.
constEnd
();
i
++
)
{
m_uas
->
getParamManager
()
->
requestParameterUpdate
(
1
,
i
.
key
());
}
...
...
src/ui/configuration/ArduPlanePidConfig.h
View file @
31a118ce
...
...
@@ -17,7 +17,7 @@ private slots:
void
writeButtonClicked
();
void
refreshButtonClicked
();
private:
QMap
<
QString
,
QDoubleSpinBox
*>
nameToBoxMap
;
QMap
<
QString
,
QDoubleSpinBox
*>
m_
nameToBoxMap
;
Ui
::
ArduPlanePidConfig
ui
;
};
...
...
src/ui/configuration/ArduRoverPidConfig.cc
View file @
31a118ce
...
...
@@ -49,6 +49,7 @@ void ArduRoverPidConfig::writeButtonClicked()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
nameToBoxMap
.
constBegin
();
i
!=
nameToBoxMap
.
constEnd
();
i
++
)
...
...
@@ -61,6 +62,7 @@ void ArduRoverPidConfig::refreshButtonClicked()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
for
(
QMap
<
QString
,
QDoubleSpinBox
*>::
const_iterator
i
=
nameToBoxMap
.
constBegin
();
i
!=
nameToBoxMap
.
constEnd
();
i
++
)
...
...
src/ui/configuration/BatteryMonitorConfig.cc
View file @
31a118ce
...
...
@@ -4,11 +4,11 @@
BatteryMonitorConfig
::
BatteryMonitorConfig
(
QWidget
*
parent
)
:
AP2ConfigWidget
(
parent
)
{
ui
.
setupUi
(
this
);
ui
.
monitorComboBox
->
addItem
(
"0: Disabled"
);
ui
.
monitorComboBox
->
addItem
(
"3: Battery Volts"
);
ui
.
monitorComboBox
->
addItem
(
"4: Voltage and Current"
);
ui
.
monitorComboBox
->
addItem
(
tr
(
"0: Disabled"
)
);
ui
.
monitorComboBox
->
addItem
(
tr
(
"3: Battery Volts"
)
);
ui
.
monitorComboBox
->
addItem
(
tr
(
"4: Voltage and Current"
)
);
ui
.
sensorComboBox
->
addItem
(
"0: Other"
);
ui
.
sensorComboBox
->
addItem
(
tr
(
"0: Other"
)
);
ui
.
sensorComboBox
->
addItem
(
"1: AttoPilot 45A"
);
ui
.
sensorComboBox
->
addItem
(
"2: AttoPilot 90A"
);
ui
.
sensorComboBox
->
addItem
(
"3: AttoPilot 180A"
);
...
...
@@ -34,19 +34,24 @@ BatteryMonitorConfig::BatteryMonitorConfig(QWidget *parent) : AP2ConfigWidget(pa
}
void
BatteryMonitorConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)),
this
,
SLOT
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)));
}
AP2ConfigWidget
::
activeUASSet
(
uas
);
if
(
!
uas
)
{
return
;
}
connect
(
uas
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)),
this
,
SLOT
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
double
,
int
)));
AP2ConfigWidget
::
activeUASSet
(
uas
);
}
void
BatteryMonitorConfig
::
calcDividerSet
()
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
bool
ok
=
false
;
...
...
@@ -63,7 +68,7 @@ void BatteryMonitorConfig::ampsPerVoltSet()
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
bool
ok
=
false
;
...
...
@@ -80,7 +85,7 @@ void BatteryMonitorConfig::batteryCapacitySet()
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
bool
ok
=
false
;
...
...
@@ -98,10 +103,10 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
if
(
index
==
0
)
if
(
index
==
0
)
//Battery Monitor Disabled
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"BATT_VOLT_PIN"
,
-
1
);
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"BATT_CURR_PIN"
,
-
1
);
...
...
@@ -114,7 +119,7 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
ui
.
calcVoltsLineEdit
->
setEnabled
(
false
);
ui
.
ampsPerVoltsLineEdit
->
setEnabled
(
false
);
}
else
if
(
index
==
1
)
else
if
(
index
==
1
)
//Monitor voltage only
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"BATT_MONITOR"
,
3
);
ui
.
sensorComboBox
->
setEnabled
(
false
);
...
...
@@ -124,7 +129,7 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
ui
.
calcVoltsLineEdit
->
setEnabled
(
false
);
ui
.
ampsPerVoltsLineEdit
->
setEnabled
(
false
);
}
else
if
(
index
==
2
)
else
if
(
index
==
2
)
//Monitor voltage and current
{
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"BATT_MONITOR"
,
4
);
ui
.
sensorComboBox
->
setEnabled
(
true
);
...
...
@@ -139,45 +144,39 @@ void BatteryMonitorConfig::monitorCurrentIndexChanged(int index)
}
void
BatteryMonitorConfig
::
sensorCurrentIndexChanged
(
int
index
)
{
float
maxvolt
=
0
;
float
maxamps
=
0
;
float
mvpervolt
=
0
;
float
mvperamp
=
0
;
float
topvolt
=
0
;
float
topamps
=
0
;
float
maxvolt
=
0
.0
;
float
maxamps
=
0
.0
;
float
mvpervolt
=
0
.0
;
float
mvperamp
=
0
.0
;
float
topvolt
=
0
.0
;
float
topamps
=
0
.0
;
if
(
index
==
1
)
{
//atto 45
//atto 45
see https://www.sparkfun.com/products/10643
maxvolt
=
13.6
;
maxamps
=
44.7
;
mvpervolt
=
242.3
;
mvperamp
=
73.20
;
}
else
if
(
index
==
2
)
{
//atto 90
maxvolt
=
5
0
;
//atto 90
see https://www.sparkfun.com/products/9028
maxvolt
=
5
1.8
;
maxamps
=
89.4
;
mvpervolt
=
63.69
;
mvperamp
=
36.60
;
}
else
if
(
index
==
3
)
{
//atto 180
maxvolt
=
5
0
;
//atto 180
see https://www.sparkfun.com/products/10644
maxvolt
=
5
1.8
;
maxamps
=
178.8
;
mvpervolt
=
63.69
;
mvperamp
=
18.30
;
}
else
if
(
index
==
4
)
{
//3dr
maxvolt
=
50
;
maxamps
=
90
;
mvpervolt
=
100
;
mvperamp
=
55.55
;
maxvolt
=
50.0
;
maxamps
=
90.0
;
}
mvpervolt
=
calculatemVPerVolt
(
3.3
,
maxvolt
);
mvperamp
=
calculatemVPerAmp
(
3.3
,
maxamps
);
if
(
index
==
0
)
{
//Other
...
...
@@ -197,12 +196,21 @@ void BatteryMonitorConfig::sensorCurrentIndexChanged(int index)
ui
.
measuredVoltsLineEdit
->
setEnabled
(
false
);
}
}
float
BatteryMonitorConfig
::
calculatemVPerAmp
(
float
maxvoltsout
,
float
maxamps
)
{
return
(
1000.0
*
(
maxvoltsout
/
maxamps
));
}
float
BatteryMonitorConfig
::
calculatemVPerVolt
(
float
maxvoltsout
,
float
maxvolts
)
{
return
(
1000.0
*
(
maxvoltsout
/
maxvolts
));
}
void
BatteryMonitorConfig
::
apmVerCurrentIndexChanged
(
int
index
)
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
if
(
index
==
0
)
//APM1
...
...
src/ui/configuration/BatteryMonitorConfig.h
View file @
31a118ce
...
...
@@ -24,6 +24,8 @@ private slots:
void
batteryChanged
(
UASInterface
*
uas
,
double
voltage
,
double
current
,
double
percent
,
int
seconds
);
private:
Ui
::
BatteryMonitorConfig
ui
;
inline
float
calculatemVPerAmp
(
float
maxvoltsout
,
float
maxamps
);
inline
float
calculatemVPerVolt
(
float
maxvoltsout
,
float
maxvolts
);
};
#endif // BATTERYMONITORCONFIG_H
src/ui/configuration/BatteryMonitorConfig.ui
View file @
31a118ce
...
...
@@ -150,7 +150,7 @@
<x>
160
</x>
<y>
70
</y>
<width>
281
</width>
<height>
80
</height>
<height>
91
</height>
</rect>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_3"
stretch=
"0,1"
>
...
...
src/ui/configuration/CameraGimbalConfig.cc
View file @
31a118ce
This diff is collapsed.
Click to expand it.
src/ui/configuration/CameraGimbalConfig.h
View file @
31a118ce
...
...
@@ -21,10 +21,10 @@ private slots:
private:
Ui
::
CameraGimbalConfig
ui
;
QString
shutterPrefix
;
QString
rollPrefix
;
QString
tiltPrefix
;
QString
panPrefix
;
QString
m_
shutterPrefix
;
QString
m_
rollPrefix
;
QString
m_
tiltPrefix
;
QString
m_
panPrefix
;
};
#endif // CAMERAGIMBALCONFIG_H
src/ui/configuration/CompassConfig.cc
View file @
31a118ce
#include "CompassConfig.h"
CompassConfig
::
CompassConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
CompassConfig
::
CompassConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
m_uas
=
0
;
ui
.
setupUi
(
this
);
...
...
@@ -13,9 +13,6 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
connect
(
ui
.
autoDecCheckBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
autoDecClicked
(
bool
)));
connect
(
ui
.
orientationComboBox
,
SIGNAL
(
currentIndexChanged
(
int
)),
this
,
SLOT
(
orientationComboChanged
(
int
)));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
activeUASSet
(
UASManager
::
instance
()
->
getActiveUAS
());
ui
.
orientationComboBox
->
addItem
(
"ROTATION_NONE"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_45"
);
ui
.
orientationComboBox
->
addItem
(
"ROTATION_YAW_90"
);
...
...
@@ -47,16 +44,6 @@ CompassConfig::CompassConfig(QWidget *parent) : QWidget(parent)
CompassConfig
::~
CompassConfig
()
{
}
void
CompassConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
return
;
if
(
!
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
m_uas
=
uas
;
connect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
void
CompassConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
parameterName
==
"MAG_ENABLE"
)
...
...
src/ui/configuration/CompassConfig.h
View file @
31a118ce
...
...
@@ -5,7 +5,8 @@
#include "ui_CompassConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class
CompassConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
class
CompassConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
...
...
@@ -13,7 +14,6 @@ public:
explicit
CompassConfig
(
QWidget
*
parent
=
0
);
~
CompassConfig
();
private
slots
:
void
activeUASSet
(
UASInterface
*
uas
);
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
enableClicked
(
bool
enabled
);
void
autoDecClicked
(
bool
enabled
);
...
...
src/ui/configuration/FailSafeConfig.cc
View file @
31a118ce
...
...
@@ -87,6 +87,7 @@ void FailSafeConfig::gcsChecked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -103,6 +104,7 @@ void FailSafeConfig::throttleActionChecked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -119,6 +121,7 @@ void FailSafeConfig::throttleChecked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -135,6 +138,7 @@ void FailSafeConfig::throttlePwmChanged()
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
m_uas
->
setParameter
(
1
,
"THR_FS_VALUE"
,
ui
.
throttlePwmSpinBox
->
value
());
...
...
@@ -144,6 +148,7 @@ void FailSafeConfig::throttleFailSafeChanged(int index)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
m_uas
->
setParameter
(
1
,
"FS_THR_ENABLE"
,
index
);
...
...
@@ -153,6 +158,7 @@ void FailSafeConfig::fsLongClicked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -169,6 +175,7 @@ void FailSafeConfig::fsShortClicked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -185,6 +192,7 @@ void FailSafeConfig::batteryFailChecked(bool checked)
{
if
(
!
m_uas
)
{
showNullMAVErrorMessageBox
();
return
;
}
if
(
checked
)
...
...
@@ -202,11 +210,21 @@ FailSafeConfig::~FailSafeConfig()
}
void
FailSafeConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanges
(
int
,
float
)));
disconnect
(
m_uas
,
SIGNAL
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)));
disconnect
(
m_uas
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
armingChanged
(
bool
)));
}
AP2ConfigWidget
::
activeUASSet
(
uas
);
connect
(
uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanges
(
int
,
float
)));
connect
(
uas
,
SIGNAL
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)));
connect
(
uas
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
armingChanged
(
bool
)));
if
(
uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
if
(
!
uas
)
{
return
;
}
connect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanges
(
int
,
float
)));
connect
(
m_uas
,
SIGNAL
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)),
this
,
SLOT
(
hilActuatorsChanged
(
uint64_t
,
float
,
float
,
float
,
float
,
float
,
float
,
float
,
float
)));
connect
(
m_uas
,
SIGNAL
(
armingChanged
(
bool
)),
this
,
SLOT
(
armingChanged
(
bool
)));
if
(
m_uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
{
ui
.
batteryFailCheckBox
->
setVisible
(
false
);
ui
.
throttleFailSafeComboBox
->
setVisible
(
false
);
...
...
@@ -221,7 +239,7 @@ void FailSafeConfig::activeUASSet(UASInterface *uas)
ui
.
fsLongCheckBox
->
setVisible
(
true
);
ui
.
fsShortCheckBox
->
setVisible
(
true
);
}
else
if
(
uas
->
getSystemType
()
==
MAV_TYPE_QUADROTOR
)
else
if
(
m_
uas
->
getSystemType
()
==
MAV_TYPE_QUADROTOR
)
{
ui
.
batteryFailCheckBox
->
setVisible
(
true
);
ui
.
throttleFailSafeComboBox
->
setVisible
(
true
);
...
...
src/ui/configuration/FlightModeConfig.cc
View file @
31a118ce
#include "FlightModeConfig.h"
FlightModeConfig
::
FlightModeConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
FlightModeConfig
::
FlightModeConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
ui
.
setupUi
(
this
);
connect
(
ui
.
savePushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
saveButtonClicked
()));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
}
FlightModeConfig
::~
FlightModeConfig
()
{
}
void
FlightModeConfig
::
setActiveUAS
(
UASInterface
*
uas
)
void
FlightModeConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
return
;
if
(
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
modeChanged
(
int
,
QString
,
QString
)));
disconnect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
}
m_uas
=
uas
;
AP2ConfigWidget
::
activeUASSet
(
uas
);
if
(
!
uas
)
return
;
connect
(
m_uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
modeChanged
(
int
,
QString
,
QString
)));
connect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
connect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
QStringList
itemlist
;
if
(
m_uas
->
getSystemType
()
==
MAV_TYPE_FIXED_WING
)
...
...
src/ui/configuration/FlightModeConfig.h
View file @
31a118ce
...
...
@@ -5,8 +5,9 @@
#include "ui_FlightModeConfig.h"
#include "UASInterface.h"
#include "UASManager.h"
#include "AP2ConfigWidget.h"
class
FlightModeConfig
:
public
Q
Widget
class
FlightModeConfig
:
public
AP2Config
Widget
{
Q_OBJECT
...
...
@@ -14,7 +15,7 @@ public:
explicit
FlightModeConfig
(
QWidget
*
parent
=
0
);
~
FlightModeConfig
();
private
slots
:
void
setActiveUAS
(
UASInterface
*
uas
);
void
activeUASSet
(
UASInterface
*
uas
);
void
saveButtonClicked
();
void
modeChanged
(
int
sysId
,
QString
status
,
QString
description
);
void
remoteControlChannelRawChanged
(
int
chan
,
float
val
);
...
...
src/ui/configuration/FrameTypeConfig.cc
View file @
31a118ce
...
...
@@ -32,9 +32,8 @@ This file is part of the QGROUNDCONTROL project
#include "FrameTypeConfig.h"
FrameTypeConfig
::
FrameTypeConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
FrameTypeConfig
::
FrameTypeConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
m_uas
=
0
;
ui
.
setupUi
(
this
);
//Disable until we get a FRAME parameter.
...
...
@@ -45,23 +44,11 @@ FrameTypeConfig::FrameTypeConfig(QWidget *parent) : QWidget(parent)
connect
(
ui
.
plusRadioButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
plusFrameSelected
()));
connect
(
ui
.
xRadioButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
xFrameSelected
()));
connect
(
ui
.
vRadioButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
vFrameSelected
()));
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
activeUASSet
(
UASManager
::
instance
()
->
getActiveUAS
());
}
FrameTypeConfig
::~
FrameTypeConfig
()
{
}
void
FrameTypeConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
!
uas
)
return
;
if
(
!
m_uas
)
{
disconnect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
m_uas
=
uas
;
connect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
void
FrameTypeConfig
::
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
)
{
if
(
parameterName
==
"FRAME"
)
...
...
src/ui/configuration/FrameTypeConfig.h
View file @
31a118ce
...
...
@@ -37,7 +37,8 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h"
#include "UASManager.h"
#include "QGCUASParamManager.h"
class
FrameTypeConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
class
FrameTypeConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
...
...
@@ -45,7 +46,6 @@ public:
explicit
FrameTypeConfig
(
QWidget
*
parent
=
0
);
~
FrameTypeConfig
();
private
slots
:
void
activeUASSet
(
UASInterface
*
uas
);
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
xFrameSelected
();
void
plusFrameSelected
();
...
...
src/ui/configuration/OsdConfig.cc
View file @
31a118ce
...
...
@@ -14,7 +14,7 @@ void OsdConfig::enableButtonClicked()
{
if
(
!
m_uas
)
{
QMessageBox
::
information
(
0
,
tr
(
"Error"
),
tr
(
"Please connect to a MAV before attempting to set configuration"
)
);
showNullMAVErrorMessageBox
(
);
return
;
}
m_uas
->
getParamManager
()
->
setParameter
(
1
,
"SR0_EXT_STAT"
,
2
);
...
...
src/ui/configuration/RadioCalibrationConfig.cc
View file @
31a118ce
...
...
@@ -32,15 +32,12 @@ This file is part of the QGROUNDCONTROL project
#include "RadioCalibrationConfig.h"
#include <QMessageBox>
RadioCalibrationConfig
::
RadioCalibrationConfig
(
QWidget
*
parent
)
:
Q
Widget
(
parent
)
RadioCalibrationConfig
::
RadioCalibrationConfig
(
QWidget
*
parent
)
:
AP2Config
Widget
(
parent
)
{
ui
.
setupUi
(
this
);
connect
(
ui
.
calibrateButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
calibrateButtonClicked
()));
m_uas
=
0
;
m_calibrationEnabled
=
false
;
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
setActiveUAS
(
UASInterface
*
)));
setActiveUAS
(
UASManager
::
instance
()
->
getActiveUAS
());
ui
.
rollWidget
->
setMin
(
800
);
ui
.
rollWidget
->
setMax
(
2200
);
ui
.
pitchWidget
->
setMin
(
800
);
...
...
@@ -79,20 +76,18 @@ RadioCalibrationConfig::RadioCalibrationConfig(QWidget *parent) : QWidget(parent
RadioCalibrationConfig
::~
RadioCalibrationConfig
()
{
}
void
RadioCalibrationConfig
::
setActiveUAS
(
UASInterface
*
uas
)
void
RadioCalibrationConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
if
(
uas
==
NULL
)
return
;
if
(
m_uas
)
{
// Disconnect old system
disconnect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
disconnect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
m_uas
=
uas
;
AP2ConfigWidget
::
activeUASSet
(
uas
);
if
(
!
uas
)
{
return
;
}
connect
(
m_uas
,
SIGNAL
(
remoteControlChannelRawChanged
(
int
,
float
)),
this
,
SLOT
(
remoteControlChannelRawChanged
(
int
,
float
)));
connect
(
m_uas
,
SIGNAL
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)),
this
,
SLOT
(
parameterChanged
(
int
,
int
,
QString
,
QVariant
)));
}
void
RadioCalibrationConfig
::
remoteControlChannelRawChanged
(
int
chan
,
float
val
)
{
...
...
src/ui/configuration/RadioCalibrationConfig.h
View file @
31a118ce
...
...
@@ -39,7 +39,8 @@ This file is part of the QGROUNDCONTROL project
#include "ui_RadioCalibrationConfig.h"
#include "UASManager.h"
#include "UASInterface.h"
class
RadioCalibrationConfig
:
public
QWidget
#include "AP2ConfigWidget.h"
class
RadioCalibrationConfig
:
public
AP2ConfigWidget
{
Q_OBJECT
...
...
@@ -50,7 +51,7 @@ protected:
void
showEvent
(
QShowEvent
*
event
);
void
hideEvent
(
QHideEvent
*
event
);
private
slots
:
void
setActiveUAS
(
UASInterface
*
uas
);
void
activeUASSet
(
UASInterface
*
uas
);
void
remoteControlChannelRawChanged
(
int
chan
,
float
val
);
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
void
guiUpdateTimerTick
();
...
...
src/ui/configuration/StandardParamConfig.cc
View file @
31a118ce
...
...
@@ -7,13 +7,6 @@ StandardParamConfig::StandardParamConfig(QWidget *parent) : AP2ConfigWidget(pare
StandardParamConfig
::~
StandardParamConfig
()
{
}
void
StandardParamConfig
::
activeUASSet
(
UASInterface
*
uas
)
{
AP2ConfigWidget
::
activeUASSet
(
uas
);
}
void
StandardParamConfig
::
addRange
(
QString
title
,
QString
description
,
QString
param
,
double
min
,
double
max
)
{
ParamWidget
*
widget
=
new
ParamWidget
(
ui
.
scrollAreaWidgetContents
);
...
...
src/ui/configuration/StandardParamConfig.h
View file @
31a118ce
...
...
@@ -18,7 +18,6 @@ private slots:
void
parameterChanged
(
int
uas
,
int
component
,
QString
parameterName
,
QVariant
value
);
private:
QMap
<
QString
,
ParamWidget
*>
paramToWidgetMap
;
void
activeUASSet
(
UASInterface
*
uas
);
Ui
::
StandardParamConfig
ui
;
};
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment