Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
B
Baitboat
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
Baitboat
Commits
2cd6d986
Commit
2cd6d986
authored
10 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
TradHeli: call passthrough_bf_roll_pitch_rate_yaw
parent
691a3d81
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
ArduCopter/heli_control_acro.pde
+4
-3
4 additions, 3 deletions
ArduCopter/heli_control_acro.pde
with
4 additions
and
3 deletions
ArduCopter/heli_control_acro.pde
+
4
−
3
View file @
2cd6d986
...
@@ -39,14 +39,15 @@ static void heli_acro_run()
...
@@ -39,14 +39,15 @@ static void heli_acro_run()
if
(
!
motors
.
has_flybar
()){
if
(
!
motors
.
has_flybar
()){
// convert the input to the desired body frame rate
// convert the input to the desired body frame rate
get_pilot_desired_angle_rates
(
g
.
rc_1
.
control_in
,
g
.
rc_2
.
control_in
,
g
.
rc_4
.
control_in
,
target_roll
,
target_pitch
,
target_yaw
);
get_pilot_desired_angle_rates
(
g
.
rc_1
.
control_in
,
g
.
rc_2
.
control_in
,
g
.
rc_4
.
control_in
,
target_roll
,
target_pitch
,
target_yaw
);
// run attitude controller
attitude_control
.
rate_bf_roll_pitch_yaw
(
target_roll
,
target_pitch
,
target_yaw
);
}
else
{
}
else
{
// flybar helis only need yaw rate control
// flybar helis only need yaw rate control
get_pilot_desired_yaw_rate
(
g
.
rc_4
.
control_in
,
target_yaw
);
get_pilot_desired_yaw_rate
(
g
.
rc_4
.
control_in
,
target_yaw
);
// run attitude controller
attitude_control
.
passthrough_bf_roll_pitch_rate_yaw
(
g
.
rc_1
.
control_in
,
g
.
rc_2
.
control_in
,
target_yaw
);
}
}
// run attitude controller
attitude_control
.
rate_bf_roll_pitch_yaw
(
target_roll
,
target_pitch
,
target_yaw
);
// output pilot's throttle without angle boost
// output pilot's throttle without angle boost
attitude_control
.
set_throttle_out
(
g
.
rc_3
.
control_in
,
false
);
attitude_control
.
set_throttle_out
(
g
.
rc_3
.
control_in
,
false
);
}
}
...
...
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