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
43adc6e5
Commit
43adc6e5
authored
Dec 10, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'experimental' of
git://github.com/tecnosapiens/qgroundcontrol
into experimental
parents
9b61aeec
0f064266
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
168 additions
and
42 deletions
+168
-42
SlugsMAV.cc
src/uas/SlugsMAV.cc
+26
-9
SlugsMAV.h
src/uas/SlugsMAV.h
+3
-0
UAS.cc
src/uas/UAS.cc
+4
-0
SlugsDataSensorView.cc
src/ui/SlugsDataSensorView.cc
+89
-6
SlugsDataSensorView.h
src/ui/SlugsDataSensorView.h
+37
-13
SlugsDataSensorView.ui
src/ui/SlugsDataSensorView.ui
+9
-14
No files found.
src/uas/SlugsMAV.cc
View file @
43adc6e5
...
...
@@ -169,11 +169,16 @@ void SlugsMAV::emitSignals (void){
case
2
:
emit
slugsAirData
(
uasId
,
mlAirData
);
emit
slugsDiagnostic
(
uasId
,
mlDiagnosticData
);
break
;
case
3
:
emit
remoteControlChannelScaledChanged
(
0
,(
mlPilotConsoleData
.
de
-
1000.0
f
)
/
1000.0
f
);
emit
remoteControlChannelScaledChanged
(
1
,
0.75
);
emit
remoteControlChannelScaledChanged
(
1
,(
mlPilotConsoleData
.
dla
-
1000.0
f
)
/
1000.0
f
);
emit
remoteControlChannelScaledChanged
(
2
,(
mlPilotConsoleData
.
dr
-
1000.0
f
)
/
1000.0
f
);
emit
remoteControlChannelScaledChanged
(
3
,(
mlPilotConsoleData
.
dra
-
1000.0
f
)
/
1000.0
f
);
emit
remoteControlChannelScaledChanged
(
0
,(
mlPilotConsoleData
.
dt
-
1000.0
f
)
/
1000.0
f
);
emit
slugsPWM
(
uasId
,
mlPwmCommands
);
break
;
...
...
@@ -185,11 +190,13 @@ void SlugsMAV::emitSignals (void){
case
5
:
emit
slugsFilteredData
(
uasId
,
mlFilteredData
);
emit
slugsGPSDateTime
(
uasId
,
mlGpsDateTime
);
break
;
case
6
:
emit
slugsActionAck
(
uasId
,
mlActionAck
);
emit
emitGpsSignals
();
break
;
}
...
...
@@ -213,20 +220,30 @@ void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS
void
SlugsMAV
::
emitGpsSignals
(
void
){
if
(
mlGpsData
.
fix_type
>
0
){
qDebug
()
<<
"After Emit GPS Signal"
<<
mlGpsData
.
fix_type
;
//ToDo Uncomment if. it was comment only to test
// if (mlGpsData.fix_type > 0){
emit
globalPositionChanged
(
this
,
mlGpsData
.
lon
,
mlGpsData
.
lat
,
mlGpsData
.
alt
,
0.0
);
// Smaller than threshold and not NaN
if
(
mlGpsData
.
v
<
1000000
&&
mlGpsData
.
v
==
mlGpsData
.
v
){
emit
speedChanged
(
this
,
(
double
)
mlGpsData
.
v
,
0.0
,
0.0
,
0.0
);
}
else
{
emit
textMessageReceived
(
uasId
,
uasId
,
255
,
QString
(
"GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s"
).
arg
(
mlGpsData
.
v
));
}
}
emit
slugsGPSCogSog
(
uasId
,
mlGpsData
.
hdg
,
mlGpsData
.
v
);
// // Smaller than threshold and not NaN
// if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
// // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
// }
// else {
// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
// }
//}
}
void
SlugsMAV
::
emitPidSignal
()
...
...
src/uas/SlugsMAV.h
View file @
43adc6e5
...
...
@@ -47,6 +47,7 @@ public slots:
signals:
void
slugsRawImu
(
int
uasId
,
const
mavlink_raw_imu_t
&
rawData
);
void
slugsGPSCogSog
(
int
uasId
,
double
cog
,
double
sog
);
#ifdef MAVLINK_ENABLED_SLUGS
...
...
@@ -67,6 +68,8 @@ signals:
void
slugsBootMsg
(
int
uasId
,
mavlink_boot_t
&
boot
);
void
slugsAttitude
(
int
uasId
,
mavlink_attitude_t
&
attitude
);
#endif
protected:
...
...
src/uas/UAS.cc
View file @
43adc6e5
...
...
@@ -330,6 +330,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"Vz"
,
pos
.
vz
,
time
);
emit
localPositionChanged
(
this
,
pos
.
x
,
pos
.
y
,
pos
.
z
,
time
);
emit
speedChanged
(
this
,
pos
.
vx
,
pos
.
vy
,
pos
.
vz
,
time
);
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state
if
(
!
positionLock
)
...
...
src/ui/SlugsDataSensorView.cc
View file @
43adc6e5
...
...
@@ -41,10 +41,12 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect
(
slugsMav
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugSpeedLocalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugAttitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
slugsGlobalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
slugsMav
,
SIGNAL
(
slugsGPSCogSog
(
int
,
double
,
double
)),
this
,
SLOT
(
slugsGPSCogSog
(
int
,
double
,
double
)));
//connect slugs especial messages
//connect slugs especial messages
connect
(
slugsMav
,
SIGNAL
(
slugsSensorBias
(
int
,
const
mavlink_sensor_bias_t
&
)),
this
,
SLOT
(
slugsSensorBiasChanged
(
int
,
const
mavlink_sensor_bias_t
&
)));
connect
(
slugsMav
,
SIGNAL
(
slugsDiagnostic
(
int
,
const
mavlink_diagnostic_t
&
)),
this
,
SLOT
(
slugsDiagnosticMessageChanged
(
int
,
const
mavlink_diagnostic_t
&
)));
connect
(
slugsMav
,
SIGNAL
(
slugsCPULoad
(
int
,
const
mavlink_cpu_load_t
&
)),
this
,
SLOT
(
slugsCpuLoadChanged
(
int
,
const
mavlink_cpu_load_t
&
)));
...
...
@@ -53,6 +55,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect
(
slugsMav
,
SIGNAL
(
slugsPWM
(
int
,
const
mavlink_pwm_commands_t
&
)),
this
,
SLOT
(
slugsPWMChanged
(
int
,
const
mavlink_pwm_commands_t
&
)));
connect
(
slugsMav
,
SIGNAL
(
slugsFilteredData
(
int
,
const
mavlink_filtered_data_t
&
)),
this
,
SLOT
(
slugsFilteredDataChanged
(
int
,
const
mavlink_filtered_data_t
&
)));
connect
(
slugsMav
,
SIGNAL
(
slugsGPSDateTime
(
int
,
const
mavlink_gps_date_time_t
&
)),
this
,
SLOT
(
slugsGPSDateTimeChanged
(
int
,
const
mavlink_gps_date_time_t
&
)));
connect
(
slugsMav
,
SIGNAL
(
slugsAirData
(
int
,
const
mavlink_air_data_t
&
)),
this
,
SLOT
(
slugsAirDataChanged
(
int
,
const
mavlink_air_data_t
&
)));
#endif // MAVLINK_ENABLED_SLUGS
// Set this UAS as active if it is the first one
...
...
@@ -69,6 +73,15 @@ void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t
ui
->
m_Axr
->
setText
(
QString
::
number
(
rawData
.
xacc
));
ui
->
m_Ayr
->
setText
(
QString
::
number
(
rawData
.
yacc
));
ui
->
m_Azr
->
setText
(
QString
::
number
(
rawData
.
zacc
));
ui
->
m_Mxr
->
setText
(
QString
::
number
(
rawData
.
xmag
));
ui
->
m_Myr
->
setText
(
QString
::
number
(
rawData
.
ymag
));
ui
->
m_Mzr
->
setText
(
QString
::
number
(
rawData
.
zmag
));
ui
->
m_Gxr
->
setText
(
QString
::
number
(
rawData
.
xgyro
));
ui
->
m_Gyr
->
setText
(
QString
::
number
(
rawData
.
ygyro
));
ui
->
m_Gzr
->
setText
(
QString
::
number
(
rawData
.
zgyro
));
}
void
SlugsDataSensorView
::
setActiveUAS
(
UASInterface
*
uas
){
...
...
@@ -85,9 +98,13 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
Q_UNUSED
(
uas
);
Q_UNUSED
(
time
);
ui
->
m_GpsLatitude
->
setText
(
QString
::
number
(
lat
));
ui
->
m_GpsLongitude
->
setText
(
QString
::
number
(
lon
));
ui
->
m_GpsHeight
->
setText
(
QString
::
number
(
alt
));
qDebug
()
<<
"GPS Position = "
<<
lat
<<
" - "
<<
lon
<<
" - "
<<
alt
;
}
...
...
@@ -103,6 +120,8 @@ void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
ui
->
ed_y
->
setPlainText
(
QString
::
number
(
y
));
ui
->
ed_z
->
setPlainText
(
QString
::
number
(
z
));
//qDebug()<<"Local Position = "<<x<<" - "<<y<<" - "<<z;
}
void
SlugsDataSensorView
::
slugSpeedLocalPositionChanged
(
UASInterface
*
uas
,
...
...
@@ -117,6 +136,9 @@ void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
ui
->
ed_vy
->
setPlainText
(
QString
::
number
(
vy
));
ui
->
ed_vz
->
setPlainText
(
QString
::
number
(
vz
));
//qDebug()<<"Speed Local Position = "<<vx<<" - "<<vy<<" - "<<vz;
}
void
SlugsDataSensorView
::
slugAttitudeChanged
(
UASInterface
*
uas
,
...
...
@@ -132,6 +154,8 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
ui
->
m_Pitch
->
setPlainText
(
QString
::
number
(
slugpitch
));
ui
->
m_Yaw
->
setPlainText
(
QString
::
number
(
slugyaw
));
qDebug
()
<<
"Attitude change = "
<<
slugroll
<<
" - "
<<
slugpitch
<<
" - "
<<
slugyaw
;
}
...
...
@@ -148,6 +172,7 @@ void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
}
void
SlugsDataSensorView
::
slugsDiagnosticMessageChanged
(
int
systemId
,
const
mavlink_diagnostic_t
&
diagnostic
){
Q_UNUSED
(
systemId
);
...
...
@@ -229,17 +254,75 @@ void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
void
SlugsDataSensorView
::
slugsGPSDateTimeChanged
(
int
systemId
,
const
mavlink_gps_date_time_t
&
gpsDateTime
){
Q_UNUSED
(
systemId
);
ui
->
m_GpsDate
->
setText
(
QString
::
number
(
gpsDateTime
.
month
)
+
"/"
+
QString
::
number
(
gpsDateTime
.
day
)
+
"/"
+
QString
month
,
day
;
month
=
QString
::
number
(
gpsDateTime
.
month
);
day
=
QString
::
number
(
gpsDateTime
.
day
);
if
(
gpsDateTime
.
month
<
10
)
month
=
"0"
+
QString
::
number
(
gpsDateTime
.
month
);
if
(
gpsDateTime
.
day
<
10
)
day
=
"0"
+
QString
::
number
(
gpsDateTime
.
day
);
ui
->
m_GpsDate
->
setText
(
day
+
"/"
+
month
+
"/"
+
QString
::
number
(
gpsDateTime
.
year
));
ui
->
m_GpsTime
->
setText
(
QString
::
number
(
gpsDateTime
.
hour
)
+
":"
+
QString
::
number
(
gpsDateTime
.
min
)
+
":"
+
QString
::
number
(
gpsDateTime
.
sec
));
QString
hour
,
min
,
sec
;
hour
=
QString
::
number
(
gpsDateTime
.
hour
);
min
=
QString
::
number
(
gpsDateTime
.
min
);
sec
=
QString
::
number
(
gpsDateTime
.
sec
);
if
(
gpsDateTime
.
hour
<
10
)
hour
=
"0"
+
QString
::
number
(
gpsDateTime
.
hour
);
if
(
gpsDateTime
.
min
<
10
)
min
=
"0"
+
QString
::
number
(
gpsDateTime
.
min
);
if
(
gpsDateTime
.
sec
<
10
)
sec
=
"0"
+
QString
::
number
(
gpsDateTime
.
sec
);
ui
->
m_GpsTime
->
setText
(
hour
+
":"
+
min
+
":"
+
sec
);
ui
->
m_GpsSat
->
setText
(
QString
::
number
(
gpsDateTime
.
visSat
));
}
/**
* @brief Updates the air data widget - 171
*/
void
SlugsDataSensorView
::
slugsAirDataChanged
(
int
systemId
,
const
mavlink_air_data_t
&
airData
)
{
Q_UNUSED
(
systemId
);
ui
->
ed_dynamic
->
setText
(
QString
::
number
(
airData
.
dynamicPressure
));
ui
->
ed_static
->
setText
(
QString
::
number
(
airData
.
staticPressure
));
ui
->
ed_temp
->
setText
(
QString
::
number
(
airData
.
temperature
));
// qDebug()<<"Air Data = "<<airData.dynamicPressure<<" - "
// <<airData.staticPressure<<" - "
// <<airData.temperature;
}
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void
SlugsDataSensorView
::
slugsGPSCogSog
(
int
systemId
,
double
cog
,
double
sog
)
{
Q_UNUSED
(
systemId
);
ui
->
m_GpsCog
->
setText
(
QString
::
number
(
cog
));
ui
->
m_GpsSog
->
setText
(
QString
::
number
(
sog
));
}
#endif // MAVLINK_ENABLED_SLUGS
src/ui/SlugsDataSensorView.h
View file @
43adc6e5
...
...
@@ -70,6 +70,9 @@ public slots:
void
setActiveUAS
(
UASInterface
*
uas
);
/**
* @brief Updates the Raw Data widget
*/
void
slugRawDataChanged
(
int
uasId
,
const
mavlink_raw_imu_t
&
rawData
);
#ifdef MAVLINK_ENABLED_SLUGS
...
...
@@ -114,58 +117,79 @@ public slots:
double
lon
,
double
alt
,
quint64
time
);
/**
* @brief Updates the sensor bias widget
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void
slugsGPSCogSog
(
int
systemId
,
double
cog
,
double
sog
);
/**
* @brief Updates the CPU load widget - 170
*/
void
slugsCpuLoadChanged
(
int
systemId
,
const
mavlink_cpu_load_t
&
cpuLoad
);
/**
* @brief Updates the air data widget - 171
*/
void
slugsAirDataChanged
(
int
systemId
,
const
mavlink_air_data_t
&
airData
);
/**
* @brief Updates the sensor bias widget - 172
*/
void
slugsSensorBiasChanged
(
int
systemId
,
const
mavlink_sensor_bias_t
&
sensorBias
);
/**
* @brief Updates the diagnostic widget
* @brief Updates the diagnostic widget
- 173
*/
void
slugsDiagnosticMessageChanged
(
int
systemId
,
const
mavlink_diagnostic_t
&
diagnostic
);
/**
* @brief Updates the CPU load widget
*/
void
slugsCpuLoadChanged
(
int
systemId
,
const
mavlink_cpu_load_t
&
cpuLoad
);
/**
* @brief Updates the Navigation widget
* @brief Updates the Navigation widget
- 176
*/
void
slugsNavegationChanged
(
int
systemId
,
const
mavlink_slugs_navigation_t
&
slugsNavigation
);
/**
* @brief Updates the Data Log widget
* @brief Updates the Data Log widget
- 177
*/
void
slugsDataLogChanged
(
int
systemId
,
const
mavlink_data_log_t
&
dataLog
);
/**
* @brief Updates the PWM Commands widget
* @brief Updates the PWM Commands widget
- 175
*/
void
slugsPWMChanged
(
int
systemId
,
const
mavlink_pwm_commands_t
&
pwmCommands
);
/**
* @brief Updates the filtered sensor measurements widget
* @brief Updates the filtered sensor measurements widget
- 178
*/
void
slugsFilteredDataChanged
(
int
systemId
,
const
mavlink_filtered_data_t
&
filteredData
);
/**
* @brief Updates the gps Date Time widget
* @brief Updates the gps Date Time widget
- 179
*/
void
slugsGPSDateTimeChanged
(
int
systemId
,
const
mavlink_gps_date_time_t
&
gpsDateTime
);
#endif // MAVLINK_ENABLED_SLUGS
protected:
...
...
src/ui/SlugsDataSensorView.ui
View file @
43adc6e5
...
...
@@ -7,7 +7,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
399
</width>
<height>
6
67
</height>
<height>
6
04
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
...
...
@@ -24,18 +24,18 @@
</property>
<property
name=
"maximumSize"
>
<size>
<width>
16777215
</width>
<height>
16777215
</height>
<width>
399
</width>
<height>
604
</height>
</size>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"Q
VBoxLayout"
name=
"verticalLayout_17
"
>
<item>
<layout
class=
"Q
GridLayout"
name=
"gridLayout_23
"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QTabWidget"
name=
"SlugsSensorView_tabWidget"
>
<property
name=
"currentIndex"
>
<number>
0
</number>
<number>
1
</number>
</property>
<widget
class=
"QWidget"
name=
"tab"
>
<attribute
name=
"title"
>
...
...
@@ -989,7 +989,7 @@
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
13
</height>
<height>
5
</height>
</size>
</property>
</spacer>
...
...
@@ -1791,8 +1791,8 @@
<attribute
name=
"title"
>
<string>
Tab 2
</string>
</attribute>
<layout
class=
"Q
VBoxLayout"
name=
"verticalLayout_11
"
>
<item>
<layout
class=
"Q
GridLayout"
name=
"gridLayout_22
"
>
<item
row=
"0"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_8"
>
<item>
<widget
class=
"QGroupBox"
name=
"gpsData_groupBox"
>
...
...
@@ -4483,11 +4483,6 @@
</item>
</layout>
</widget>
<widget
class=
"QWidget"
name=
"tab_2"
>
<attribute
name=
"title"
>
<string>
Tab 4
</string>
</attribute>
</widget>
</widget>
</item>
</layout>
...
...
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