Browse Source

use actuator_controls[8] for collective tilt for tiltrotor VTOL, instead of [4]

[4] is reserved for Flaps, so also having the tilt on it was preventing us from
using flaps on tiltrotors, and other ripple effects.
By using [8] the tilt is separated from all other channels - it requires to increase the size of
actuator_controls by 1 to 9.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
main
Silvan Fuhrer 3 years ago
parent
commit
21a2892f47
  1. 8
      ROMFS/px4fmu_common/mixers-sitl/tiltrotor_sitl.main.mix
  2. 2
      ROMFS/px4fmu_common/mixers/claire.aux.mix
  3. 2
      ROMFS/px4fmu_common/mixers/firefly6.aux.mix
  4. 8
      ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix
  5. 4
      ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix
  6. 4
      ROMFS/px4fmu_test/mixers/vtol2_test.mix
  7. 4
      ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix
  8. 3
      msg/actuator_controls.msg
  9. 5
      msg/vehicle_attitude_setpoint.msg
  10. 2
      src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  11. 2
      src/modules/vtol_att_control/tiltrotor.cpp

8
ROMFS/px4fmu_common/mixers-sitl/tiltrotor_sitl.main.mix

@ -8,22 +8,22 @@ R: 4x @@ -8,22 +8,22 @@ R: 4x
# tilt servo motor 1
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 2
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 3
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# tilt servo motor 4
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 1

2
ROMFS/px4fmu_common/mixers/claire.aux.mix

@ -10,7 +10,7 @@ Tilt mechanism servo mixer @@ -10,7 +10,7 @@ Tilt mechanism servo mixer
M: 1
S: 1 4 10000 10000 0 -10000 10000
S: 1 8 10000 10000 0 -10000 10000

2
ROMFS/px4fmu_common/mixers/firefly6.aux.mix

@ -6,7 +6,7 @@ @@ -6,7 +6,7 @@
Tilt mechanism servo mixer
---------------------------
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
Elevon mixers
-------------

8
ROMFS/px4fmu_common/mixers/vtol_TTTTAAER.aux.mix

@ -6,19 +6,19 @@ @@ -6,19 +6,19 @@
---------------------------
# front left up:2000 down:1000
M: 1
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
# front right up:1000 down:2000
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# rear left up:2000 down:1000
M: 1
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
# rear right up:1000 down:2000
M: 1
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
# Aileron mixer

4
ROMFS/px4fmu_common/mixers/vtol_convergence.main.mix

@ -10,12 +10,12 @@ Tilt mechanism servo mixer @@ -10,12 +10,12 @@ Tilt mechanism servo mixer
---------------------------
#RIGHT up:2000 down:1000
M: 2
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers

4
ROMFS/px4fmu_test/mixers/vtol2_test.mix

@ -10,13 +10,13 @@ Tilt mechanism servo mixer @@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 -20000 9000 -10000 10000
S: 1 8 0 -20000 9000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
Elevon mixers

4
ROMFS/px4fmu_test/mixers/vtol_convergence.main.mix

@ -10,13 +10,13 @@ Tilt mechanism servo mixer @@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers

3
msg/actuator_controls.msg

@ -11,6 +11,7 @@ uint8 INDEX_AIRBRAKES = 6 @@ -11,6 +11,7 @@ uint8 INDEX_AIRBRAKES = 6
uint8 INDEX_LANDING_GEAR = 7
uint8 INDEX_GIMBAL_SHUTTER = 3
uint8 INDEX_CAMERA_ZOOM = 4
uint8 INDEX_COLLECTIVE_TILT = 8
uint8 GROUP_INDEX_ATTITUDE = 0
uint8 GROUP_INDEX_ATTITUDE_ALTERNATE = 1
@ -19,7 +20,7 @@ uint8 GROUP_INDEX_MANUAL_PASSTHROUGH = 3 @@ -19,7 +20,7 @@ uint8 GROUP_INDEX_MANUAL_PASSTHROUGH = 3
uint8 GROUP_INDEX_PAYLOAD = 6
uint64 timestamp_sample # the timestamp the data this control response is based on was sampled
float32[8] control
float32[9] control
# TOPICS actuator_controls actuator_controls_0 actuator_controls_1 actuator_controls_2 actuator_controls_3
# TOPICS actuator_controls_virtual_fw actuator_controls_virtual_mc

5
msg/vehicle_attitude_setpoint.msg

@ -24,4 +24,9 @@ uint8 FLAPS_OFF = 0 # no flaps @@ -24,4 +24,9 @@ uint8 FLAPS_OFF = 0 # no flaps
uint8 FLAPS_LAND = 1 # landing config flaps
uint8 FLAPS_TAKEOFF = 2 # take-off config flaps
uint8 apply_spoilers # spoiler config specifier
uint8 SPOILERS_OFF = 0 # no spoilers
uint8 SPOILERS_LAND = 1 # landing config spoiler
uint8 SPOILERS_DESCEND = 2 # descend config spoiler
# TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint

2
src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp

@ -109,7 +109,7 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo @@ -109,7 +109,7 @@ void ActuatorEffectivenessTiltrotorVTOL::updateSetpoint(const matrix::Vector<flo
actuator_controls_s actuator_controls_1;
if (_actuator_controls_1_sub.copy(&actuator_controls_1)) {
float control_tilt = actuator_controls_1.control[4] * 2.f - 1.f;
float control_tilt = actuator_controls_1.control[actuator_controls_s::INDEX_COLLECTIVE_TILT] * 2.f - 1.f;
// set control_tilt to exactly -1 or 1 if close to these end points
control_tilt = control_tilt < -0.99f ? -1.f : control_tilt;

2
src/modules/vtol_att_control/tiltrotor.cpp

@ -531,7 +531,7 @@ void Tiltrotor::fill_actuator_outputs() @@ -531,7 +531,7 @@ void Tiltrotor::fill_actuator_outputs()
}
// Fixed wing output
fw_out[4] = _tilt_control;
fw_out[actuator_controls_s::INDEX_COLLECTIVE_TILT] = _tilt_control;
if (_params->elevons_mc_lock && _vtol_schedule.flight_mode == vtol_mode::MC_MODE) {
fw_out[actuator_controls_s::INDEX_ROLL] = 0;

Loading…
Cancel
Save