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
f38fc465
Commit
f38fc465
authored
Jun 24, 2010
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
write read eeprom added, actions updated
parent
0566491b
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
45 additions
and
20 deletions
+45
-20
UAS.cc
src/uas/UAS.cc
+22
-12
UAS.h
src/uas/UAS.h
+3
-1
UASInterface.h
src/uas/UASInterface.h
+3
-1
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+15
-6
QGCParamWidget.h
src/ui/QGCParamWidget.h
+2
-0
No files found.
src/uas/UAS.cc
View file @
f38fc465
...
...
@@ -661,10 +661,20 @@ void UAS::requestParameters()
sendMessage
(
msg
);
}
void
UAS
::
writeParameters
()
void
UAS
::
writeParameters
ToStorage
()
{
//mavlink_message_t msg;
qDebug
()
<<
__FILE__
<<
__LINE__
<<
__func__
<<
"IS NOT IMPLEMENTED!"
;
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
uint8_t
)
MAV_ACTION_STORAGE_WRITE
);
sendMessage
(
msg
);
}
void
UAS
::
readParametersFromStorage
()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,(
uint8_t
)
MAV_ACTION_STORAGE_READ
);
sendMessage
(
msg
);
}
void
UAS
::
enableAllDataTransmission
(
bool
enabled
)
...
...
@@ -929,7 +939,7 @@ void UAS::launch()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),(
uint8_t
)
MAV_ACTION_LAUNCH
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
uint8_t
)
MAV_ACTION_LAUNCH
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -943,7 +953,7 @@ void UAS::enable_motors()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),(
uint8_t
)
MAV_ACTION_MOTORS_START
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
uint8_t
)
MAV_ACTION_MOTORS_START
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -957,7 +967,7 @@ void UAS::disable_motors()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),(
uint8_t
)
MAV_ACTION_MOTORS_STOP
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
uint8_t
)
MAV_ACTION_MOTORS_STOP
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1069,7 +1079,7 @@ void UAS::halt()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_HALT
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_HALT
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1079,7 +1089,7 @@ void UAS::go()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_CONTINUE
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_CONTINUE
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1090,7 +1100,7 @@ void UAS::home()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_RETURN
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_RETURN
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1104,7 +1114,7 @@ void UAS::emergencySTOP()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_EMCY_LAND
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_EMCY_LAND
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1135,7 +1145,7 @@ bool UAS::emergencyKILL()
{
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_EMCY_KILL
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_EMCY_KILL
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
@@ -1164,7 +1174,7 @@ void UAS::shutdown()
// If the active UAS is set, execute command
mavlink_message_t
msg
;
// TODO Replace MG System ID with static function call and allow to change ID in GUI
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
(
int
)
MAV_ACTION_SHUTDOWN
);
mavlink_msg_action_pack
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
this
->
getUASID
(),
MAV_COMP_ID_IMU
,
(
int
)
MAV_ACTION_SHUTDOWN
);
// Send message twice to increase chance of reception
sendMessage
(
msg
);
sendMessage
(
msg
);
...
...
src/uas/UAS.h
View file @
f38fc465
...
...
@@ -200,7 +200,9 @@ public slots:
void
setParameter
(
int
component
,
QString
id
,
float
value
);
/** @brief Write parameters to permanent storage */
void
writeParameters
();
void
writeParametersToStorage
();
/** @brief Read parameters from permanent storage */
void
readParametersFromStorage
();
void
enableAllDataTransmission
(
bool
enabled
);
void
enableRawSensorDataTransmission
(
bool
enabled
);
...
...
src/uas/UASInterface.h
View file @
f38fc465
...
...
@@ -173,7 +173,9 @@ public slots:
/** @brief Request all onboard parameters of all components */
virtual
void
requestParameters
()
=
0
;
/** @brief Write parameter to permanent storage */
virtual
void
writeParameters
()
=
0
;
virtual
void
writeParametersToStorage
()
=
0
;
/** @brief Read parameter from permanent storage */
virtual
void
readParametersFromStorage
()
=
0
;
/** @brief Set a system parameter
* @param component ID of the system component to write the parameter to
* @param id String identifying the parameter
...
...
src/ui/QGCParamWidget.cc
View file @
f38fc465
...
...
@@ -64,18 +64,22 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) :
horizontalLayout
->
setSizeConstraint
(
QLayout
::
SetMinimumSize
);
horizontalLayout
->
addWidget
(
tree
,
0
,
0
,
1
,
3
);
QPushButton
*
re
adButton
=
new
QPushButton
(
tr
(
"Read
"
));
connect
(
re
ad
Button
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
requestParameterList
()));
horizontalLayout
->
addWidget
(
re
ad
Button
,
1
,
0
);
QPushButton
*
re
freshButton
=
new
QPushButton
(
tr
(
"Refresh
"
));
connect
(
re
fresh
Button
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
requestParameterList
()));
horizontalLayout
->
addWidget
(
re
fresh
Button
,
1
,
0
);
QPushButton
*
setButton
=
new
QPushButton
(
tr
(
"
Set (RAM)
"
));
QPushButton
*
setButton
=
new
QPushButton
(
tr
(
"
Transmit
"
));
connect
(
setButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
setParameters
()));
horizontalLayout
->
addWidget
(
setButton
,
1
,
1
);
QPushButton
*
writeButton
=
new
QPushButton
(
tr
(
"Write (
Disk
)"
));
QPushButton
*
writeButton
=
new
QPushButton
(
tr
(
"Write (
ROM
)"
));
connect
(
writeButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
writeParameters
()));
horizontalLayout
->
addWidget
(
writeButton
,
1
,
2
);
QPushButton
*
readButton
=
new
QPushButton
(
tr
(
"Read (ROM)"
));
connect
(
readButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
readParameters
()));
horizontalLayout
->
addWidget
(
readButton
,
2
,
2
);
QPushButton
*
loadFileButton
=
new
QPushButton
(
tr
(
"Load File"
));
connect
(
loadFileButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
loadParameters
()));
horizontalLayout
->
addWidget
(
loadFileButton
,
2
,
0
);
...
...
@@ -432,7 +436,12 @@ void QGCParamWidget::setParameters()
*/
void
QGCParamWidget
::
writeParameters
()
{
mav
->
writeParameters
();
mav
->
writeParametersToStorage
();
}
void
QGCParamWidget
::
readParameters
()
{
mav
->
readParametersFromStorage
();
}
/**
...
...
src/ui/QGCParamWidget.h
View file @
f38fc465
...
...
@@ -65,6 +65,8 @@ public slots:
void
setParameters
();
/** @brief Write the current parameters to permanent storage (EEPROM/HDD) */
void
writeParameters
();
/** @brief Read the parameters from permanent storage to RAM */
void
readParameters
();
/** @brief Clear the parameter list */
void
clear
();
/** @brief Update when user changes parameters */
...
...
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