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
4bfa7069
Commit
4bfa7069
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Copter: Y6 new motor factor fix
parent
e02827b2
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
libraries/AP_Motors/AP_MotorsY6.cpp
+6
-6
6 additions, 6 deletions
libraries/AP_Motors/AP_MotorsY6.cpp
with
6 additions
and
6 deletions
libraries/AP_Motors/AP_MotorsY6.cpp
+
6
−
6
View file @
4bfa7069
...
...
@@ -30,12 +30,12 @@ void AP_MotorsY6::setup_motors()
if
(
_flags
.
frame_orientation
>=
AP_MOTORS_NEW_PLUS_FRAME
)
{
// Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.
666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
1
);
add_motor_raw
(
AP_MOTORS_MOT_2
,
-
1.0
,
0.
666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
add_motor_raw
(
AP_MOTORS_MOT_3
,
0.0
,
-
1.
333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
3
);
add_motor_raw
(
AP_MOTORS_MOT_4
,
0.0
,
-
1.
333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
4
);
add_motor_raw
(
AP_MOTORS_MOT_5
,
1.0
,
0.
666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
5
);
add_motor_raw
(
AP_MOTORS_MOT_6
,
1.0
,
0.
666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
6
);
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.
500
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
1
);
add_motor_raw
(
AP_MOTORS_MOT_2
,
-
1.0
,
0.
500
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
add_motor_raw
(
AP_MOTORS_MOT_3
,
0.0
,
-
1.
000
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
3
);
add_motor_raw
(
AP_MOTORS_MOT_4
,
0.0
,
-
1.
000
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
4
);
add_motor_raw
(
AP_MOTORS_MOT_5
,
1.0
,
0.
500
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
5
);
add_motor_raw
(
AP_MOTORS_MOT_6
,
1.0
,
0.
500
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
6
);
}
else
{
// original Y6 motor definition
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
...
...
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