Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
A
ardupilot
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Terms and privacy
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
SASC
ardupilot
Commits
e906310b
Commit
e906310b
authored
8 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Plane: rudder_arming moved to AP_Arming_Plane
parent
7cc8b723
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
ArduPlane/AP_Arming.h
+8
-0
8 additions, 0 deletions
ArduPlane/AP_Arming.h
ArduPlane/radio.cpp
+3
-3
3 additions, 3 deletions
ArduPlane/radio.cpp
with
11 additions
and
3 deletions
ArduPlane/AP_Arming.h
+
8
−
0
View file @
e906310b
...
...
@@ -8,6 +8,12 @@
class
AP_Arming_Plane
:
public
AP_Arming
{
public:
enum
ArmingRudder
{
ARMING_RUDDER_DISABLED
=
0
,
ARMING_RUDDER_ARMONLY
=
1
,
ARMING_RUDDER_ARMDISARM
=
2
};
AP_Arming_Plane
(
const
AP_AHRS
&
ahrs_ref
,
const
AP_Baro
&
baro
,
Compass
&
compass
,
const
AP_BattMonitor
&
battery
)
:
AP_Arming
(
ahrs_ref
,
baro
,
compass
,
battery
)
{
...
...
@@ -16,6 +22,8 @@ public:
bool
pre_arm_checks
(
bool
report
);
bool
arm
(
uint8_t
method
)
override
;
ArmingRudder
rudder_arming
()
const
{
return
(
ArmingRudder
)
rudder_arming_value
.
get
();
}
// var_info for holding Parameter information
static
const
struct
AP_Param
::
GroupInfo
var_info
[];
...
...
This diff is collapsed.
Click to expand it.
ArduPlane/radio.cpp
+
3
−
3
View file @
e906310b
...
...
@@ -103,9 +103,9 @@ void Plane::init_rc_out_aux()
*/
void
Plane
::
rudder_arm_disarm_check
()
{
AP_Arming
::
ArmingRudder
arming_rudder
=
arming
.
rudder_arming
();
AP_Arming
_Plane
::
ArmingRudder
arming_rudder
=
arming
.
rudder_arming
();
if
(
arming_rudder
==
AP_Arming
::
ARMING_RUDDER_DISABLED
)
{
if
(
arming_rudder
==
AP_Arming
_Plane
::
ARMING_RUDDER_DISABLED
)
{
//parameter disallows rudder arming/disabling
return
;
}
...
...
@@ -144,7 +144,7 @@ void Plane::rudder_arm_disarm_check()
// not at full right rudder
rudder_arm_timer
=
0
;
}
}
else
if
(
arming_rudder
==
AP_Arming
::
ARMING_RUDDER_ARMDISARM
&&
!
is_flying
())
{
}
else
if
(
arming_rudder
==
AP_Arming
_Plane
::
ARMING_RUDDER_ARMDISARM
&&
!
is_flying
())
{
// when armed and not flying, full left rudder starts disarming counter
if
(
channel_rudder
->
get_control_in
()
<
-
4000
)
{
uint32_t
now
=
millis
();
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment