I plan to do what is called a "pull" to made changes to the custom code regarding custom shaped copters.
This change in code would only impacts irregular shaped quads, hexas, and octas when the pilot specifically opts to go custom versus the default (the standard X or +). You have a custom quad if the:
o aspect ratio <> 1 (length is different than width).
o rotors are non symmetric around the
- forward axis (y) going through the center of gravity (CG)
- sideways axis (x) going through the CG
- vertical axis (z) going through the CG
o has a front that is more open for a camera
o deviates from the pictures of a a + or X for the quad, hexa, or octa
o this includes ships described as spider, V, H, U, 88--88, C, etc.
o motor spin direction(s) are different than the pictures
o your CG is pushed somewhere else besides the centroid of the motors.
The advantages of going custom is that the motor factors will be tuned to the coordinate/spin system of your copter versus the coordinate/spin system of the regular copter. They will fly better. Pilots will probably not notice small deviations nor would they see significantly improved flight times. Large deviations might be noticed and provide noticeable changes in flight duration.
Please reply with the motor number (the out-pin number on the APM), coordinates of the motor, and rotation direction of each rotor. For example,
the owner of this copter would reply (motor number, x, y, CCW/CW):
o 1 (400, 200) CCW
o 2 (-250, -200) CCW
o 3 (-400, 200), CW
o 4 (250, -200 CW
[note: no need to tell us your units of measure just so long as you are consistent in measuring; say mm or inches]
Please note:
o The center of gravity of any quad spider or V is not necessarily where the bars cross. The bars typically cross behind the CG. .
o The CG is the center of the coordinates or (0,0) where x=0 and y=0
If you decide to participate by replying, the idea is that you will be able to access your custom motor factors without having to compile firmware. No promises at this point. First we see what's out there. But if you do reply, it's far more likely that your design will be implemented in the library.
If you have any questions or difficulties in doing this, let me know so I can help.
Replies
Transformable Multirotor
Hi everyone. It would seem I have found what i am looking for in this thread. I am a third year maths student and a 3d heli pilot. I have been playing with X quads for a few years. I have completely lost interest in 3d flight and i'm now consumed by the very thing that is making these multicopters fly. I'm certainly no genius which is why i now have a beautiful variant frame quad with a really nice gimbal and camera controlled by an APM that has a very dangerous yaw. I have tried changing code, angles and motor outputs but im back to reloading the standard firmware. I will be following this thread with great interest and hopefully contribute in the future. For now i am enjoying my X with a pixhawk, my fleet of choppers and only very carefully flying and filming with my Variant X.
define "dangerous yaw"
- when does it occur (no input, during yaw input, etc.)?
- what is the behavior (it wobbles and doesn't yaw, etc.)?
Roll and pitch seem to be fine. When I start to yaw left(with stick input) the rear right motor has way too much input and lifts the back of my quad, and same if i yaw right, the back left motor has way too much input. I thought this was a simple fix in the AP_Motors.cpp file. I was pretty sure that if i put the correct angles in the AP_Motors.cpp V Frame lines of code i could reduce the input of the motors causing the quad to lift at the rear during yaw. I also read that changing the angles was all i had to do and that would take care of the individual motor inputs for the yaw. I may be missing something, i am on a steep learning curve so please forgive me. This thread seems to be the most up to date information, most other places i have been reading from date back two years.
P.S The yaw problem is very aggressive, hence dangerous in a situation where i need to yaw quickly.
This does sound like a coupling issue. If you input angles and the V Frame, then you will have coupling on a custom ship. If you input motor factors based on V-frame design, then you are close, but may be inputting the wrong factors.
Did you use CustomCAD (my Excel program) to determine motor factors?
Give me your exact ship layout in a x/y coordinates for each motor along with the code you used in AP and we'll test the above hypothesis.
I tried to change the code and compile.I did'nt get it to work.I then tried to compile the code using the instructions on this page http://dev.ardupilot.com/wiki/building-the-code/building-px4-with-m... but could'nt make it to compile.
A friend tried also but he said that the "Make" was missing he tried to find any info regarding that but could'nt.He then tried to compile it in ubuntu using this instructionshttp://dev.ardupilot.com/wiki/building-the-code/building-px4-for-li... .
And it managed to compile the code!
But...now when I try too setup it in mission planner, it spins just 4 engines and it is from the motor outputs 1 to 4 so it seems the firmware is for a quad?
I changed the "//#define frame_config quad_frame" to "define FRAME_CONFIG OCTA_FRAME" (removed //)in APM_CONFIG.h file
And here is the code in AP_motorsocta.cpp:
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see a href="http://www.gnu.org/licenses/>" target="_blank">http://www.gnu.org/licenses/>.
*/
/*
* AP_MotorsOcta.cpp - ArduCopter motors library
* Code by RandyMackay. DIYDrones.com
*
*/
#include "AP_MotorsOcta.h"
// setup_motors - configures the motors for a octa
void AP_MotorsOcta::setup_motors()
{
// call parent
AP_MotorsMatrix::setup_motors();
// hard coded config for supported frames
if( _flags.frame_orientation == AP_MOTORS_PLUS_FRAME ) {
// plus frame set-up
add_motor(AP_MOTORS_MOT_1, 0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
add_motor(AP_MOTORS_MOT_2, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
add_motor(AP_MOTORS_MOT_3, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
add_motor(AP_MOTORS_MOT_4, 135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
add_motor(AP_MOTORS_MOT_5, -45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
add_motor(AP_MOTORS_MOT_6, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
add_motor(AP_MOTORS_MOT_7, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
add_motor(AP_MOTORS_MOT_8, 90, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
}else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) {
// V frame set-up my vocto setup
add_motor_raw(AP_MOTORS_MOT_1, 0.835, -0.338, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
add_motor_raw(AP_MOTORS_MOT_2, -0.665, 0.338, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
add_motor_raw(AP_MOTORS_MOT_3, 0.665, 0.338, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
add_motor_raw(AP_MOTORS_MOT_4, -0.5, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
add_motor_raw(AP_MOTORS_MOT_5, 1.0, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
add_motor_raw(AP_MOTORS_MOT_6, -0.835, -0.338, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
add_motor_raw(AP_MOTORS_MOT_7, -1.0, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
}else {
// X orginal apm vocto
add_motor_raw(AP_MOTORS_MOT_1, 1.0, -0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
add_motor_raw(AP_MOTORS_MOT_2, -1.0, 0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
add_motor_raw(AP_MOTORS_MOT_3, 1.0, 0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
add_motor_raw(AP_MOTORS_MOT_4, -0.5, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
add_motor_raw(AP_MOTORS_MOT_5, 1.0, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
add_motor_raw(AP_MOTORS_MOT_6, -1.0, -0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
add_motor_raw(AP_MOTORS_MOT_7, -1.0, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
}
}
So I do not understand what went wrong? may the code have changed since this compilation instructional was written?
So it needs some more changes in the code?
Thank you Forrest for the compile manual link! I found this old link http://diydrones.com/photo/big-octacopter-v and there
is this image of a v octo
and if i look at the code you added:
}else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) {
// V frame set-up
add_motor_raw(AP_MOTORS_MOT_1, 1.0, 0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7);
add_motor_raw(AP_MOTORS_MOT_2, -1.0, -0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3);
add_motor_raw(AP_MOTORS_MOT_3, 1.0, -0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6);
add_motor_raw(AP_MOTORS_MOT_4, -0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
add_motor_raw(AP_MOTORS_MOT_5, 1.0, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8);
add_motor_raw(AP_MOTORS_MOT_6, -1.0, 0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
add_motor_raw(AP_MOTORS_MOT_7, -1.0, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1);
add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5);
Then number after AP_MOTORS_MOT_(bold italic) seems to match prop rotation and motor number in image.
And roll, pitch numbers also looks to match
I think I will test to compile the code using your manual of how to do it.And base it on the above image and code, and only change roll and pitch factors to the values you gave me in the spredsheet.
But what does the number(?) after YAW_FACTOR_(CW or CCW),(?) stand for?
I've read different things on the number after the yaw factor (opposites, test spin order). My conclusion so far is that whatever they are, they might be obsolete. So guess i'm the wrong person to ask.
Ok.Good to know just curios....
And should we not talk about center of Mass instead of center of Gravity....