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
a4f710a3
Commit
a4f710a3
authored
11 years ago
by
Robert Lefebvre
Committed by
Randy Mackay
10 years ago
Browse files
Options
Downloads
Patches
Plain Diff
TradHeli: Add yaw-only rate request function for flybar acro mode.
parent
3316fe8f
No related branches found
No related tags found
No related merge requests found
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
ArduCopter/heli_control_acro.pde
+18
-5
18 additions, 5 deletions
ArduCopter/heli_control_acro.pde
with
18 additions
and
5 deletions
ArduCopter/heli_control_acro.pde
+
18
−
5
View file @
a4f710a3
...
...
@@ -34,13 +34,15 @@ static void heli_acro_run()
if
(
motors
.
armed
()
&&
heli_flags
.
init_targets_on_arming
)
{
heli_flags
.
init_targets_on_arming
=
false
;
attitude_control
.
relax_bf_rate_controller
();
}
// To-Do: add support for flybarred helis
// 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
);
if
(
!
motors
.
has_flybar
()){
// 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
);
}
else
{
// flybar helis only need yaw rate control
get_pilot_desired_yaw_rate
(
g
.
rc_4
.
control_in
,
target_yaw
);
}
// run attitude controller
attitude_control
.
rate_bf_roll_pitch_yaw
(
target_roll
,
target_pitch
,
target_yaw
);
...
...
@@ -49,4 +51,15 @@ static void heli_acro_run()
attitude_control
.
set_throttle_out
(
g
.
rc_3
.
control_in
,
false
);
}
// get_pilot_desired_yaw_rate - transform pilot's yaw input into a desired yaw angle rate
// returns desired yaw rate in centi-degrees-per-second
static
void
get_pilot_desired_yaw_rate
(
int16_t
yaw_in
,
float
&
yaw_out
)
{
// calculate rate request
float
rate_bf_yaw_request
=
yaw_in
*
g
.
acro_yaw_p
;
// hand back rate request
yaw_out
=
rate_bf_yaw_request
;
}
#endif //HELI_FRAME
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