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
8da2820d
Commit
8da2820d
authored
Jan 05, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed ground time button YEEHAY!
parent
40716011
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
18 additions
and
6 deletions
+18
-6
UAS.cc
src/uas/UAS.cc
+5
-2
UAS.h
src/uas/UAS.h
+1
-1
UASInterface.h
src/uas/UASInterface.h
+7
-1
HUD.cc
src/ui/HUD.cc
+1
-1
LinechartPlot.cc
src/ui/linechart/LinechartPlot.cc
+4
-1
No files found.
src/uas/UAS.cc
View file @
8da2820d
...
...
@@ -1259,8 +1259,10 @@ void UAS::enableExtra3Transmission(int rate)
* @param id Name of the parameter
* @param value Parameter value
*/
void
UAS
::
setParameter
(
int
component
,
QString
id
,
float
value
)
{
void
UAS
::
setParameter
(
const
int
component
,
const
QString
&
id
,
const
float
value
)
{
if
(
!
id
.
isNull
())
{
mavlink_message_t
msg
;
mavlink_param_set_t
p
;
p
.
param_value
=
value
;
...
...
@@ -1288,6 +1290,7 @@ void UAS::setParameter(int component, QString id, float value)
}
mavlink_msg_param_set_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
p
);
sendMessage
(
msg
);
}
}
/**
...
...
src/uas/UAS.h
View file @
8da2820d
...
...
@@ -239,7 +239,7 @@ public slots:
void
requestParameters
();
/** @brief Set a system parameter */
void
setParameter
(
int
component
,
QString
id
,
float
value
);
void
setParameter
(
const
int
component
,
const
QString
&
id
,
const
float
value
);
/** @brief Write parameters to permanent storage */
void
writeParametersToStorage
();
...
...
src/uas/UASInterface.h
View file @
8da2820d
...
...
@@ -214,7 +214,7 @@ public slots:
* @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it
* @param value Value of the parameter, IEEE 754 single precision floating point
*/
virtual
void
setParameter
(
int
component
,
QString
id
,
float
value
)
=
0
;
virtual
void
setParameter
(
const
int
component
,
const
QString
&
id
,
const
float
value
)
=
0
;
/**
* @brief Add a link to the list of current links
...
...
@@ -327,8 +327,14 @@ signals:
* @param value the value that changed
* @param msec the timestamp of the message, in milliseconds
*/
// FIXME Exchange the lines below against the commented ones
void
valueChanged
(
int
uasId
,
QString
name
,
double
value
,
quint64
msec
);
void
valueChanged
(
UASInterface
*
uas
,
QString
name
,
double
value
,
quint64
msec
);
// void valueChanged(const int uasId, const QString& name, const double value, const quint64 msec);
// //void valueChanged(UASInterface* uas, QString name, double value, quint64 msec);
void
voltageChanged
(
int
uasId
,
double
voltage
);
void
waypointUpdated
(
int
uasId
,
int
id
,
double
x
,
double
y
,
double
z
,
double
yaw
,
bool
autocontinue
,
bool
active
);
void
waypointSelected
(
int
uasId
,
int
id
);
...
...
src/ui/HUD.cc
View file @
8da2820d
...
...
@@ -285,7 +285,7 @@ void HUD::updateAttitudeThrustSetPoint(UASInterface*, double rollDesired, double
void
HUD
::
updateAttitude
(
UASInterface
*
uas
,
double
roll
,
double
pitch
,
double
yaw
,
quint64
timestamp
)
{
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"ROLL
"
<<
yaw
;
//qDebug() << __FILE__ << __LINE__ << "YAW
" << yaw;
updateValue
(
uas
,
"roll"
,
roll
,
timestamp
);
updateValue
(
uas
,
"pitch"
,
pitch
,
timestamp
);
updateValue
(
uas
,
"yaw"
,
yaw
,
timestamp
);
...
...
src/ui/linechart/LinechartPlot.cc
View file @
8da2820d
...
...
@@ -254,7 +254,8 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
if
(
ms
<
minTime
)
minTime
=
ms
;
if
(
ms
>
maxTime
)
maxTime
=
ms
;
storageInterval
=
maxTime
-
minTime
;
lastTime
=
time
;
if
(
time
>
lastTime
)
lastTime
=
time
;
//
if
(
value
<
minValue
)
minValue
=
value
;
...
...
@@ -276,6 +277,8 @@ void LinechartPlot::appendData(QString dataname, quint64 ms, double value)
void
LinechartPlot
::
enforceGroundTime
(
bool
enforce
)
{
m_groundTime
=
enforce
;
lastTime
=
QGC
::
groundTimeUsecs
()
/
1000
;
}
/**
...
...
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