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
41ea9079
Commit
41ea9079
authored
13 years ago
by
Pat Hickey
Browse files
Options
Downloads
Patches
Plain Diff
Arducopter Motors Octa: revert OCTA_V_FRAME back to part of OCTA_FRAME
parent
7d264d11
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/motors_octa.pde
+4
-5
4 additions, 5 deletions
ArduCopter/motors_octa.pde
with
4 additions
and
5 deletions
ArduCopter/motors_octa.pde
+
4
−
5
View file @
41ea9079
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#if
(
FRAME_CONFIG == OCTA_FRAME
) || (FRAME_CONFIG == OCTA_V_FRAME)
#if FRAME_CONFIG == OCTA_FRAME
static
void
init_motors_out
()
{
...
...
@@ -39,7 +39,6 @@ static void output_motors_armed()
g
.
rc_3
.
calc_pwm
();
g
.
rc_4
.
calc_pwm
();
#if FRAME_TYPE == OCTA_FRAME
if
(
g
.
frame_orientation
==
X_FRAME
){
roll_out
=
(
float
)
g
.
rc_1
.
pwm_out
*
0.4
;
pitch_out
=
(
float
)
g
.
rc_2
.
pwm_out
*
0.4
;
...
...
@@ -79,8 +78,8 @@ static void output_motors_armed()
motor_out
[
MOT_7
]
=
g
.
rc_3
.
radio_out
-
roll_out
-
pitch_out
;
// CCW BACK RIGHT
motor_out
[
MOT_6
]
=
g
.
rc_3
.
radio_out
-
g
.
rc_2
.
pwm_out
;
// CW BACK
motor_out
[
MOT_5
]
=
g
.
rc_3
.
radio_out
+
roll_out
-
pitch_out
;
// CCW BACK LEFT
}
#elif FRAME_TYPE == OCTA_
V_FRAME
}
else
if
(
g
.
frame_orientation
==
V_FRAME
){
int
roll_out2
,
pitch_out2
;
int
roll_out3
,
pitch_out3
;
...
...
@@ -111,8 +110,8 @@ static void output_motors_armed()
motor_out
[
MOT_8
]
=
g
.
rc_3
.
radio_out
-
g
.
rc_2
.
pwm_out
+
roll_out4
;
// CW BACK LEFT
motor_out
[
MOT_1
]
=
g
.
rc_3
.
radio_out
-
g
.
rc_2
.
pwm_out
-
roll_out4
;
// CCW BACK RIGHT
#endif // FRAME_TYPE
}
// Yaw
motor_out
[
MOT_1
]
+=
g
.
rc_4
.
pwm_out
;
// CCW
motor_out
[
MOT_3
]
+=
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