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
0bdc6c34
Commit
0bdc6c34
authored
Apr 24, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor MAVLink update
parent
05536245
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
9 additions
and
27 deletions
+9
-27
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+0
-1
UAS.cc
src/uas/UAS.cc
+8
-23
UAS.h
src/uas/UAS.h
+1
-3
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
0bdc6c34
...
...
@@ -155,7 +155,6 @@ void MAVLinkSimulationLink::mainloop()
attitude_t
attitude
;
raw_aux_t
rawAuxValues
;
raw_imu_t
rawImuValues
;
raw_sensor_t
rawSensorValues
;
uint8_t
buffer
[
MAVLINK_MAX_PACKET_LEN
];
int
bufferlength
;
...
...
src/uas/UAS.cc
View file @
0bdc6c34
...
...
@@ -172,11 +172,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
modeAudio
=
" is now in "
+
mode
;
}
currentVoltage
=
state
.
vbat
;
filterVoltage
(
currentVoltage
);
lpVoltage
=
filterVoltage
(
currentVoltage
);
if
(
startVoltage
==
0
)
startVoltage
=
currentVoltage
;
timeRemaining
=
calculateTimeRemaining
();
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit
batteryChanged
(
this
,
filterVoltage
()
,
getChargeLevel
(),
timeRemaining
);
emit
batteryChanged
(
this
,
lpVoltage
,
getChargeLevel
(),
timeRemaining
);
emit
voltageChanged
(
message
.
sysid
,
state
.
vbat
/
1000.0
f
);
// COMMUNICATIONS DROP RATE
...
...
@@ -241,11 +241,11 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"Mag. Z"
,
raw
.
zmag
,
time
);
}
break
;
case
MAVLINK_MSG_ID_RAW_
SENSOR
:
case
MAVLINK_MSG_ID_RAW_
AUX
:
{
raw_
sensor
_t
raw
;
message_raw_
sensor
_decode
(
&
message
,
&
raw
);
quint64
time
=
raw
.
msec
;
raw_
aux
_t
raw
;
message_raw_
aux
_decode
(
&
message
,
&
raw
);
quint64
time
=
MG
::
TIME
::
getGroundTimeNow
();
//
raw.msec;
if
(
time
==
0
)
{
time
=
MG
::
TIME
::
getGroundTimeNow
();
...
...
@@ -258,16 +258,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
time
+=
onboardTimeOffset
;
}
emit
valueChanged
(
uasId
,
"Accel. X"
,
raw
.
xacc
,
time
);
emit
valueChanged
(
uasId
,
"Accel. Y"
,
raw
.
yacc
,
time
);
emit
valueChanged
(
uasId
,
"Accel. Z"
,
raw
.
zacc
,
time
);
emit
valueChanged
(
uasId
,
"Gyro Phi"
,
raw
.
xgyro
,
time
);
emit
valueChanged
(
uasId
,
"Gyro Theta"
,
raw
.
ygyro
,
time
);
emit
valueChanged
(
uasId
,
"Gyro Psi"
,
raw
.
zgyro
,
time
);
emit
valueChanged
(
uasId
,
"Mag. X"
,
raw
.
xmag
,
time
);
emit
valueChanged
(
uasId
,
"Mag. Y"
,
raw
.
ymag
,
time
);
emit
valueChanged
(
uasId
,
"Mag. Z"
,
raw
.
zmag
,
time
);
emit
valueChanged
(
uasId
,
"Pressure"
,
raw
.
baro
,
time
);
emit
valueChanged
(
uasId
,
"Temperature"
,
raw
.
temp
,
time
);
}
...
...
@@ -435,16 +425,12 @@ void UAS::sendMessage(LinkInterface* link, mavlink_message_t message)
}
}
float
UAS
::
filterVoltage
()
{
return
lpVoltage
;
}
/**
* @param value battery voltage
*/
float
UAS
::
filterVoltage
(
float
value
)
const
float
UAS
::
filterVoltage
(
float
value
)
{
return
lpVoltage
*
0.8
f
+
value
*
0.2
f
;
/*
currentVoltage = value;
static QList<float> voltages<float>(20);
...
...
@@ -460,7 +446,6 @@ float UAS::filterVoltage(float value)
{
lpVoltage += v;
}*/
return
currentVoltage
;
}
void
UAS
::
getStatusForCode
(
int
statusCode
,
QString
&
uasState
,
QString
&
stateDescription
)
...
...
src/uas/UAS.h
View file @
0bdc6c34
...
...
@@ -72,10 +72,8 @@ public:
quint64
getUptime
();
/** @brief Get the status flag for the communication */
int
getCommunicationStatus
();
/** @brief Get low-passed voltage */
float
filterVoltage
();
/** @brief Add one measurement and get low-passed voltage */
float
filterVoltage
(
float
value
);
const
float
filterVoltage
(
float
value
);
/** @brief Get the links associated with this robot */
QList
<
LinkInterface
*>*
getLinks
();
...
...
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