Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

PX4 SITL Octocopter #3593

Closed
aaqibismail opened this issue Apr 14, 2021 · 8 comments
Closed

PX4 SITL Octocopter #3593

aaqibismail opened this issue Apr 14, 2021 · 8 comments

Comments

@aaqibismail
Copy link
Contributor

What feature are you suggesting?

Overview:

I suggest adding an Octocopter mode for the PX4 Airsim bridge that would allow creating simulations of vehicles with an Octo X configuration.

Smaller Details:

I have tried implementing this feature myself following a similar process that the Quad and Hexacopter's go through in the existing codebase.

I added an additional model -- "Octocopter" -- within the setupParams function in Px4MultiRotorParams.hpp. From there, I would call a function named setupFrameGenericOcto that I defined in MultiRotorParams.hpp that is similar to the function setupFrameGenericHex except changing the params.rotor_count to 8, and calling a function named initializeRotorOctoX for correctly aligning the rotor poses. The initializeRotorOctoX function aligns the rotors with an Octo X configuration as specified by PX4. I followed the NED's left hand rule to the best of my abilities for calculating the angle rotations; I used π/8 and 3π/8 as my rotation angles.

I have tested this on the latest Windows with the latest Airsim, Cygwin v0.8, and PX4 v1.10.1. The simulation will run, however when I try to lift the vehicle off the ground, it will flip forward instead. I am having trouble understanding whether this is due to a mistake in my rotor poses or if the thrust and masses values need to be adjusted because of the Octocopter configuration. Additionally, I am uncertain whether PX4 is generating all 8 actuator outputs. You can find a PX4 log file from one of my runs here.

   void setupFrameGenericOcto(Params& params) {
        //set up arm lengths
        //dimensions are for F450 frame: http://artofcircuits.com/product/quadcopter-frame-hj450-with-power-distribution
        params.rotor_count = 8;
        std::vector<real_T> arm_lengths(params.rotor_count, 0.2275f);

        //set up mass
        //this has to be between max_thrust*rotor_count/10 (2.5kg using default parameters in RotorParams.hpp) and (idle throttle percentage)*max_thrust*rotor_count/10 (1.25kg using default parameters and SimpleFlight)
        //any value above the maximum would result in the motors not being able to lift the body even at max thrust,
        //and any value below the minimum would cause the drone to fly upwards on idling throttle (50% of the max throttle if using SimpleFlight)

        params.mass = 1.0f; //can be varied from 0.800 to 1.600
        real_T motor_assembly_weight = 0.055f;  //weight for MT2212 motor for F450 frame
        real_T box_mass = params.mass - params.rotor_count * motor_assembly_weight;

        // using rotor_param default, but if you want to change any of the rotor_params, call calculateMaxThrust() to recompute the max_thrust
        // given new thrust coefficients, motor max_rpm and propeller diameter.
        params.rotor_params.calculateMaxThrust();

        //set up dimensions of core body box or abdomen (not including arms).
        params.body_box.x() = 0.180f; params.body_box.y() = 0.11f; params.body_box.z() = 0.040f; // y:155 , x:250 , z:50
        real_T rotor_z = 2.5f / 100;

        //computer rotor poses
        initializeRotorOctoX(params.rotor_poses, params.rotor_count, arm_lengths.data(), rotor_z);

        //compute inertia matrix
        computeInertiaMatrix(params.inertia, params.body_box, params.rotor_poses, box_mass, motor_assembly_weight);
    }

   static void initializeRotorOctoX(vector<RotorPose>& rotor_poses /* the result we are building */,
        uint rotor_count /* must be 8 */,
        real_T arm_lengths[],
        real_T rotor_z /* z relative to center of gravity */)
    {
        Vector3r unit_z(0, 0, -1);  //NED frame
        if (rotor_count == 8) {
            rotor_poses.clear();
            /* Note: rotor_poses are built in this order: rotor 0 is CW
              See OCTO X configuration on http://ardupilot.org/copter/docs/connect-escs-and-motors.html

                     x-axis
                  
                 (4)  |  (0) 
                      |
            (6)       |       (2)
            __________|__________  y-axis
                      |
            (5)       |       (7)
                      |
                 (1)  |  (3)

            0 CW: 67.5 from +Y
            1 CW: 67.5 from -Y 
            2 CCW: 22.5 from +Y
            3 CCW: 22.5 from -X
            4 CCW: 22.5 from +X
            5 CCW: 22.5 from -Y
            6 CW: 67.5 from +X
            7 CW: 67.5 from -X
            
            */

            // vectors below are rotated according to NED left hand rule (so the vectors are rotated counter clockwise).
            Quaternionr octo_rot22(AngleAxisr(M_PIf / 8, unit_z)); // 22.5 degrees
            Quaternionr octo_rot67(AngleAxisr(3* M_PIf / 8, unit_z)); // 67.5 degrees
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(0, arm_lengths[0], rotor_z), octo_rot67, true),
            unit_z, RotorTurningDirection::RotorTurningDirectionCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(0, -arm_lengths[1], rotor_z), octo_rot67, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCW);

            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(0, arm_lengths[2], rotor_z), octo_rot22, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(-arm_lengths[3], 0, rotor_z), octo_rot22, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(arm_lengths[4], 0, rotor_z), octo_rot22, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(0, -arm_lengths[5], rotor_z), octo_rot22, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(arm_lengths[6], 0, rotor_z), octo_rot67, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCW);
            
            rotor_poses.emplace_back(VectorMath::rotateVector(
                Vector3r(-arm_lengths[7], 0, rotor_z), octo_rot67, true),
                unit_z, RotorTurningDirection::RotorTurningDirectionCW);
        }
        else
            throw std::invalid_argument("Rotor count other than 8 is not supported by this method!");
    }

