I have been digging some answers for a while but had very little success. And it seems to point that ArduCopter Mega doesnt support uneven Hexa/Octo. But I could be wrong.

 

Does arducopter mega support the following

- SpiderHexa

- TY6 (Q4 Icecrab) IceCrab VD-SLR 6

- H6

 

Or is it possible to reconfigure so that ACM will support them?

 

Oh I forgot I am a complete noob in multirotor but have experience on heli and airplanes. I know the Hexa frame is about to be launch soon as Jani mentioned but this frame arrangement is pretty interesting specially for AP/AV

 

 

Views: 1878

Reply to This

Replies to This Discussion

I need H6 and V-Octo.

 

I am sure its easy - we need just new mixing files.

 

Hi Jeff,

I wrote a little doc in ArduPirates Wiki to try to explain how motor mixing works, this should get you started to make your own for almost any shape!

http://code.google.com/p/ardupirates/wiki/motormixing

 

Dani

Wow, thats very detailed. I was reading the motor config earlier and had no clue what the codes are for but this guide is very informative.Thanks Dani.

I plan to do this arrangement

 

 

 

 

 

Motor   Pitch   Roll   Yaw
1 FrontLeft CW  42% 100% -
6 BackLeft CCW  -42% 100% +
5 BackLeft CW  -100% 42% -
2 FrontRight CCW  42% -100% +
3 BackRight CW  -42% -100% -
4 BackRight CCW  -100% -42% + 

 

 

 

 

 

Would this be correct without out of bound values?

 

FrontLeftCW = constrain(throttle + (0.42 * control_pitch) + control_roll - control_yaw, minThrottle, 2000);

BackLeftCCW  = constrain(throttle - (0.42 *control_pitch) + control_roll + control_yaw, minThrottle, 2000);

BackLeftCW = constrain(throttle - control_pitch + (0.42 * control_roll) - control_yaw, minThrottle, 2000);

FrontRightCCW = constrain(throttle + (0.42 * control_pitch) - control_roll + control_yaw, minThrottle, 2000);

BackRightCW = constrain(throttle - (0.42 * control_pitch) - control_roll - control_yaw, minThrottle, 2000);

BackRightCCW = constrain(throttle - control_pitch - (0.42 * control_roll) + control_yaw, minThrottle, 2000);

 

Any comments or suggestions specially criticism? I know I have to check and make sure that the motors are assigned correctly but want to make sure I'm not missing anything. I hope I am on the right path, maybe I need to open a new thread to be more focused.

 

Also if anyone knows who can assist in fabricating parts can message me directly. Thanks

 

 

 

 

There is v-octo configuration in just reliesed version 2.0.26!

Hi Jeff,

If I were you, I'd use a V-6  shape with the two middle motors centered, you'll get a more stable platform, using your arrangement, the two front motors will have to overwork to keep it flying:

possible V-6  mixing:

Motor   Pitch   Roll   Yaw
1 FrontLeft CW  100% 100% -
6 CenterLeft CCW     0% 60%(aprox) +
5 BackLeft CW  -100% 42% -
2 FrontRight CCW  100% -100% +
3 CenterRight CW   0% -60% -
4 BackRight CCW  -100% -42% + 

 

Here is code for H6 : (to include inside motors_hexa.pde)

 

No modifications for Yaw.

 

Be careful, for this to work, some minor modifications need to be done inside setup.pde, defines.h and perhaps a couple other files.

 

 

 

I hope this is correct.

 

 

