Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
A
Ardupilot
Manage
Activity
Members
Labels
Plan
Issues
0
Issue boards
Milestones
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
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
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
OpenSource
Ardupilot
Commits
c16e3a03
Commit
c16e3a03
authored
11 years ago
by
Andrew Tridgell
Browse files
Options
Downloads
Patches
Plain Diff
Plane: fixed disarmed throttle in HIL
parent
776b999f
No related branches found
Branches containing commit
No related tags found
Tags containing commit
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduPlane/Attitude.pde
+10
-10
10 additions, 10 deletions
ArduPlane/Attitude.pde
with
10 additions
and
10 deletions
ArduPlane/Attitude.pde
+
10
−
10
View file @
c16e3a03
...
@@ -855,16 +855,6 @@ static void set_servos(void)
...
@@ -855,16 +855,6 @@ static void set_servos(void)
channel_rudder
->
radio_out
=
channel_rudder
->
radio_in
;
channel_rudder
->
radio_out
=
channel_rudder
->
radio_in
;
}
}
#if HIL_MODE != HIL_MODE_DISABLED
// get the servos to the GCS immediately for HIL
if
(
comm_get_txspace
(
MAVLINK_COMM_0
)
-
MAVLINK_NUM_NON_PAYLOAD_BYTES
>=
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN
)
{
send_radio_out
(
MAVLINK_COMM_0
);
}
if
(
!
g
.
hil_servos
)
{
return
;
}
#endif
if
(
g
.
vtail_output
!=
MIXING_DISABLED
)
{
if
(
g
.
vtail_output
!=
MIXING_DISABLED
)
{
channel_output_mixer
(
g
.
vtail_output
,
channel_pitch
->
radio_out
,
channel_rudder
->
radio_out
);
channel_output_mixer
(
g
.
vtail_output
,
channel_pitch
->
radio_out
,
channel_rudder
->
radio_out
);
}
else
if
(
g
.
elevon_output
!=
MIXING_DISABLED
)
{
}
else
if
(
g
.
elevon_output
!=
MIXING_DISABLED
)
{
...
@@ -889,6 +879,16 @@ static void set_servos(void)
...
@@ -889,6 +879,16 @@ static void set_servos(void)
}
}
}
}
#if HIL_MODE != HIL_MODE_DISABLED
// get the servos to the GCS immediately for HIL
if
(
comm_get_txspace
(
MAVLINK_COMM_0
)
-
MAVLINK_NUM_NON_PAYLOAD_BYTES
>=
MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN
)
{
send_servo_out
(
MAVLINK_COMM_0
);
}
if
(
!
g
.
hil_servos
)
{
return
;
}
#endif
// send values to the PWM timers for output
// send values to the PWM timers for output
// ----------------------------------------
// ----------------------------------------
channel_roll
->
output
();
channel_roll
->
output
();
...
...
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