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
0042aebd
Commit
0042aebd
authored
May 13, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed bug in parameter interface, finished channel selection on IMU
parent
e0b418c2
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
80 additions
and
21 deletions
+80
-21
UAS.cc
src/uas/UAS.cc
+75
-19
UAS.h
src/uas/UAS.h
+1
-1
ParameterInterface.cc
src/ui/ParameterInterface.cc
+4
-1
No files found.
src/uas/UAS.cc
View file @
0042aebd
...
...
@@ -49,6 +49,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) :
commStatus
(
COMM_DISCONNECTED
),
name
(
""
),
links
(
new
QList
<
LinkInterface
*>
()),
unknownPackets
(),
thrustSum
(
0
),
thrustMax
(
10
),
startVoltage
(
0
),
...
...
@@ -67,7 +68,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) :
manualThrust
(
0
),
receiveDropRate
(
0
),
sendDropRate
(
0
),
unknownPackets
(),
lowBattAlarm
(
false
)
{
setBattery
(
LIPOLY
,
3
);
...
...
@@ -386,7 +386,7 @@ quint64 UAS::getUnixTime(quint64 time)
// THIS CALCULATION IS EXPANDED BY THE PREPROCESSOR/COMPILER ONE-TIME,
// NO NEED TO MULTIPLY MANUALLY!
else
if
(
time
<
40
*
365
*
24
*
60
*
60
*
1000
*
1000
)
else
if
(
time
<
(
quint64
)(
40
*
365
*
24
*
60
*
60
*
1000
*
1000
)
)
{
if
(
onboardTimeOffset
==
0
)
{
...
...
@@ -536,10 +536,10 @@ void UAS::enableAllDataTransmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_stream_t
stream
;
mavlink_request_
data_
stream_t
stream
;
// Select the message to request from now on
// 0 is a magic ID and will enable/disable the standard message set except for heartbeat
stream
.
req_
message
_id
=
0
;
stream
.
req_
stream
_id
=
0
;
// Select the update rate in Hz the message should be send
// All messages will be send with their default rate
stream
.
req_message_rate
=
0
;
...
...
@@ -550,7 +550,7 @@ void UAS::enableAllDataTransmission(bool enabled)
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
mavlink_msg_request_
data_
stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
...
...
@@ -558,9 +558,9 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_stream_t
stream
;
mavlink_request_
data_
stream_t
stream
;
// Select the message to request from now on
stream
.
req_
message_id
=
MAVLINK_MSG_ID_RAW_IMU
;
stream
.
req_
stream_id
=
1
;
// Select the update rate in Hz the message should be send
stream
.
req_message_rate
=
200
;
// Start / stop the message
...
...
@@ -570,32 +570,88 @@ void UAS::enableRawSensorDataTransmission(bool enabled)
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
mavlink_msg_request_
data_
stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
void
UAS
::
enableExtendedSystemStatusTransmission
(
bool
enabled
)
{
// FIXME
qDebug
()
<<
__FILE__
<<
__LINE__
<<
__func__
<<
"IS NOT IMPLEMENTED!"
;
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_data_stream_t
stream
;
// Select the message to request from now on
stream
.
req_stream_id
=
2
;
// Select the update rate in Hz the message should be send
stream
.
req_message_rate
=
10
;
// Start / stop the message
stream
.
start_stop
=
(
enabled
)
?
1
:
0
;
// The system which should take this command
stream
.
target_system
=
uasId
;
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_data_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
void
UAS
::
enableRCChannelDataTransmission
(
bool
enabled
)
{
// FIXME
qDebug
()
<<
__FILE__
<<
__LINE__
<<
__func__
<<
"IS NOT IMPLEMENTED!"
;
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_data_stream_t
stream
;
// Select the message to request from now on
stream
.
req_stream_id
=
3
;
// Select the update rate in Hz the message should be send
stream
.
req_message_rate
=
200
;
// Start / stop the message
stream
.
start_stop
=
(
enabled
)
?
1
:
0
;
// The system which should take this command
stream
.
target_system
=
uasId
;
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_data_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
void
UAS
::
enableRawControllerDataTransmission
(
bool
enabled
)
{
// FIXME
qDebug
()
<<
__FILE__
<<
__LINE__
<<
__func__
<<
"IS NOT IMPLEMENTED!"
;
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_data_stream_t
stream
;
// Select the message to request from now on
stream
.
req_stream_id
=
4
;
// Select the update rate in Hz the message should be send
stream
.
req_message_rate
=
200
;
// Start / stop the message
stream
.
start_stop
=
(
enabled
)
?
1
:
0
;
// The system which should take this command
stream
.
target_system
=
uasId
;
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_data_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
void
UAS
::
enableRawSensorFusionTransmission
(
bool
enabled
)
{
// FIXME
qDebug
()
<<
__FILE__
<<
__LINE__
<<
__func__
<<
"IS NOT IMPLEMENTED!"
;
// Buffers to write data to
mavlink_message_t
msg
;
mavlink_request_data_stream_t
stream
;
// Select the message to request from now on
stream
.
req_stream_id
=
5
;
// Select the update rate in Hz the message should be send
stream
.
req_message_rate
=
200
;
// Start / stop the message
stream
.
start_stop
=
(
enabled
)
?
1
:
0
;
// The system which should take this command
stream
.
target_system
=
uasId
;
// The component / subsystem which should take this command
stream
.
target_component
=
0
;
// Encode and send the message
mavlink_msg_request_data_stream_encode
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
&
stream
);
sendMessage
(
msg
);
}
void
UAS
::
setParameter
(
int
component
,
QString
id
,
float
value
)
...
...
@@ -608,15 +664,15 @@ void UAS::setParameter(int component, QString id, float value)
// Copy string into buffer, ensuring not to exceed the buffer size
char
*
s
=
(
char
*
)
id
.
toStdString
().
c_str
();
for
(
int
i
=
0
;
i
<
sizeof
(
p
.
param_id
);
i
++
)
for
(
unsigned
int
i
=
0
;
i
<
sizeof
(
p
.
param_id
);
i
++
)
{
// String characters
if
(
i
<
id
.
length
()
&&
i
<
(
sizeof
(
p
.
param_id
)
-
1
))
if
(
(
int
)
i
<
id
.
length
()
&&
i
<
(
sizeof
(
p
.
param_id
)
-
1
))
{
p
.
param_id
[
i
]
=
s
[
i
];
}
// Null termination at end of string or end of buffer
else
if
(
i
==
id
.
length
()
||
i
==
(
sizeof
(
p
.
param_id
)
-
1
))
else
if
(
(
int
)
i
==
id
.
length
()
||
i
==
(
sizeof
(
p
.
param_id
)
-
1
))
{
p
.
param_id
[
i
]
=
'\0'
;
}
...
...
src/uas/UAS.h
View file @
0042aebd
...
...
@@ -86,6 +86,7 @@ protected:
CommStatus
commStatus
;
///< Communication status
QString
name
;
///< Human-friendly name of the vehicle, e.g. bravo
QList
<
LinkInterface
*>*
links
;
///< List of links this UAS can be reached by
QList
<
int
>
unknownPackets
;
///< Packet IDs which are unknown and have been received
MAVLinkProtocol
*
mavlink
;
///< Reference to the MAVLink instance
BatteryType
batteryType
;
///< The battery type
int
cells
;
///< Number of cells
...
...
@@ -95,7 +96,6 @@ protected:
QList
<
double
>
motorValues
;
QList
<
QString
>
motorNames
;
QList
<
int
>
unknownPackets
;
///< Packet IDs which are unknown and have been received
double
thrustSum
;
///< Sum of forward/up thrust of all thrust actuators, in Newtons
double
thrustMax
;
///< Maximum forward/up thrust of this vehicle, in Newtons
...
...
src/ui/ParameterInterface.cc
View file @
0042aebd
...
...
@@ -15,6 +15,9 @@ ParameterInterface::ParameterInterface(QWidget *parent) :
m_ui
(
new
Ui
::
parameterWidget
)
{
m_ui
->
setupUi
(
this
);
// Make sure the combo box is empty
// because else indices get messed up
m_ui
->
vehicleComboBox
->
clear
();
// Setup UI connections
connect
(
m_ui
->
vehicleComboBox
,
SIGNAL
(
activated
(
int
)),
this
,
SLOT
(
selectUAS
(
int
)));
...
...
@@ -54,7 +57,7 @@ void ParameterInterface::addUAS(UASInterface* uas)
// Set widgets as default
if
(
curr
==
-
1
)
{
m_ui
->
sensorSettings
->
setCurrentWidget
(
param
);
m_ui
->
sensorSettings
->
setCurrentWidget
(
sensor
);
m_ui
->
stackedWidget
->
setCurrentWidget
(
param
);
curr
=
uas
->
getUASID
();
}
...
...
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