if(g.frame_orientation == X_FRAME){
        roll_out          = g.rc_1.pwm_out / 2;
        pitch_out          = (float)g.rc_2.pwm_out * .866;

        //left side
        motor_out[CH_2]        = g.rc_3.radio_out + g.rc_1.pwm_out;        // CCW Middle
        motor_out[CH_3]        = g.rc_3.radio_out + roll_out + pitch_out;    // CW Front
        motor_out[CH_8]     = g.rc_3.radio_out + roll_out - pitch_out;    // CW Back

        //right side
        motor_out[CH_1]        = g.rc_3.radio_out - g.rc_1.pwm_out;        // CW Middle
        motor_out[CH_7]     = g.rc_3.radio_out - roll_out + pitch_out;    // CCW Front
        motor_out[CH_4]     = g.rc_3.radio_out - roll_out - pitch_out;    // CCW Back

    }if(g.frame_orientation == PLUS_FRAME){
       
        roll_out          = (float)g.rc_1.pwm_out * .866;
        pitch_out          = g.rc_2.pwm_out / 2;

        //Front side
        motor_out[CH_1]        = g.rc_3.radio_out + g.rc_2.pwm_out;        // CW     FRONT
        motor_out[CH_7]     = g.rc_3.radio_out + roll_out + pitch_out;    // CCW     FRONT LEFT
        motor_out[CH_4]     = g.rc_3.radio_out - roll_out + pitch_out;    // CCW     FRONT RIGHT

        //Back side
        motor_out[CH_2]        = g.rc_3.radio_out - g.rc_2.pwm_out;        // CCW    BACK
        motor_out[CH_3]        = g.rc_3.radio_out + roll_out - pitch_out;    // CW,     BACK LEFT
        motor_out[CH_8]        = g.rc_3.radio_out - roll_out - pitch_out;    // CW    BACK RIGHT
   
    }else{
   
    // H6 frame setup
   
       
        //left side
        motor_out[CH_2]        = g.rc_3.radio_out + g.rc_1.pwm_out;        // CCW Middle
        motor_out[CH_3]        = g.rc_3.radio_out + g.rc_1.pwm_out + g.rc_2.pwm_out;    // CW Front
        motor_out[CH_8]     = g.rc_3.radio_out + g.rc_1.pwm_out - g.rc_2.pwm_out;    // CW Back

        //right side
        motor_out[CH_1]        = g.rc_3.radio_out - g.rc_1.pwm_out;        // CW Middle
        motor_out[CH_7]     = g.rc_3.radio_out - g.rc_1.pwm_out + g.rc_2.pwm_out;    // CCW Front
        motor_out[CH_4]     = g.rc_3.radio_out - g.rc_1.pwm_out - g.rc_2.pwm_out;    // CCW Back
   
    }

Thanks Dani, you have a very good point. Just wondering how those guys running the icecrab and spider hex made their setup seems so stable specially with the icecrab that had a sample video with a mark II 5D.

Delete my reply by mistake

 

Anyway, as I was asking would it make a difference if I move the CoG closer to the center motor or the V-6 is still advisable? Its just that this icecrab seems so stable and not wobly at all. I mean if the can do it on their platform ArduCopter might be more than capable.

 

Motor   Pitch   Roll   Yaw
1 FrontLeft CW  71% 100% -
6 BackLeft CCW  -13% 100% +
5 BackLeft CW  -58% 42% -
2 FrontRight CCW  71% -100% +
3 BackRight CW  -13% -100% -
4 BackRight CCW  -58% -42% + 

 

Thanks

Dani, I'm puzzled by the logic of the motor mixing. A motor that's closer to the centre has a smaller moment, so it applies less angular force (Force x distance), but instead of correcting for this, the mixing applies less force from this motor instead of more. Why is this?

Thanks

Rob

Hey, if possible can a idiot proof example of how to write the code for the above V-6 hexa be shown here. I get the percentages from 100% arm length and how to figure that to fit my frame, what I don't get is exactly how to write the code and where to write it.

 I can adjust the values to my adjusted lengths, I just don't know how to write code properly. If you guys can make this a simple follow these steps type modification then you will blow the socks off of every other flight control board out there. Modification is cool and it is what makes Arducopter so appealing. Simple steps will revolutionize the multicopter industry. It will allow people to build copters to suit their personal needs. My email is

wayneabonga@charter.net

PM or email is fine.

Thanks

Wayne

 

Dani - Do you have time to look at the attached Excel file for making custom frame calculations and creating the add_motor_raw commands?  I'm looking to create a document that tells custom frame folk how to use arducopter.

Please look at the Custom Quad +, Custom Quad X, and Custom Hexa X tabs.

Attachments:

Reply to Discussion

RSS

Groups

Season Two of the Trust Time Trial (T3) Contest 
A list of all T3 contests is here. The current round, the Vertical Horizontal one, is here

© 2020   Created by Chris Anderson.   Powered by

Badges  |  Report an Issue  |  Terms of Service