Nature of Request:

  • Addition

Why would this feature be useful?

This feature would be useful for simulating additional PX4 vehicles that currently cannot be simulated. Furthermore, it would provide insight on how to implement more configurations that are more complex than an Octo X.

@lovettchris
Copy link
Member

That all looks great, I think the only thing missing is configuring PX4 itself to output 8 motor outputs. In the .ulg log file you sent me I see only 6 outputs from PX4, the 7th and 8th are all zeros. Can you ad information to your above summary about how you configured PX4 to be a HIL mode octocopter?

@aaqibismail
Copy link
Contributor Author

I don't have access to any PX4 hardware so I was running in SITL none_iris mode. Is it possible to change the airframe in the SITL mode? Changing it within QGroundControl does not seem to do anything.

@lovettchris
Copy link
Member

Yes, I think your choice of airframes are listed in this location in your PX4-Autopilot repo:

ROMFS/px4fmu_common/init.d-posix/airframes

and the command line we are using to launch PX4 make px4_sitl_default none_iris is specifying the 'iris' drone (10016_iris). if instead you start with make px4_sitl_default none_typhoon_h480 you will get that airframe which is a hexacopter. Not sure if there is an octocopter in this list, you may need to add one, the key for generating 8 outputs will be in the "MIXER" you specify. THe mixers live here ROMFS/px4fmu_common/mixers and you'll probably want the "octo_x" mixer...

@aaqibismail
Copy link
Contributor Author

You are absolutely right! I changed the 10016_iris file to set MAV_TYPE 14 and set MIXER octo_x, and now it seems to work correctly. I checked the log files and confirmed that there were 8 actuator outputs. The only issue I'm dealing with is the PX4 SITL device frequently having vehicle_magnetometer lost errors or Accelerometer errors. Is there any workaround for these errors?

@lovettchris
Copy link
Member

Hey congrats, that is great that it works. You should post a demo video. There are a lot of PX4 related fixes coming in this pull request: #3603 and that might fix the vehicle_magnetometer lost errors you are seeing.

@lovettchris
Copy link
Member

#3603 is now merged, so you can merge with master and see what happens.

@lovettchris
Copy link
Member

Also your code to setupFrameGenericOcto and initializeRotorOctoX would make a great pull request :-)

@lovettchris
Copy link
Member

Woops, I mispoke, I thought it was merged already, but it is not... should be soon though...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

3 participants