diff --git a/Tools/simulation/gazebo-classic/sitl_gazebo-classic b/Tools/simulation/gazebo-classic/sitl_gazebo-classic index c0e0751341..fbd8e9e6bb 160000 --- a/Tools/simulation/gazebo-classic/sitl_gazebo-classic +++ b/Tools/simulation/gazebo-classic/sitl_gazebo-classic @@ -1 +1 @@ -Subproject commit c0e0751341d46108377bbae2ae1bb6da8a5d4106 +Subproject commit fbd8e9e6bbd2188de81677494f15885dead99c48 diff --git a/src/modules/control_allocator/ControlAllocator.cpp b/src/modules/control_allocator/ControlAllocator.cpp index 0bc3f9c86e..99e280dd71 100644 --- a/src/modules/control_allocator/ControlAllocator.cpp +++ b/src/modules/control_allocator/ControlAllocator.cpp @@ -270,6 +270,14 @@ ControlAllocator::update_effectiveness_source() tmp = new ActuatorEffectivenessHelicopterCoaxial(this); break; + case EffectivenessSource::SPACECRAFT_2D: + // spacecraft_allocation does allocation and publishes directly to actuator_motors topic + break; + + case EffectivenessSource::SPACECRAFT_3D: + // spacecraft_allocation does allocation and publishes directly to actuator_motors topic + break; + default: PX4_ERR("Unknown airframe"); break; diff --git a/src/modules/control_allocator/ControlAllocator.hpp b/src/modules/control_allocator/ControlAllocator.hpp index 303316f1ef..1f91f7d17d 100644 --- a/src/modules/control_allocator/ControlAllocator.hpp +++ b/src/modules/control_allocator/ControlAllocator.hpp @@ -158,6 +158,8 @@ private: HELICOPTER_TAIL_ESC = 10, HELICOPTER_TAIL_SERVO = 11, HELICOPTER_COAXIAL = 12, + SPACECRAFT_2D = 13, + SPACECRAFT_3D = 14, }; enum class FailureMode { diff --git a/src/modules/control_allocator/module.yaml b/src/modules/control_allocator/module.yaml index 013b954033..6dc0efacff 100644 --- a/src/modules/control_allocator/module.yaml +++ b/src/modules/control_allocator/module.yaml @@ -7,33 +7,8 @@ module_name: Control Allocation parameters: - group: Geometry definitions: - CA_AIRFRAME: - description: - short: Airframe selection - long: | - Defines which mixer implementation to use. - Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. - 'Custom' should only be used if noting else can be used. - type: enum - values: - 0: Multirotor - 1: Fixed-wing - 2: Standard VTOL - 3: Tiltrotor VTOL - 4: Tailsitter VTOL - 5: Rover (Ackermann) - 6: Rover (Differential) - 7: Motors (6DOF) - 8: Multirotor with Tilt - 9: Custom - 10: Helicopter (tail ESC) - 11: Helicopter (tail Servo) - 12: Helicopter (Coaxial) - 13: Rover (Mecanum) - default: 0 - - CA_METHOD: + SC_CA_METHOD: description: short: Control allocation method long: | @@ -42,12 +17,12 @@ parameters: type: enum values: 0: Pseudo-inverse with output clipping - 1: Pseudo-inverse with sequential desaturation technique + 1: Pseudo-inverse with metric allocation 2: Automatic - default: 2 + default: 1 # Motor parameters - CA_R_REV: + SC_CA_R_REV: description: short: Bidirectional/Reversible motors long: | @@ -67,7 +42,7 @@ parameters: 10: Motor 11 11: Motor 12 default: 0 - CA_R${i}_SLEW: + SC_CA_R${i}_SLEW: description: short: Motor ${i} slew rate limit long: | @@ -86,7 +61,7 @@ parameters: default: 0.0 # Servo params - CA_SV${i}_SLEW: + SC_CA_SV${i}_SLEW: description: short: Servo ${i} slew rate limit long: | @@ -104,8 +79,8 @@ parameters: default: 0.0 - # (MC) Rotors - CA_ROTOR_COUNT: + # Motors for external disturbances + SC_CA_ROTOR_COUNT: description: short: Total number of rotors type: enum @@ -124,7 +99,7 @@ parameters: 11: '11' 12: '12' default: 0 - CA_ROTOR${i}_PX: + SC_CA_ROTOR${i}_PX: description: short: Position of rotor ${i} along X body axis relative to center of gravity type: float @@ -135,7 +110,7 @@ parameters: min: -100 max: 100 default: 0.0 - CA_ROTOR${i}_PY: + SC_CA_ROTOR${i}_PY: description: short: Position of rotor ${i} along Y body axis relative to center of gravity type: float @@ -146,7 +121,7 @@ parameters: min: -100 max: 100 default: 0.0 - CA_ROTOR${i}_PZ: + SC_CA_ROTOR${i}_PZ: description: short: Position of rotor ${i} along Z body axis relative to center of gravity type: float @@ -158,7 +133,7 @@ parameters: max: 100 default: 0.0 - CA_ROTOR${i}_AX: + SC_CA_ROTOR${i}_AX: description: short: Axis of rotor ${i} thrust vector, X body axis component long: Only the direction is considered (the vector is normalized). @@ -169,7 +144,7 @@ parameters: min: -100 max: 100 default: 0.0 - CA_ROTOR${i}_AY: + SC_CA_ROTOR${i}_AY: description: short: Axis of rotor ${i} thrust vector, Y body axis component long: Only the direction is considered (the vector is normalized). @@ -180,7 +155,7 @@ parameters: min: -100 max: 100 default: 0.0 - CA_ROTOR${i}_AZ: + SC_CA_ROTOR${i}_AZ: description: short: Axis of rotor ${i} thrust vector, Z body axis component long: Only the direction is considered (the vector is normalized). @@ -192,7 +167,7 @@ parameters: max: 100 default: -1.0 - CA_ROTOR${i}_CT: + SC_CA_ROTOR${i}_CT: description: short: Thrust coefficient of rotor ${i} long: | @@ -207,7 +182,7 @@ parameters: max: 100 default: 6.5 - CA_ROTOR${i}_KM: + SC_CA_ROTOR${i}_KM: description: short: Moment coefficient of rotor ${i} long: | @@ -222,7 +197,7 @@ parameters: min: -1 max: 1 default: 0.05 - CA_ROTOR${i}_TILT: + SC_CA_ROTOR${i}_TILT: description: short: Rotor ${i} tilt assignment long: If not set to None, this motor is tilted by the configured tilt servo. @@ -237,10 +212,10 @@ parameters: instance_start: 0 default: 0 - # control surfaces - CA_SV_CS_COUNT: + # (SC) Thrusters + SC_CA_THRUSTER_CNT: description: - short: Total number of Control Surfaces + short: Total number of thrusters type: enum values: 0: '0' @@ -252,330 +227,92 @@ parameters: 6: '6' 7: '7' 8: '8' + 9: '9' + 10: '10' + 11: '11' + 12: '12' default: 0 - CA_SV_CS${i}_TYPE: + SC_CA_THRUSTER${i}_PX: description: - short: Control Surface ${i} type - type: enum - values: - 0: (Not set) - 1: Left Aileron - 2: Right Aileron - 3: Elevator - 4: Rudder - 5: Left Elevon - 6: Right Elevon - 7: Left V-Tail - 8: Right V-Tail - 9: Left Flap - 10: Right Flap - 11: Airbrake - 12: Custom - 13: Left A-tail - 14: Right A-tail - 15: Single Channel Aileron - 16: Steering Wheel - 17: Left Spoiler - 18: Right Spoiler - num_instances: *max_num_servos - instance_start: 0 - default: 0 - - CA_SV_CS${i}_TRQ_R: - description: - short: Control Surface ${i} roll torque scaling + short: Position of thruster ${i} along X body axis type: float decimal: 2 - num_instances: *max_num_servos - instance_start: 0 - default: 0.0 - - CA_SV_CS${i}_TRQ_P: - description: - short: Control Surface ${i} pitch torque scaling - type: float - decimal: 2 - num_instances: *max_num_servos - instance_start: 0 - default: 0.0 - - CA_SV_CS${i}_TRQ_Y: - description: - short: Control Surface ${i} yaw torque scaling - type: float - decimal: 2 - num_instances: *max_num_servos - instance_start: 0 - default: 0.0 - - CA_SV_CS${i}_TRIM: - description: - short: Control Surface ${i} trim - long: Can be used to add an offset to the servo control. - type: float - decimal: 2 - min: -1.0 - max: 1.0 - num_instances: *max_num_servos - instance_start: 0 - default: 0.0 - - CA_SV_CS${i}_FLAP: - description: - short: Control Surface ${i} configuration as flap - type: float - decimal: 2 - min: -1.0 - max: 1.0 - num_instances: *max_num_servos - instance_start: 0 - default: 0 - - CA_SV_CS${i}_SPOIL: - description: - short: Control Surface ${i} configuration as spoiler - type: float - decimal: 2 - min: -1.0 - max: 1.0 - num_instances: *max_num_servos - instance_start: 0 - default: 0 - - # Tilts - CA_SV_TL_COUNT: - description: - short: Total number of Tilt Servos - type: enum - values: - 0: '0' - 1: '1' - 2: '2' - 3: '3' - 4: '4' - default: 0 - CA_SV_TL${i}_CT: - description: - short: Tilt ${i} is used for control - long: Define if this servo is used for additional control. - type: enum # This could be a bitset, but the enum shows up nicer in the UI - values: - 0: 'None' - 1: 'Yaw' - 2: 'Pitch' - 3: 'Yaw and Pitch' - num_instances: *max_num_tilts - instance_start: 0 - default: 1 - CA_SV_TL${i}_MINA: - description: - short: Tilt Servo ${i} Tilt Angle at Minimum - long: | - Defines the tilt angle when the servo is at the minimum. - An angle of zero means upwards. - type: float - decimal: 0 - unit: 'deg' - num_instances: *max_num_tilts - instance_start: 0 - min: -90.0 - max: 90.0 - default: 0.0 - CA_SV_TL${i}_MAXA: - description: - short: Tilt Servo ${i} Tilt Angle at Maximum - long: | - Defines the tilt angle when the servo is at the maximum. - An angle of zero means upwards. - type: float - decimal: 0 - unit: 'deg' - num_instances: *max_num_tilts - instance_start: 0 - min: -90.0 - max: 90.0 - default: 90.0 - CA_SV_TL${i}_TD: - description: - short: Tilt Servo ${i} Tilt Direction - long: | - Defines the direction the servo tilts towards when moving towards the maximum tilt angle. - For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', - the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. - type: enum - values: - 0: 'Towards Front' - 90: 'Towards Right' - min: 0 - max: 359 - num_instances: *max_num_tilts - instance_start: 0 - default: 0 - - # helicopter - CA_SP0_COUNT: - description: - short: Number of swash plates servos - type: enum - values: - 2: '2' - 3: '3' - 4: '4' - default: 3 - CA_SP0_ANG${i}: - description: - short: Angle for swash plate servo ${i} - long: | - The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis). - type: float - decimal: 0 - increment: 10 - unit: deg - num_instances: 4 - min: 0 - max: 360 - default: [0, 140, 220, 0] - CA_SP0_ARM_L${i}: - description: - short: Arm length for swash plate servo ${i} - long: | - This is relative to the other arm lengths. - type: float - decimal: 3 increment: 0.1 - num_instances: 4 - min: 0 - max: 10 - default: 1.0 - CA_HELI_THR_C${i}: + unit: m + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: 0.0 + SC_CA_THRUSTER${i}_PY: description: - short: Throttle curve at position ${i} - long: | - Defines the output throttle at the interval position ${i}. + short: Position of thruster ${i} along Y body axis type: float - decimal: 3 + decimal: 2 increment: 0.1 - num_instances: 5 - min: 0 - max: 1 - default: [1, 1, 1, 1, 1] - CA_HELI_PITCH_C${i}: + unit: m + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: 0.0 + SC_CA_THRUSTER${i}_PZ: description: - short: Collective pitch curve at position ${i} - long: | - Defines the collective pitch at the interval position ${i} for a given thrust setpoint. - - Use negative values if the swash plate needs to move down to provide upwards thrust. + short: Position of thruster ${i} along Z body axis type: float - decimal: 3 + decimal: 2 increment: 0.1 - num_instances: 5 - min: -1 - max: 1 - default: [-0.05, 0.0725, 0.2, 0.325, 0.45] - CA_HELI_YAW_CP_S: - description: - short: Scale for yaw compensation based on collective pitch - long: | - This allows to add a proportional factor of the collective pitch command to the yaw command. - A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. - - tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) - type: float - decimal: 3 - increment: 0.1 - min: -2 - max: 2 - default: 0.0 - CA_HELI_YAW_CP_O: - description: - short: Offset for yaw compensation based on collective pitch - long: | - This allows to specify which collective pitch command results in the least amount of rotor drag. - This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch - by aligning the lowest rotor drag with zero compensation. - For symmetric profile blades this is the command that results in exactly 0° collective blade angle. - For lift profile blades this is typically a command resulting in slightly negative collective blade angle. - - tail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O) - type: float - decimal: 3 - increment: 0.1 - min: -2 - max: 2 - default: 0.0 - CA_HELI_YAW_TH_S: - description: - short: Scale for yaw compensation based on throttle - long: | - This allows to add a proportional factor of the throttle command to the yaw command. - A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. - - tail_output += CA_HELI_YAW_TH_S * throttle - type: float - decimal: 3 - increment: 0.1 - min: -2 - max: 2 - default: 0.0 - CA_HELI_YAW_CCW: - description: - short: Main rotor turns counter-clockwise - long: | - Default configuration is for a clockwise turning main rotor and - positive thrust of the tail rotor is expected to rotate the vehicle clockwise. - Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction - which is mostly the case when the main rotor turns counter-clockwise. - type: boolean - default: 0 - CA_HELI_RPM_SP: - description: - short: Setpoint for main rotor rpm - long: | - Requires rpm feedback for the controller. - type: float - decimal: 0 - increment: 1 - min: 100 - max: 10000 - default: 1500 - CA_HELI_RPM_P: - description: - short: Proportional gain for rpm control - long: | - Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. - - motor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000 - type: float - decimal: 3 - increment: 0.1 - min: 0 - max: 10 - default: 0.0 - CA_HELI_RPM_I: - description: - short: Integral gain for rpm control - long: | - Same definition as the proportional gain but for integral. - type: float - decimal: 3 - increment: 0.1 - min: 0 - max: 10 - default: 0.0 - - # Others - CA_FAILURE_MODE: + unit: m + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: 0.0 + SC_CA_THRUSTER${i}_AX: description: - short: Motor failure handling mode + short: Axis of thruster ${i} thrust vector, X body axis component + long: Only the direction is considered (the vector is normalized). + type: float + decimal: 2 + increment: 0.1 + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: 0.0 + SC_CA_THRUSTER${i}_AY: + description: + short: Axis of thruster ${i} thrust vector, Y body axis component + long: Only the direction is considered (the vector is normalized). + type: float + decimal: 2 + increment: 0.1 + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: 0.0 + SC_CA_THRUSTER${i}_AZ: + description: + short: Axis of thruster ${i} thrust vector, Z body axis component + long: Only the direction is considered (the vector is normalized). + type: float + decimal: 2 + increment: 0.1 + num_instances: *max_num_sc_thrusters + min: -100 + max: 100 + default: -1.0 + + SC_CA_THRUSTER${i}_CT: + description: + short: Thrust coefficient of rotor ${i} long: | - This is used to specify how to handle motor failures - reported by failure detector. - type: enum - values: - 0: Ignore - 1: Remove first failed motor from effectiveness - default: 0 + The thrust coefficient if defined as Thrust = CT * u^2, + where u (with value between actuator minimum and maximum) + is the output signal sent to the motor controller. + type: float + decimal: 1 + increment: 1 + num_instances: *max_num_sc_thrusters + min: 0 + max: 100 + default: 6.5 # Mixer mixer: @@ -587,7 +324,7 @@ mixer: max: 1 default_is_nan: true per_item_parameters: - - name: 'CA_R_REV' + - name: 'SC_CA_R_REV' label: 'Bidirectional' show_as: 'bitset' index_offset: 0 @@ -596,6 +333,12 @@ mixer: label: 'Slew Rate' index_offset: 0 advanced: true + thruster: + functions: 'Thruster' + actuator_testing_values: + min: 0 + max: 1 + default_is_nan: true servo: functions: 'Servo' actuator_testing_values: @@ -603,7 +346,7 @@ mixer: max: 1 default: 0 per_item_parameters: - - name: 'CA_SV${i}_SLEW' + - name: 'SC_CA_SV${i}_SLEW' label: 'Slew Rate' index_offset: 0 advanced: true @@ -753,440 +496,47 @@ mixer: config: param: CA_AIRFRAME types: - 0: # Multirotor - type: 'multirotor' - title: 'Multirotor' + 13: # Spacecraft 2D + type: 'spacecraft_2d' + title: 'Spacecraft 2D' actuators: - - actuator_type: 'motor' - count: 'CA_ROTOR_COUNT' + - actuator_type: 'thruster' + count: 'SC_CA_THRUSTER_CNT' # count would be too long for 16 max size per_item_parameters: standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] + position: [ 'SC_CA_THRUSTER${i}_PX', 'SC_CA_THRUSTER${i}_PY', 'SC_CA_THRUSTER${i}_PZ' ] extra: - - name: 'CA_ROTOR${i}_KM' - label: 'Direction CCW' - function: 'spin-dir' - show_as: 'true-if-positive' - - name: 'CA_ROTOR${i}_AX' + - name: 'SC_CA_THRUSTER${i}_AX' label: 'Axis X' function: 'axisx' advanced: true - - name: 'CA_ROTOR${i}_AY' + - name: 'SC_CA_THRUSTER${i}_AY' label: 'Axis Y' function: 'axisy' advanced: true - - name: 'CA_ROTOR${i}_AZ' + - name: 'SC_CA_THRUSTER${i}_AZ' label: 'Axis Z' function: 'axisz' advanced: true - 1: # Fixed Wing - title: 'Fixed Wing' + 14: # Sapcecraft 3D + title: 'Spacecraft 3D' actuators: - - actuator_type: 'motor' - group_label: 'Motors' - count: 'CA_ROTOR_COUNT' - - actuator_type: 'servo' - group_label: 'Control Surfaces' - count: 'CA_SV_CS_COUNT' - per_item_parameters: - extra: - - name: 'CA_SV_CS${i}_TYPE' - label: 'Type' - function: 'type' - identifier: 'servo-type' - - name: 'CA_SV_CS${i}_TRQ_R' - label: 'Roll Torque' - identifier: 'servo-torque-roll' - - name: 'CA_SV_CS${i}_TRQ_P' - label: 'Pitch Torque' - identifier: 'servo-torque-pitch' - - name: 'CA_SV_CS${i}_TRQ_Y' - label: 'Yaw Torque' - identifier: 'servo-torque-yaw' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - - name: 'CA_SV_CS${i}_FLAP' - label: 'Flaps Scale' - advanced: true - identifier: 'servo-scale-flap' - - name: 'CA_SV_CS${i}_SPOIL' - label: 'Spoiler Scale' - advanced: true - identifier: 'servo-scale-spoiler' - - 2: # Standard VTOL - title: 'Standard VTOL' - actuators: - - actuator_type: 'motor' - group_label: 'Motors' - count: 'CA_ROTOR_COUNT' + - actuator_type: 'thruster' + count: 'SC_CA_THRUSTER_CNT' per_item_parameters: standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] + position: [ 'SC_CA_THRUSTER${i}_PX', 'SC_CA_THRUSTER${i}_PY', 'SC_CA_THRUSTER${i}_PZ' ] extra: - - name: 'CA_ROTOR${i}_KM' - label: 'Direction CCW' - function: 'spin-dir' - show_as: 'true-if-positive' - - name: 'CA_ROTOR${i}_AX' + - name: 'SC_CA_THRUSTER${i}_AX' label: 'Axis X' function: 'axisx' - - name: 'CA_ROTOR${i}_AY' + advanced: true + - name: 'SC_CA_THRUSTER${i}_AY' label: 'Axis Y' function: 'axisy' - - name: 'CA_ROTOR${i}_AZ' + advanced: true + - name: 'SC_CA_THRUSTER${i}_AZ' label: 'Axis Z' function: 'axisz' - - actuator_type: 'servo' - group_label: 'Control Surfaces' - count: 'CA_SV_CS_COUNT' - per_item_parameters: - extra: - - name: 'CA_SV_CS${i}_TYPE' - label: 'Type' - function: 'type' - identifier: 'servo-type' - - name: 'CA_SV_CS${i}_TRQ_R' - label: 'Roll Scale' - identifier: 'servo-torque-roll' - - name: 'CA_SV_CS${i}_TRQ_P' - label: 'Pitch Scale' - identifier: 'servo-torque-pitch' - - name: 'CA_SV_CS${i}_TRQ_Y' - label: 'Yaw Scale' - identifier: 'servo-torque-yaw' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - - name: 'CA_SV_CS${i}_FLAP' - label: 'Flaps Scale' advanced: true - identifier: 'servo-scale-flap' - - name: 'CA_SV_CS${i}_SPOIL' - label: 'Spoiler Scale' - advanced: true - identifier: 'servo-scale-spoiler' - parameters: - - label: 'Lock control surfaces in hover' - name: VT_ELEV_MC_LOCK - - 3: # Tiltrotor VTOL - title: 'Tiltrotor VTOL' - actuators: - - actuator_type: 'motor' - group_label: 'MC Motors' - count: 'CA_ROTOR_COUNT' - per_item_parameters: - standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] - extra: - - name: 'CA_ROTOR${i}_TILT' - label: 'Tilted by' - - name: 'CA_ROTOR${i}_KM' - label: 'Direction CCW' - function: 'spin-dir' - show_as: 'true-if-positive' - - actuator_type: 'servo' - group_label: 'Control Surfaces' - count: 'CA_SV_CS_COUNT' - item_label_prefix: 'Surface ${i}' - per_item_parameters: - extra: - - name: 'CA_SV_CS${i}_TYPE' - label: 'Type' - function: 'type' - identifier: 'servo-type' - - name: 'CA_SV_CS${i}_TRQ_R' - label: 'Roll Scale' - identifier: 'servo-torque-roll' - - name: 'CA_SV_CS${i}_TRQ_P' - label: 'Pitch Scale' - identifier: 'servo-torque-pitch' - - name: 'CA_SV_CS${i}_TRQ_Y' - label: 'Yaw Scale' - identifier: 'servo-torque-yaw' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - - name: 'CA_SV_CS${i}_FLAP' - label: 'Flaps Scale' - advanced: true - identifier: 'servo-scale-flap' - - name: 'CA_SV_CS${i}_SPOIL' - label: 'Spoiler Scale' - advanced: true - identifier: 'servo-scale-spoiler' - parameters: - - label: 'Lock control surfaces in hover' - name: VT_ELEV_MC_LOCK - - actuator_type: 'servo' - group_label: 'Tilt Servos' - count: 'CA_SV_TL_COUNT' - item_label_prefix: 'Tilt ${i}' - per_item_parameters: - extra: - - name: 'CA_SV_TL${i}_MINA' - label: "Angle at Min\nTilt" - - name: 'CA_SV_TL${i}_MAXA' - label: "Angle at Max\nTilt" - - name: 'CA_SV_TL${i}_TD' - label: 'Tilt Direction' - - name: 'CA_SV_TL${i}_CT' - label: 'Use for Control' - - 4: # Tailsitter VTOL - title: 'Tailsitter VTOL' - actuators: - - actuator_type: 'motor' - group_label: 'MC Motors' - count: 'CA_ROTOR_COUNT' - per_item_parameters: - standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] - extra: - - name: 'CA_ROTOR${i}_KM' - label: 'Direction CCW' - function: 'spin-dir' - show_as: 'true-if-positive' - - actuator_type: 'servo' - group_label: 'Control Surfaces' - count: 'CA_SV_CS_COUNT' - item_label_prefix: 'Surface ${i}' - per_item_parameters: - extra: - - name: 'CA_SV_CS${i}_TYPE' - label: 'Type' - function: 'type' - identifier: 'servo-type-tailsitter' - - name: 'CA_SV_CS${i}_TRQ_R' - label: 'Roll Scale' - identifier: 'servo-torque-roll-tailsitter' - - name: 'CA_SV_CS${i}_TRQ_P' - label: 'Pitch Scale' - identifier: 'servo-torque-pitch-tailsitter' - - name: 'CA_SV_CS${i}_TRQ_Y' - label: 'Yaw Scale' - identifier: 'servo-torque-yaw-tailsitter' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - - name: 'CA_SV_CS${i}_FLAP' - label: 'Flaps Scale' - advanced: true - identifier: 'servo-scale-flap' - - name: 'CA_SV_CS${i}_SPOIL' - label: 'Spoiler Scale' - advanced: true - identifier: 'servo-scale-spoiler' - parameters: - - label: 'Lock control surfaces in hover' - name: VT_ELEV_MC_LOCK - - 5: # Rover (Ackermann) - title: 'Rover (Ackermann)' - actuators: - - actuator_type: 'motor' - instances: - - name: 'Throttle' - position: [ -1, 0, 0 ] - - actuator_type: 'servo' - instances: - - name: 'Steering' - position: [ 1, 0, 0 ] - - 6: # Rover (Differential) - title: 'Rover (Differential)' - actuators: - - actuator_type: 'motor' - instances: - - name: 'Right Motor' - position: [ 0, 1, 0 ] - - name: 'Left Motor' - position: [ 0, -1, 0 ] - - 7: # Motors (6DOF) - actuators: - - actuator_type: 'motor' - count: 'CA_ROTOR_COUNT' - per_item_parameters: - standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] - extra: - - name: 'CA_ROTOR${i}_AX' - label: 'Axis X' - function: 'axisx' - - name: 'CA_ROTOR${i}_AY' - label: 'Axis Y' - function: 'axisy' - - name: 'CA_ROTOR${i}_AZ' - label: 'Axis Z' - function: 'axisz' - - name: 'CA_ROTOR${i}_KM' - label: "Moment\nCoefficient" - - 8: # Multirotor with Tilt - title: 'Multirotor with Tilt' - actuators: - - actuator_type: 'motor' - count: 'CA_ROTOR_COUNT' - per_item_parameters: - standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] - extra: - - name: 'CA_ROTOR${i}_KM' - label: 'Direction CCW' - function: 'spin-dir' - show_as: 'true-if-positive' - - name: 'CA_ROTOR${i}_TILT' - label: 'Tilted by' - - actuator_type: 'servo' - group_label: 'Tilt Servos' - count: 'CA_SV_TL_COUNT' - item_label_prefix: 'Tilt ${i}' - per_item_parameters: - extra: - - name: 'CA_SV_TL${i}_MINA' - label: "Angle at Min\nTilt" - - name: 'CA_SV_TL${i}_MAXA' - label: "Angle at Max\nTilt" - - name: 'CA_SV_TL${i}_TD' - label: 'Tilt Direction' - - name: 'CA_SV_TL${i}_CT' - label: 'Use for Control' - - 9: # Custom - actuators: - - actuator_type: 'motor' - group_label: 'Thrust/Motors' - count: 'CA_ROTOR_COUNT' - per_item_parameters: - standard: - position: [ 'CA_ROTOR${i}_PX', 'CA_ROTOR${i}_PY', 'CA_ROTOR${i}_PZ' ] - extra: - - name: 'CA_ROTOR${i}_AX' - label: 'Axis X' - function: 'axisx' - - name: 'CA_ROTOR${i}_AY' - label: 'Axis Y' - function: 'axisy' - - name: 'CA_ROTOR${i}_AZ' - label: 'Axis Z' - function: 'axisz' - - name: 'CA_ROTOR${i}_CT' - label: "Thrust\nCoefficient" - - name: 'CA_ROTOR${i}_KM' - label: "Moment\nCoefficient" - - actuator_type: 'servo' - group_label: 'Torque' - count: 'CA_SV_CS_COUNT' - item_label_prefix: 'Torque ${i}' - per_item_parameters: - extra: - - name: 'CA_SV_CS${i}_TRQ_R' - label: 'Roll Scale' - - name: 'CA_SV_CS${i}_TRQ_P' - label: 'Pitch Scale' - - name: 'CA_SV_CS${i}_TRQ_Y' - label: 'Yaw Scale' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - - name: 'CA_SV_CS${i}_FLAP' - label: 'Flaps Scale' - advanced: true - identifier: 'servo-scale-flap' - - name: 'CA_SV_CS${i}_SPOIL' - label: 'Spoiler Scale' - advanced: true - identifier: 'servo-scale-spoiler' - - 10: # Helicopter (tail ESC) - actuators: - - actuator_type: 'motor' - count: 1 - item_label_prefix: ['Rotor'] - - actuator_type: 'motor' - item_label_prefix: ['Yaw tail Motor'] - count: 1 - - actuator_type: 'servo' - group_label: 'Swash plate servos' - count: 'CA_SP0_COUNT' - per_item_parameters: - extra: - - name: 'CA_SP0_ANG${i}' - label: 'Angle' - - name: 'CA_SP0_ARM_L${i}' - label: 'Arm Length (relative)' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - parameters: - - label: 'Collective pitch offset to align least amount of rotor drag' - name: CA_HELI_YAW_CP_O - - label: 'Yaw compensation scale based on collective pitch' - name: CA_HELI_YAW_CP_S - - label: 'Yaw compensation scale based on throttle' - name: CA_HELI_YAW_TH_S - - label: 'Main rotor turns counter-clockwise' - name: CA_HELI_YAW_CCW - - label: 'Throttle spoolup time' - name: COM_SPOOLUP_TIME - - 11: # Helicopter (tail Servo) - actuators: - - actuator_type: 'motor' - count: 1 - item_label_prefix: ['Rotor'] - - actuator_type: 'servo' - item_label_prefix: ['Yaw tail Servo'] - count: 1 - - actuator_type: 'servo' - group_label: 'Swash plate servos' - count: 'CA_SP0_COUNT' - per_item_parameters: - extra: - - name: 'CA_SP0_ANG${i}' - label: 'Angle' - - name: 'CA_SP0_ARM_L${i}' - label: 'Arm Length (relative)' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - parameters: - - label: 'Yaw compensation scale based on collective pitch' - name: CA_HELI_YAW_CP_S - - label: 'Yaw compensation scale based on throttle' - name: CA_HELI_YAW_TH_S - - label: 'Main rotor turns counter-clockwise' - name: CA_HELI_YAW_CCW - - label: 'Throttle spoolup time' - name: COM_SPOOLUP_TIME - - 12: # Helicopter (Coaxial) - actuators: - - actuator_type: 'motor' - count: 2 - item_label_prefix: ['Clockwise Rotor', 'Counter-clockwise Rotor'] - - actuator_type: 'servo' - group_label: 'Swash plate servos' - count: 'CA_SP0_COUNT' - per_item_parameters: - extra: - - name: 'CA_SP0_ANG${i}' - label: 'Angle' - - name: 'CA_SP0_ARM_L${i}' - label: 'Arm Length (relative)' - - name: 'CA_SV_CS${i}_TRIM' - label: 'Trim' - parameters: - - label: 'Throttle spoolup time' - name: COM_SPOOLUP_TIME - - 13: # Rover (Mecanum) - title: 'Rover (Mecanum)' - actuators: - - actuator_type: 'motor' - instances: - - name: 'Right Motor Front' - position: [ 1, 1, 0 ] - - name: 'Left Motor Front' - position: [ 1, -1, 0 ] - - name: 'Right Motor Back' - position: [ -1, 1, 0 ] - - name: 'Left Motor Back' - position: [ -1, -1, 0 ]