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
6fd51342
Commit
6fd51342
authored
11 years ago
by
Randy Mackay
Browse files
Options
Downloads
Patches
Plain Diff
Copter: add Y6 with all top props CW
Set FRAME parameter to 10
parent
9a87f15b
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
libraries/AP_Motors/AP_MotorsY6.cpp
+17
-7
17 additions, 7 deletions
libraries/AP_Motors/AP_MotorsY6.cpp
libraries/AP_Motors/AP_Motors_Class.h
+5
-1
5 additions, 1 deletion
libraries/AP_Motors/AP_Motors_Class.h
with
22 additions
and
8 deletions
libraries/AP_Motors/AP_MotorsY6.cpp
+
17
−
7
View file @
6fd51342
...
@@ -28,11 +28,21 @@ void AP_MotorsY6::setup_motors()
...
@@ -28,11 +28,21 @@ void AP_MotorsY6::setup_motors()
// call parent
// call parent
AP_MotorsMatrix
::
setup_motors
();
AP_MotorsMatrix
::
setup_motors
();
// MultiWii set-up
if
(
_flags
.
frame_orientation
>=
AP_MOTORS_NEW_PLUS_FRAME
)
{
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
// Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise
add_motor_raw
(
AP_MOTORS_MOT_2
,
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
5
);
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
1
);
add_motor_raw
(
AP_MOTORS_MOT_3
,
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
6
);
add_motor_raw
(
AP_MOTORS_MOT_2
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
add_motor_raw
(
AP_MOTORS_MOT_4
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
4
);
add_motor_raw
(
AP_MOTORS_MOT_3
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
3
);
add_motor_raw
(
AP_MOTORS_MOT_5
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
1
);
add_motor_raw
(
AP_MOTORS_MOT_4
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
4
);
add_motor_raw
(
AP_MOTORS_MOT_6
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
3
);
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
);
}
else
{
// original Y6 motor definition
add_motor_raw
(
AP_MOTORS_MOT_1
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
2
);
add_motor_raw
(
AP_MOTORS_MOT_2
,
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
5
);
add_motor_raw
(
AP_MOTORS_MOT_3
,
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
6
);
add_motor_raw
(
AP_MOTORS_MOT_4
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
4
);
add_motor_raw
(
AP_MOTORS_MOT_5
,
-
1.0
,
0.666
,
AP_MOTORS_MATRIX_YAW_FACTOR_CW
,
1
);
add_motor_raw
(
AP_MOTORS_MOT_6
,
0.0
,
-
1.333
,
AP_MOTORS_MATRIX_YAW_FACTOR_CCW
,
3
);
}
}
}
This diff is collapsed.
Click to expand it.
libraries/AP_Motors/AP_Motors_Class.h
+
5
−
1
View file @
6fd51342
...
@@ -38,6 +38,10 @@
...
@@ -38,6 +38,10 @@
#define AP_MOTORS_X_FRAME 1
#define AP_MOTORS_X_FRAME 1
#define AP_MOTORS_V_FRAME 2
#define AP_MOTORS_V_FRAME 2
#define AP_MOTORS_H_FRAME 3 // same as X frame but motors spin in opposite direction
#define AP_MOTORS_H_FRAME 3 // same as X frame but motors spin in opposite direction
#define AP_MOTORS_NEW_PLUS_FRAME 10 // NEW frames are same as original 4 but with motor orders changed to be clockwise from the front
#define AP_MOTORS_NEW_X_FRAME 11
#define AP_MOTORS_NEW_V_FRAME 12
#define AP_MOTORS_NEW_H_FRAME 13 // same as X frame but motors spin in opposite direction
// motor update rate
// motor update rate
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
...
@@ -149,7 +153,7 @@ protected:
...
@@ -149,7 +153,7 @@ protected:
// flag bitmask
// flag bitmask
struct
AP_Motors_flags
{
struct
AP_Motors_flags
{
uint8_t
armed
:
1
;
// 1 if the motors are armed, 0 if disarmed
uint8_t
armed
:
1
;
// 1 if the motors are armed, 0 if disarmed
uint8_t
frame_orientation
:
2
;
// PLUS_FRAME 0, X_FRAME 1, V_FRAME 2, H_FRAME 3
uint8_t
frame_orientation
:
4
;
// PLUS_FRAME 0, X_FRAME 1, V_FRAME 2, H_FRAME 3
, NEW_PLUS_FRAME 10, NEW_X_FRAME, NEW_V_FRAME, NEW_H_FRAME
uint8_t
slow_start
:
1
;
// 1 if slow start is active
uint8_t
slow_start
:
1
;
// 1 if slow start is active
uint8_t
slow_start_low_end
:
1
;
// 1 just after arming so we can ramp up the spin_when_armed value
uint8_t
slow_start_low_end
:
1
;
// 1 just after arming so we can ramp up the spin_when_armed value
}
_flags
;
}
_flags
;
...
...
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