I am having issues compiling your Y4 patch, and I was hoping you could offer some advice for how to fix the issue. When compiling this is what I get along with multiple lines saying certain variables are declared but never used. Thanks in advance.
In file included from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_Motors.h:17:0, from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AC_AttitudeControl/AC_AttitudeControl.h:14, from ArduCopter.ino:123: C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h: In constructor 'AP_MotorsY4::AP_MotorsY4(RC_Channel*, RC_Channel*, RC_Channel*, RC_Channel*, uint16_t)': C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h:19:217: error: no matching function for call to 'AP_MotorsMatrix::AP_MotorsMatrix(RC_Channel*&, RC_Channel*&, RC_Channel*&, RC_Channel*&, uint16_t&)' C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h:19:217: note: candidates are: In file included from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_Motors.h:7:0, from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AC_AttitudeControl/AC_AttitudeControl.h:14, from ArduCopter.ino:123: C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:24:5: note: AP_MotorsMatrix::AP_MotorsMatrix(RC_Channel&, RC_Channel&, RC_Channel&, RC_Channel&, uint16_t) C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:24:5: note: no known conversion for argument 1 from 'RC_Channel*' to 'RC_Channel&' C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:20:7: note: AP_MotorsMatrix::AP_MotorsMatrix(const AP_MotorsMatrix&) C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:20:7: note: candidate expects 1 argument, 5 provided motors.ino: In function 'bool pre_arm_gps_checks(bool)': motors.ino:551:28: warning: comparison between signed and unsigned integer expressions
John Stäck > Kevin Teigen WilliamsFebruary 18, 2015 at 9:19am
What version of the Ardupilot code are you using? I haven't looked at the newer ones (still running with an old one since it works for what I do), it might be that patch doesn't work anymore. Does it compile cleanly without the patch?
So I assume I have the most recent version. Without the patch the Code compiles, uploads, and flies just fine. I did notice some differences in the code from what your patch showed.
Is it possible to download an older version of the code?
Do you still fly your Y4? I'd like to test this out on a proper Y4 frame and would therefore like to try out your code
Would your patch still be working in the 3.1?
I have yet to set up the IDE to compile this so this is why I ask - I'm in the process of setting it up try myself but if you could update us with any videos or even more of your experience on the matter I'd like to work this into a usable frame for APM.
Additionally I have a working Multiwii Board that supports Y4, so I could also test out flight characteristics between the two for comparison
I flew it earlier this summer, but crashed it and broke the frame and have not had time to rebuild it. Haven't looked at the newer source code (like 3.1), but the patch is pretty simple and should be easy enough to rewrite for it.
Hey John, so I've figured out what I needed to modify to get it flying - after testing a bunch of different parameters.
It has a big tendency to lean forward as you said it would.
This is my motor mix for it (having removed front YAW completely)
add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.666, 0, 1); add_motor_raw(AP_MOTORS_MOT_2, 1.0, 0.666, 0, 3); add_motor_raw(AP_MOTORS_MOT_3, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); //mot 4 on y6a frame - must be bottom motor of Y4 add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); //mot 6 on y6a frame - must be bottom motor of y4
It was so long ago I fiddled with the code that I am not entirely sure of what I was actually flew with (I set it up and left it alone and just flew it).
I did get rid of the forward-pitch tendency by just trimming it, I remember lowering the back a bit when zeroing the accellerometer (but that might have been when just testing things out).
I also did try with having the front motors configured for "zero yaw" (as you have above), same as the tail motors, or a small fraction of the tail rotors. It didn't make that much difference (some combinations made it roll a bit when yawing), but I think this is what I ended up flying with:
I was trying out a lot of math, Y4V_TAIL_WIDTH is basically the component of the tail motor perpendicular to the roll axis (tail width * cos(tilt angle)). Fiddled with the same thing for yaw and pitch, but it didn't make much difference, it was all tunable&trimmable without it. I ended up running 12x4.5 props in front and 10x4.5 back, which made the whole thing fly level easier, and also made the tail rotors have even less effect on roll.
This setup is for an "A tail" (upside-down V), so the left rear rotor is "pulling" the tail to the left, rotating the multicopter in the clockwise direction. I also chose the direction of the motor/prop so the "yaw torque" would work in the same direciton, so the left-rear prop is CCW.
I will probably be rebuilding a new and improved V-tail Y4 soon and spend some more time fiddling with the firmware, will update with how it goes.
Thanks for answering! I've already patched in all the changes you've made into 3.2rc4 however at the moment I'm just trying to make sure there isn't anything else I'm missing.
I had an ESC glitch mid-flight (bad connection somewhere), had nothing to do with the APM. Lost power to the front-right motor, made a roll and inverted dive into terrain.
Replies
I am having issues compiling your Y4 patch, and I was hoping you could offer some advice for how to fix the issue. When compiling this is what I get along with multiple lines saying certain variables are declared but never used. Thanks in advance.
In file included from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_Motors.h:17:0,
from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AC_AttitudeControl/AC_AttitudeControl.h:14,
from ArduCopter.ino:123:
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h: In constructor 'AP_MotorsY4::AP_MotorsY4(RC_Channel*, RC_Channel*, RC_Channel*, RC_Channel*, uint16_t)':
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h:19:217: error: no matching function for call to 'AP_MotorsMatrix::AP_MotorsMatrix(RC_Channel*&, RC_Channel*&, RC_Channel*&, RC_Channel*&, uint16_t&)'
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsY4.h:19:217: note: candidates are:
In file included from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_Motors.h:7:0,
from C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AC_AttitudeControl/AC_AttitudeControl.h:14,
from ArduCopter.ino:123:
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:24:5: note: AP_MotorsMatrix::AP_MotorsMatrix(RC_Channel&, RC_Channel&, RC_Channel&, RC_Channel&, uint16_t)
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:24:5: note: no known conversion for argument 1 from 'RC_Channel*' to 'RC_Channel&'
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:20:7: note: AP_MotorsMatrix::AP_MotorsMatrix(const AP_MotorsMatrix&)
C:\Program Files\Git\ardupilot-master\ardupilot-master\libraries\AP_Motors/AP_MotorsMatrix.h:20:7: note: candidate expects 1 argument, 5 provided
motors.ino: In function 'bool pre_arm_gps_checks(bool)':
motors.ino:551:28: warning: comparison between signed and unsigned integer expressions
What version of the Ardupilot code are you using? I haven't looked at the newer ones (still running with an old one since it works for what I do), it might be that patch doesn't work anymore. Does it compile cleanly without the patch?
I followed the steps here: http://dev.ardupilot.com/wiki/building-the-code/building-ardupilot-...
So I assume I have the most recent version. Without the patch the Code compiles, uploads, and flies just fine. I did notice some differences in the code from what your patch showed.
Is it possible to download an older version of the code?
any Y4 support coming?
this looks pretty cool
http://reptile-tech.com/content/?4.html
Hey John,
Do you still fly your Y4? I'd like to test this out on a proper Y4 frame and would therefore like to try out your code
Would your patch still be working in the 3.1?
I have yet to set up the IDE to compile this so this is why I ask - I'm in the process of setting it up try myself but if you could update us with any videos or even more of your experience on the matter I'd like to work this into a usable frame for APM.
Additionally I have a working Multiwii Board that supports Y4, so I could also test out flight characteristics between the two for comparison
I flew it earlier this summer, but crashed it and broke the frame and have not had time to rebuild it. Haven't looked at the newer source code (like 3.1), but the patch is pretty simple and should be easy enough to rewrite for it.
Hey John, so I've figured out what I needed to modify to get it flying - after testing a bunch of different parameters.
It has a big tendency to lean forward as you said it would.
This is my motor mix for it (having removed front YAW completely)
add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.666, 0, 1);
add_motor_raw(AP_MOTORS_MOT_2, 1.0, 0.666, 0, 3);
add_motor_raw(AP_MOTORS_MOT_3, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); //mot 4 on y6a frame - must be bottom motor of Y4
add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); //mot 6 on y6a frame - must be bottom motor of y4
Video of it flying - to keep it level I have to push back on the pitch in order to avoid too much forward drift.
https://www.youtube.com/watch?v=cYybCajUmZc
However I'd like to see if its possible to fix the forward pitching without playing with the CG, the way that multiwii does it.
Anyone have any ideas where to start?
It was so long ago I fiddled with the code that I am not entirely sure of what I was actually flew with (I set it up and left it alone and just flew it).
I did get rid of the forward-pitch tendency by just trimming it, I remember lowering the back a bit when zeroing the accellerometer (but that might have been when just testing things out).
I also did try with having the front motors configured for "zero yaw" (as you have above), same as the tail motors, or a small fraction of the tail rotors. It didn't make that much difference (some combinations made it roll a bit when yawing), but I think this is what I ended up flying with:
I was trying out a lot of math, Y4V_TAIL_WIDTH is basically the component of the tail motor perpendicular to the roll axis (tail width * cos(tilt angle)). Fiddled with the same thing for yaw and pitch, but it didn't make much difference, it was all tunable&trimmable without it. I ended up running 12x4.5 props in front and 10x4.5 back, which made the whole thing fly level easier, and also made the tail rotors have even less effect on roll.
This setup is for an "A tail" (upside-down V), so the left rear rotor is "pulling" the tail to the left, rotating the multicopter in the clockwise direction. I also chose the direction of the motor/prop so the "yaw torque" would work in the same direciton, so the left-rear prop is CCW.
I will probably be rebuilding a new and improved V-tail Y4 soon and spend some more time fiddling with the firmware, will update with how it goes.
Thanks for answering! I've already patched in all the changes you've made into 3.2rc4 however at the moment I'm just trying to make sure there isn't anything else I'm missing.
Did you ever ascertain what caused your crash?
I had an ESC glitch mid-flight (bad connection somewhere), had nothing to do with the APM. Lost power to the front-right motor, made a roll and inverted dive into terrain.