3D Thrust for Omnicopter

I’m currently building an omnicopter following the omnicopter guide with a Kakute H7V2. While running the simulation it appears that the control & mixers are still tilt-based. I saw the video of the omnicopter and it looks like it had 3D thrust control, and want to do a sanity check before diving into re-writing my own controller for 3D thrust.

Does such a controller already exist somewhere?

1 Like

@bkueng would appreciate your answer on this!

1 Like

@chen716 this part isn’t completely integrated yet. I added some test code for the demo, and you find the branch here: GitHub - PX4/PX4-Autopilot at omnicopter-testing.
Specifically this commit: TEST: allow omnicopter to rotate via AUX1 & use 3D thrust in pos/miss… · PX4/PX4-Autopilot@923b5b1 · GitHub.

You’re welcome to cleanly integrate this.

2 Likes

Hi @bkueng, thanks for the reply.

From my understanding of the file, it is taking in an additional parameter from aux setpoints to be used to control the roll of the omnicopter. Then the compute attitude and thrust results are passed on to angle/angular rates control. Does this mean without the additional change in the rate/angular rate controller, and only provide an additional roll/pitch the copter is supposed to balance itself given the roll/pitch(eg. setting the roll/pitch to a constant of 0 would mean the drone doing “3d thrust”)?

Thanks!

Dear @junwoo0914 ,

Video: omni - Google Drive

I’m also running into some issues with the build of my omnicopter… When I put it in stabilized mode and raise the thrust, it takeoff a bit(10cm) but quickly becomes imbalanced and starts rotating along motor1’s axis. I suspect that my balance of the drone/position of the motor could be off. Any suggestions on how to construct the drone better/where to place the motors? Currently, I’m placing all my motors at a fixed distance from the 3D parts (~10.4cm), but it looks like the torque was imbalanced and caused the drone to spin.

Really appreciate your help.

Thanks!

