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
a7ae20ed
Commit
a7ae20ed
authored
Feb 11, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed battery voltage setting, fixed mean in linechart
parent
354438be
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
79 additions
and
48 deletions
+79
-48
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+1
-1
UAS.cc
src/uas/UAS.cc
+56
-28
UAS.h
src/uas/UAS.h
+4
-1
LinechartPlot.cc
src/ui/linechart/LinechartPlot.cc
+16
-16
LinechartWidget.cc
src/ui/linechart/LinechartWidget.cc
+1
-1
UASView.cc
src/ui/uas/UASView.cc
+1
-1
No files found.
src/comm/MAVLinkSimulationMAV.cc
View file @
a7ae20ed
...
...
@@ -163,7 +163,7 @@ void MAVLinkSimulationMAV::mainloop()
status
.
packet_drop
=
0
;
status
.
vbat
=
10500
;
status
.
status
=
sys_state
;
status
.
battery_remaining
=
9
00
;
status
.
battery_remaining
=
9
12
;
mavlink_msg_sys_status_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
msg
,
&
status
);
link
->
sendMAVLinkMessage
(
&
msg
);
timer10Hz
=
5
;
...
...
src/uas/UAS.cc
View file @
a7ae20ed
...
...
@@ -41,8 +41,10 @@ thrustSum(0),
thrustMax
(
10
),
startVoltage
(
0
),
warnVoltage
(
9.5
f
),
warnLevelPercent
(
20.0
f
),
currentVoltage
(
12.0
f
),
lpVoltage
(
12.0
f
),
batteryRemainingEstimateEnabled
(
true
),
mode
(
MAV_MODE_UNINIT
),
status
(
MAV_STATE_UNINIT
),
onboardTimeOffset
(
0
),
...
...
@@ -305,6 +307,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
lpVoltage
=
filterVoltage
(
currentVoltage
);
if
(
startVoltage
==
0
)
startVoltage
=
currentVoltage
;
timeRemaining
=
calculateTimeRemaining
();
if
(
!
batteryRemainingEstimateEnabled
)
{
chargeLevel
=
state
.
battery_remaining
/
10.0
f
;
}
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit
batteryChanged
(
this
,
lpVoltage
,
getChargeLevel
(),
timeRemaining
);
emit
voltageChanged
(
message
.
sysid
,
state
.
vbat
/
1000.0
f
);
...
...
@@ -1906,29 +1912,49 @@ void UAS::setBattery(BatteryType type, int cells)
void
UAS
::
setBatterySpecs
(
const
QString
&
specs
)
{
QString
stringList
=
specs
;
stringList
=
stringList
.
remove
(
"V"
);
stringList
=
stringList
.
remove
(
"v"
);
QStringList
parts
=
stringList
.
split
(
","
);
if
(
parts
.
length
()
==
3
)
if
(
specs
.
length
()
==
0
||
specs
.
contains
(
"%"
))
{
float
temp
;
batteryRemainingEstimateEnabled
=
false
;
bool
ok
;
// Get the empty voltage
temp
=
parts
.
at
(
0
).
toFloat
(
&
ok
);
if
(
ok
)
emptyVoltage
=
temp
;
// Get the warning voltage
temp
=
parts
.
at
(
1
).
toFloat
(
&
ok
);
if
(
ok
)
warnVoltage
=
temp
;
// Get the full voltage
temp
=
parts
.
at
(
2
).
toFloat
(
&
ok
);
if
(
ok
)
fullVoltage
=
temp
;
QString
percent
=
specs
;
percent
=
percent
.
remove
(
"%"
);
float
temp
=
percent
.
toFloat
(
&
ok
);
if
(
ok
)
warnLevelPercent
=
temp
;
}
else
{
batteryRemainingEstimateEnabled
=
true
;
QString
stringList
=
specs
;
stringList
=
stringList
.
remove
(
"V"
);
stringList
=
stringList
.
remove
(
"v"
);
QStringList
parts
=
stringList
.
split
(
","
);
if
(
parts
.
length
()
==
3
)
{
float
temp
;
bool
ok
;
// Get the empty voltage
temp
=
parts
.
at
(
0
).
toFloat
(
&
ok
);
if
(
ok
)
emptyVoltage
=
temp
;
// Get the warning voltage
temp
=
parts
.
at
(
1
).
toFloat
(
&
ok
);
if
(
ok
)
warnVoltage
=
temp
;
// Get the full voltage
temp
=
parts
.
at
(
2
).
toFloat
(
&
ok
);
if
(
ok
)
fullVoltage
=
temp
;
}
}
}
QString
UAS
::
getBatterySpecs
()
{
return
QString
(
"%1V,%2V,%3V"
).
arg
(
emptyVoltage
).
arg
(
warnVoltage
).
arg
(
fullVoltage
);
if
(
batteryRemainingEstimateEnabled
)
{
return
QString
(
"%1V,%2V,%3V"
).
arg
(
emptyVoltage
).
arg
(
warnVoltage
).
arg
(
fullVoltage
);
}
else
{
return
QString
(
"%1%"
).
arg
(
warnLevelPercent
);
}
}
int
UAS
::
calculateTimeRemaining
()
...
...
@@ -1947,20 +1973,22 @@ int UAS::calculateTimeRemaining()
/**
* @return charge level in percent - 0 - 100
*/
double
UAS
::
getChargeLevel
()
float
UAS
::
getChargeLevel
()
{
float
chargeLevel
;
if
(
lpVoltage
<
emptyVoltage
)
if
(
batteryRemainingEstimateEnabled
)
{
chargeLevel
=
0.0
f
;
}
else
if
(
lpVoltage
>
fullVoltage
)
{
chargeLevel
=
100.0
f
;
}
else
{
chargeLevel
=
100.0
f
*
((
lpVoltage
-
emptyVoltage
)
/
(
fullVoltage
-
emptyVoltage
));
if
(
lpVoltage
<
emptyVoltage
)
{
chargeLevel
=
0.0
f
;
}
else
if
(
lpVoltage
>
fullVoltage
)
{
chargeLevel
=
100.0
f
;
}
else
{
chargeLevel
=
100.0
f
*
((
lpVoltage
-
emptyVoltage
)
/
(
fullVoltage
-
emptyVoltage
));
}
}
return
chargeLevel
;
}
...
...
src/uas/UAS.h
View file @
a7ae20ed
...
...
@@ -124,8 +124,11 @@ protected: //COMMENTS FOR TEST UNIT
float
emptyVoltage
;
///< Voltage of the empty battery (0%)
float
startVoltage
;
///< Voltage at system start
float
warnVoltage
;
///< Voltage where QGC will start to warn about low battery
float
warnLevelPercent
;
///< Warning level, in percent
double
currentVoltage
;
///< Voltage currently measured
float
lpVoltage
;
///< Low-pass filtered voltage
bool
batteryRemainingEstimateEnabled
;
///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float
chargeLevel
;
///< Charge level of battery, in percent
int
timeRemaining
;
///< Remaining time calculated based on previous and current
unsigned
int
mode
;
///< The current mode of the MAV
int
status
;
///< The current status of the MAV
...
...
@@ -167,7 +170,7 @@ public:
/** @brief Estimate how much flight time is remaining */
int
calculateTimeRemaining
();
/** @brief Get the current charge level */
double
getChargeLevel
();
float
getChargeLevel
();
/** @brief Get the human-readable status message for this code */
void
getStatusForCode
(
int
statusCode
,
QString
&
uasState
,
QString
&
stateDescription
);
/** @brief Check if vehicle is in autonomous mode */
...
...
src/ui/linechart/LinechartPlot.cc
View file @
a7ae20ed
...
...
@@ -789,13 +789,13 @@ void TimeSeriesData::append(quint64 ms, double value)
this
->
value
[
count
]
=
value
;
this
->
lastValue
=
value
;
this
->
mean
=
0
;
QList
<
double
>
medianList
=
QList
<
double
>
();
//
QList<double> medianList = QList<double>();
for
(
unsigned
int
i
=
0
;
(
i
<
averageWindow
)
&&
(((
int
)
count
-
(
int
)
i
)
>=
0
);
++
i
)
{
this
->
mean
+=
this
->
value
[
count
-
i
];
medianList
.
append
(
this
->
value
[
count
-
i
]);
//
medianList.append(this->value[count-i]);
}
mean
=
mean
/
static_cast
<
double
>
(
qMin
(
averageWindow
,
static_cast
<
unsigned
int
>
(
count
)));
this
->
mean
=
mean
/
static_cast
<
double
>
(
qMin
(
averageWindow
,
static_cast
<
unsigned
int
>
(
count
)));
this
->
variance
=
0
;
for
(
unsigned
int
i
=
0
;
(
i
<
averageWindow
)
&&
(((
int
)
count
-
(
int
)
i
)
>=
0
);
++
i
)
...
...
@@ -804,19 +804,19 @@ void TimeSeriesData::append(quint64 ms, double value)
}
this
->
variance
=
this
->
variance
/
static_cast
<
double
>
(
qMin
(
averageWindow
,
static_cast
<
unsigned
int
>
(
count
)));
qSort
(
medianList
);
if
(
medianList
.
count
()
>
2
)
{
if
(
medianList
.
count
()
%
2
==
0
)
{
median
=
(
medianList
.
at
(
medianList
.
count
()
/
2
)
+
medianList
.
at
(
medianList
.
count
()
/
2
+
1
))
/
2.0
;
}
else
{
median
=
medianList
.
at
(
medianList
.
count
()
/
2
+
1
);
}
}
//
qSort(medianList);
//
if (medianList.count() > 2)
//
{
//
if (medianList.count() % 2 == 0)
//
{
//
median = (medianList.at(medianList.count()/2) + medianList.at(medianList.count()/2+1)) / 2.0;
//
}
//
else
//
{
//
median = medianList.at(medianList.count()/2+1);
//
}
//
}
// Update statistical values
if
(
ms
<
startTime
)
startTime
=
ms
;
...
...
src/ui/linechart/LinechartWidget.cc
View file @
a7ae20ed
...
...
@@ -416,7 +416,7 @@ void LinechartWidget::refresh()
QMap
<
QString
,
QLabel
*>::
iterator
j
;
for
(
j
=
curveMeans
->
begin
();
j
!=
curveMeans
->
end
();
++
j
)
{
double
val
=
activePlot
->
get
CurrentValue
(
j
.
key
());
double
val
=
activePlot
->
get
Mean
(
j
.
key
());
int
intval
=
static_cast
<
int
>
(
val
);
if
(
intval
>=
100000
||
intval
<=
-
100000
)
{
...
...
src/ui/uas/UASView.cc
View file @
a7ae20ed
...
...
@@ -435,7 +435,7 @@ void UASView::setBatterySpecs()
{
bool
ok
;
QString
newName
=
QInputDialog
::
getText
(
this
,
tr
(
"Set Battery Specifications for %1"
).
arg
(
uas
->
getUASName
()),
tr
(
"Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V)"
),
QLineEdit
::
Normal
,
tr
(
"Specs: (empty,warn,full), e.g. (9V,9.5V,12.6V)
or just warn level in percent (e.g. 15%) to use estimate from MAV
"
),
QLineEdit
::
Normal
,
uas
->
getBatterySpecs
(),
&
ok
);
if
(
ok
&&
!
newName
.
isEmpty
())
uas
->
setBatterySpecs
(
newName
);
...
...
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