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
51e21f9f
Commit
51e21f9f
authored
Sep 11, 2013
by
Jean Cyr
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Implement message driven receiver pairing
parent
341c7719
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
20 additions
and
7 deletions
+20
-7
UAS.cc
src/uas/UAS.cc
+11
-0
UAS.h
src/uas/UAS.h
+3
-0
UASInterface.h
src/uas/UASInterface.h
+2
-0
QGCPX4VehicleConfig.cc
src/ui/QGCPX4VehicleConfig.cc
+4
-7
No files found.
src/uas/UAS.cc
View file @
51e21f9f
...
...
@@ -2866,6 +2866,17 @@ void UAS::land()
sendMessage
(
msg
);
}
/**
* Order the robot to land on the runway
*/
void
UAS
::
pairRX
(
int
rxType
,
int
rxSubType
)
{
mavlink_message_t
msg
;
mavlink_msg_command_long_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
uasId
,
MAV_COMP_ID_ALL
,
MAV_CMD_START_RX_PAIR
,
0
,
rxType
,
rxSubType
,
0
,
0
,
0
,
0
,
0
);
sendMessage
(
msg
);
}
/**
* The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
* and might differ between systems.
...
...
src/uas/UAS.h
View file @
51e21f9f
...
...
@@ -723,6 +723,9 @@ public slots:
void
home
();
/** @brief Order the robot to land **/
void
land
();
/** @brief Order the robot to pair its receiver **/
void
pairRX
(
int
rxType
,
int
rxSubType
);
void
halt
();
void
go
();
...
...
src/uas/UASInterface.h
View file @
51e21f9f
...
...
@@ -290,6 +290,8 @@ public slots:
virtual
void
home
()
=
0
;
/** @brief Order the robot to land **/
virtual
void
land
()
=
0
;
/** @brief Order the robot to pair its receiver **/
virtual
void
pairRX
(
int
rxType
,
int
rxSubType
)
=
0
;
/** @brief Halt the system */
virtual
void
halt
()
=
0
;
/** @brief Start/continue the current robot action */
...
...
src/ui/QGCPX4VehicleConfig.cc
View file @
51e21f9f
...
...
@@ -343,15 +343,12 @@ void QGCPX4VehicleConfig::toggleSpektrumPairing(bool enabled)
warnMsgBox
.
setStandardButtons
(
QMessageBox
::
Ok
);
warnMsgBox
.
setDefaultButton
(
QMessageBox
::
Ok
);
(
void
)
warnMsgBox
.
exec
();
return
;
}
int
mode
=
1
;
// DSM2
if
(
ui
->
dsmxRadioButton
->
isChecked
())
mode
=
2
;
// DSMX
mav
->
getParamManager
()
->
setPendingParam
(
0
,
"RC_DSM_BIND"
,
mode
,
true
);
// Do not save this parameter, just set in RAM
mav
->
getParamManager
()
->
sendPendingParameters
(
false
,
true
);
UASInterface
*
mav
=
UASManager
::
instance
()
->
getActiveUAS
();
if
(
mav
)
mav
->
pairRX
(
0
,
ui
->
dsmxRadioButton
->
isChecked
()
?
1
:
0
);
}
void
QGCPX4VehicleConfig
::
setTrimPositions
()
...
...
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