Mavros launch:
process[mavros-1]: started with pid [1112]
[ INFO] [1690940125.631457077]: FCU URL: /dev/ttyACM0:57600
[ INFO] [1690940125.654279836]: serial0: device: /dev/ttyACM0 @ 57600 bps
[ INFO] [1690940125.657652170]: GCS URL: udp://:14550@192.168.1.220:14550
[ INFO] [1690940125.659000577]: udp1: Bind address: 0.0.0.0:14550
[ INFO] [1690940125.659336281]: udp1: Remote address: 192.168.1.220:14550
[ INFO] [1690940126.088270743]: Plugin 3dr_radio loaded
[ INFO] [1690940126.117742540]: Plugin 3dr_radio initialized
[ INFO] [1690940126.118303021]: Plugin actuator_control loaded
[ INFO] [1690940126.161246910]: Plugin actuator_control initialized
[ INFO] [1690940126.423731799]: Plugin adsb loaded
[ INFO] [1690940126.478729780]: Plugin adsb initialized
[ INFO] [1690940126.478899521]: Plugin altitude blacklisted
[ INFO] [1690940126.479605188]: Plugin cam_imu_sync loaded
[ INFO] [1690940126.487006817]: Plugin cam_imu_sync initialized
[ INFO] [1690940126.487528502]: Plugin camera loaded
[ INFO] [1690940126.494965151]: Plugin camera initialized
[ INFO] [1690940126.495651928]: Plugin cellular_status loaded
[ INFO] [1690940126.534185039]: Plugin cellular_status initialized
[ INFO] [1690940126.535103410]: Plugin command loaded
[ INFO] [1690940126.623268113]: Plugin command initialized
[ INFO] [1690940126.623925854]: Plugin companion_process_status loaded
[ INFO] [1690940126.660467447]: Plugin companion_process_status initialized
[ INFO] [1690940126.660614965]: Plugin debug_value blacklisted
[ INFO] [1690940126.660749910]: Plugin distance_sensor blacklisted
[ INFO] [1690940126.661545169]: Plugin esc_status loaded
[ INFO] [1690940126.676014076]: Plugin esc_status initialized
[ INFO] [1690940126.676825613]: Plugin esc_telemetry loaded
[ INFO] [1690940126.683842076]: Plugin esc_telemetry initialized
[ INFO] [1690940126.684795984]: Plugin fake_gps loaded
[ INFO] [1690940126.956273613]: Plugin fake_gps initialized
[ INFO] [1690940126.956420521]: Plugin ftp blacklisted
[ INFO] [1690940126.957344854]: Plugin geofence loaded
[ INFO] [1690940127.000626613]: Plugin geofence initialized
[ INFO] [1690940127.001526576]: Plugin global_position loaded
[ INFO] [1690940127.230717261]: Plugin global_position initialized
[ INFO] [1690940127.231492632]: Plugin gps_input loaded
[ INFO] [1690940127.272961595]: Plugin gps_input initialized
[ INFO] [1690940127.273837650]: Plugin gps_rtk loaded
[ INFO] [1690940127.316605057]: Plugin gps_rtk initialized
[ INFO] [1690940127.317493132]: Plugin gps_status loaded
[ INFO] [1690940127.347000428]: Plugin gps_status initialized
[ INFO] [1690940127.347756261]: Plugin guided_target loaded
[ INFO] [1690940127.434278780]: Plugin guided_target initialized
[ INFO] [1690940127.434475557]: Plugin hil blacklisted
[ INFO] [1690940127.435461928]: Plugin home_position loaded
[ INFO] [1690940127.483295113]: Plugin home_position initialized
[ INFO] [1690940127.484587354]: Plugin imu loaded
[ INFO] [1690940127.582993557]: Plugin imu initialized
[ INFO] [1690940127.583753242]: Plugin landing_target loaded
[ INFO] [1690940127.808898316]: Plugin landing_target initialized
[ INFO] [1690940127.809952002]: Plugin local_position loaded
[ INFO] [1690940127.903150502]: Plugin local_position initialized
[ INFO] [1690940127.903893057]: Plugin log_transfer loaded
[ INFO] [1690940127.944418576]: Plugin log_transfer initialized
[ INFO] [1690940127.945189113]: Plugin mag_calibration_status loaded
[ INFO] [1690940127.961840279]: Plugin mag_calibration_status initialized
[ INFO] [1690940127.962699742]: Plugin manual_control loaded
[ INFO] [1690940128.003779187]: Plugin manual_control initialized
[ INFO] [1690940128.004591594]: Plugin mocap_pose_estimate loaded
01
[ INFO] [1690940128.062658353]: Plugin mocap_pose_estimate initialized
[ INFO] [1690940128.063453390]: Plugin mount_control loaded
[ WARN] [1690940128.140854724]: Could not retrive negate_measured_roll parameter value, using default (0)
[ WARN] [1690940128.147751224]: Could not retrive negate_measured_pitch parameter value, using default (0)
[ WARN] [1690940128.154830094]: Could not retrive negate_measured_yaw parameter value, using default (0)
[ WARN] [1690940128.180850983]: Could not retrive debounce_s parameter value, using default (4.000000)
[ WARN] [1690940128.186769187]: Could not retrive err_threshold_deg parameter value, using default (10.000000)
[ INFO] [1690940128.187169538]: Plugin mount_control initialized
[ INFO] [1690940128.188031612]: Plugin nav_controller_output loaded
[ INFO] [1690940128.196678390]: Plugin nav_controller_output initialized
[ INFO] [1690940128.197502150]: Plugin obstacle_distance loaded
[ INFO] [1690940128.241184224]: Plugin obstacle_distance initialized
[ INFO] [1690940128.242032187]: Plugin odom loaded
[ INFO] [1690940128.295495372]: Plugin odom initialized
[ INFO] [1690940128.296323224]: Plugin onboard_computer_status loaded
[ INFO] [1690940128.330353594]: Plugin onboard_computer_status initialized
[ INFO] [1690940128.331483594]: Plugin param loaded
[ INFO] [1690940128.363328335]: Plugin param initialized
[ INFO] [1690940128.363983557]: Plugin play_tune loaded
[ INFO] [1690940128.398338798]: Plugin play_tune initialized
[ INFO] [1690940128.398522612]: Plugin px4flow blacklisted
[ INFO] [1690940128.399430483]: Plugin rallypoint loaded
[ INFO] [1690940128.439487316]: Plugin rallypoint initialized
[ INFO] [1690940128.440357835]: Plugin rangefinder loaded
[ INFO] [1690940128.448119446]: Plugin rangefinder initialized
[ INFO] [1690940128.448965742]: Plugin rc_io loaded
[ INFO] [1690940128.501512038]: Plugin rc_io initialized
[ INFO] [1690940128.501758501]: Plugin safety_area blacklisted
[ INFO] [1690940128.502845316]: Plugin setpoint_accel loaded
[ INFO] [1690940128.555386483]: Plugin setpoint_accel initialized
[ INFO] [1690940128.556813186]: Plugin setpoint_attitude loaded
[ INFO] [1690940128.710941594]: Plugin setpoint_attitude initialized
[ INFO] [1690940128.711756075]: Plugin setpoint_position loaded
[ INFO] [1690940128.943225094]: Plugin setpoint_position initialized
[ INFO] [1690940128.944398964]: Plugin setpoint_raw loaded
[ INFO] [1690940129.077934408]: Plugin setpoint_raw initialized
[ INFO] [1690940129.079050834]: Plugin setpoint_trajectory loaded
[ INFO] [1690940129.142935723]: Plugin setpoint_trajectory initialized
[ INFO] [1690940129.143820779]: Plugin setpoint_velocity loaded
[ INFO] [1690940129.229932649]: Plugin setpoint_velocity initialized
[ INFO] [1690940129.231763982]: Plugin sys_status loaded
[ INFO] [1690940129.380570964]: Plugin sys_status initialized
[ INFO] [1690940129.381336982]: Plugin sys_time loaded
[ INFO] [1690940129.466690093]: TM: Timesync mode: MAVLINK
[ INFO] [1690940129.472923334]: TM: Not publishing sim time
[ INFO] [1690940129.490639871]: Plugin sys_time initialized
[ INFO] [1690940129.491479982]: Plugin terrain loaded
[ INFO] [1690940129.499104167]: Plugin terrain initialized
[ INFO] [1690940129.499933371]: Plugin trajectory loaded
[ INFO] [1690940129.572987575]: Plugin trajectory initialized
[ INFO] [1690940129.573807667]: Plugin tunnel loaded
[ INFO] [1690940129.616067556]: Plugin tunnel initialized
[ INFO] [1690940129.617016056]: Plugin vfr_hud loaded
[ INFO] [1690940129.626634075]: Plugin vfr_hud initialized
[ INFO] [1690940129.626779186]: Plugin vibration blacklisted
[ INFO] [1690940129.627446223]: Plugin vision_pose_estimate loaded
[ INFO] [1690940129.672282112]: **********LISTENING FOR VISION
[ INFO] [1690940129.672528297]: Listen to vision transform map → vision_estimate
[ INFO] [1690940129.711319463]: Plugin vision_pose_estimate initialized
[ INFO] [1690940129.712368352]: Plugin vision_speed_estimate loaded
[ INFO] [1690940129.772500426]: Plugin vision_speed_estimate initialized
[ INFO] [1690940129.773401334]: Plugin waypoint loaded
[ INFO] [1690940129.840061704]: Plugin waypoint initialized
[ INFO] [1690940129.840328167]: Plugin wheel_odometry blacklisted
[ INFO] [1690940129.841162056]: Plugin wind_estimation loaded
[ INFO] [1690940129.850322389]: Plugin wind_estimation initialized
[ INFO] [1690940129.851221186]: Built-in SIMD instructions: None
[ INFO] [1690940129.851375260]: Built-in MAVLink package version: 2021.3.3
[ INFO] [1690940129.851506167]: Known MAVLink dialects: common ardupilotmega ASLUAV all autoquad icarous matrixpilot paparazzi standard uAvionix ualberta
[ INFO] [1690940129.851651389]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1690940131.995214129]: GF: Using MISSION_ITEM_INT
[ INFO] [1690940131.995559981]: RP: Using MISSION_ITEM_INT
[ INFO] [1690940131.995808518]: WP: Using MISSION_ITEM_INT
[ INFO] [1690940131.996233684]: VER: 1.1: Capabilities 0x000000000000ecff
[ INFO] [1690940131.996534944]: VER: 1.1: Flight software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940131.996741407]: VER: 1.1: Middleware software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940131.996931684]: VER: 1.1: OS software: 0b0000ff (3f77354c0dc88793)
[ INFO] [1690940131.997125462]: VER: 1.1: Board hardware: 00000050
[ INFO] [1690940131.997307907]: VER: 1.1: VID/PID: 3162:0050
[ INFO] [1690940131.997491166]: VER: 1.1: UID: 3430510b38303334
[ WARN] [1690940132.000718203]: TM : RTT too high for timesync: 947.63 ms.
[ WARN] [1690940132.002290462]: TM : RTT too high for timesync: 349.22 ms.
[ INFO] [1690940132.015870925]: IMU: Attitude quaternion IMU detected!
[ INFO] [1690940132.016825758]: IMU: High resolution IMU detected!
[ INFO] [1690940132.138011814]: udp1: Remote address: 192.168.1.220:14550
[ INFO] [1690940132.993720258]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1690940133.017083202]: IMU: Attitude quaternion IMU detected!
[ INFO] [1690940133.018739776]: IMU: High resolution IMU detected!
[ INFO] [1690940133.032257832]: VER: 1.1: Capabilities 0x000000000000ecff
[ INFO] [1690940133.032386276]: VER: 1.1: Flight software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940133.032472758]: VER: 1.1: Middleware software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940133.032548721]: VER: 1.1: OS software: 0b0000ff (3f77354c0dc88793)
[ INFO] [1690940133.032628461]: VER: 1.1: Board hardware: 00000050
[ INFO] [1690940133.032701054]: VER: 1.1: VID/PID: 3162:0050
[ INFO] [1690940133.032772961]: VER: 1.1: UID: 3430510b38303334
[ WARN] [1690940133.033277924]: CMD: Unexpected command 512, result 0
[ INFO] [1690940133.046851647]: VER: 1.1: Capabilities 0x000000000000ecff
[ INFO] [1690940133.047018702]: VER: 1.1: Flight software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940133.047147684]: VER: 1.1: Middleware software: 010e0000 (3cc940cb06000000)
[ INFO] [1690940133.047256702]: VER: 1.1: OS software: 0b0000ff (3f77354c0dc88793)
[ INFO] [1690940133.047367128]: VER: 1.1: Board hardware: 00000050
[ INFO] [1690940133.047473147]: VER: 1.1: VID/PID: 3162:0050
[ INFO] [1690940133.047583943]: VER: 1.1: UID: 3430510b38303334
[ INFO] [1690940134.567092386]: WP: seems GCS requesting mission
[ INFO] [1690940134.567275831]: WP: scheduling pull after GCS is done
[ INFO] [1690940134.578644553]: GF: seems GCS requesting mission
[ INFO] [1690940134.578799572]: GF: scheduling pull after GCS is done
[ INFO] [1690940134.611645053]: RP: seems GCS requesting mission
[ INFO] [1690940134.611817386]: RP: scheduling pull after GCS is done
[ INFO] [1690940139.568374365]: WP: mission received
[ INFO] [1690940139.579712661]: GF: mission received
[ INFO] [1690940139.612723291]: RP: mission received
[ INFO] [1690940143.000322752]: HP: requesting home position
[ WARN] [1690940144.714872121]: CMD: Unexpected command 176, result 0
[ INFO] [1690940151.502090765]: FCU: Armed by external command
[ INFO] [1690940151.549989524]: FCU: [logger] /fs/microsd/log/2023-08-02/01_35_49.ulg
[ INFO] [1690940152.419873505]: FCU: Takeoff detected
[ INFO] [1690940153.000126394]: HP: requesting home position

Hi, I’m just leaving my answer here because I’m currently working on using 3D thrust as well.

The changes are needed to decouple the attitude setpoint from the thrust setpoint. A standard drone needs this coupling to know how much to tilt in order to fly a certain amount in horizontal direction. In the controller diagrams in the doc this should be the block between velocity and attitude controller named “Acceleration and Yaw to Attitude”. The function thrustToAttitude from ControlMath does exactly this if I’m not mistaken.

Now in order to decouple the position from the attitude you just need to get rid of this function and replace it with your own code. In order for this to still work you need to provide a separate attitude setpoint. How you do this depends on what you want to do with it. I probably just want to fly sideways without tilting the drone, so for me it would be enough to set roll and pitch to zero and calculate my attitude setpoint from this. If you want it to fly at an arbitrary orientation you can try to implement something similar to the changes from the omnicopter-testing branch.

The drone should, regardless of its orientation, use 3d thrust, because the whole thrust setpoint (with x, y and z) is being passed to the attitude controller. I’m just not sure yet what’s exactly done with the “Rotate thrust by negative attitude” (I guess some kind of coordinate transformation).

2 Likes