|
|
|
@ -94,6 +94,7 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
@@ -94,6 +94,7 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
|
|
|
|
|
_system_type == MAV_TYPE_OCTOROTOR || |
|
|
|
|
_system_type == MAV_TYPE_VTOL_DUOROTOR || |
|
|
|
|
_system_type == MAV_TYPE_VTOL_QUADROTOR || |
|
|
|
|
_system_type == MAV_TYPE_VTOL_TILTROTOR || |
|
|
|
|
_system_type == MAV_TYPE_VTOL_RESERVED2) { |
|
|
|
|
|
|
|
|
|
/* multirotors: set number of rotor outputs depending on type */ |
|
|
|
@ -101,19 +102,13 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
@@ -101,19 +102,13 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
|
|
|
|
|
unsigned n; |
|
|
|
|
|
|
|
|
|
switch (_system_type) { |
|
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
|
n = 4; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_TYPE_HEXAROTOR: |
|
|
|
|
n = 6; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_TYPE_VTOL_DUOROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_DUOROTOR: |
|
|
|
|
n = 2; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_QUADROTOR: |
|
|
|
|
case MAV_TYPE_VTOL_TILTROTOR: |
|
|
|
|
n = 4; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
@ -122,6 +117,10 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
@@ -122,6 +117,10 @@ void Simulator::pack_actuator_message(mavlink_hil_actuator_controls_t &msg, unsi
|
|
|
|
|
n = 5; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_TYPE_HEXAROTOR: |
|
|
|
|
n = 6; |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
n = 8; |
|
|
|
|
break; |
|
|
|
|