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
5cee2b67
Commit
5cee2b67
authored
13 years ago
by
Pat Hickey
Browse files
Options
Downloads
Patches
Plain Diff
Arducopter Motors Hexa: Revert HEXA_PLUS_ and HEXA_X_ to single HEXA_FRAME
parent
8463acc9
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/motors_hexa.pde
+3
-3
3 additions, 3 deletions
ArduCopter/motors_hexa.pde
with
3 additions
and
3 deletions
ArduCopter/motors_hexa.pde
+
3
−
3
View file @
5cee2b67
...
...
@@ -37,7 +37,7 @@ static void output_motors_armed()
g
.
rc_3
.
calc_pwm
();
g
.
rc_4
.
calc_pwm
();
#if FRAME_CONFIG == HEXA_
X_FRAME
if
(
g
.
frame_orientation
==
X_FRAME
){
roll_out
=
g
.
rc_1
.
pwm_out
/
2
;
pitch_out
=
(
float
)
g
.
rc_2
.
pwm_out
*
.866
;
...
...
@@ -50,7 +50,7 @@ static void output_motors_armed()
motor_out
[
MOT_1
]
=
g
.
rc_3
.
radio_out
-
roll_out
+
pitch_out
;
// FRONT CCW
motor_out
[
MOT_6
]
=
g
.
rc_3
.
radio_out
-
g
.
rc_1
.
pwm_out
;
// MIDDLE CW
motor_out
[
MOT_5
]
=
g
.
rc_3
.
radio_out
-
roll_out
-
pitch_out
;
// BACK CCW
#elif FRAME_CONFIG == HEXA_PLUS_FRAME
}
else
{
roll_out
=
(
float
)
g
.
rc_1
.
pwm_out
*
.866
;
pitch_out
=
g
.
rc_2
.
pwm_out
/
2
;
...
...
@@ -63,7 +63,7 @@ static void output_motors_armed()
motor_out
[
MOT_4
]
=
g
.
rc_3
.
radio_out
+
roll_out
-
pitch_out
;
// BACK LEFT CW
motor_out
[
MOT_5
]
=
g
.
rc_3
.
radio_out
-
g
.
rc_2
.
pwm_out
;
// BACK CCW
motor_out
[
MOT_6
]
=
g
.
rc_3
.
radio_out
-
roll_out
-
pitch_out
;
// BACK RIGHT CW
#endif
}
// Yaw
motor_out
[
MOT_1
]
+=
g
.
rc_4
.
pwm_out
;
// CCW
...
...
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