|
|
@ -81,6 +81,14 @@ const unsigned mode_flag_custom = 1; |
|
|
|
|
|
|
|
|
|
|
|
using namespace time_literals; |
|
|
|
using namespace time_literals; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Simulator::Simulator() |
|
|
|
|
|
|
|
: ModuleParams(nullptr) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
int32_t sys_ctrl_alloc = 0; |
|
|
|
|
|
|
|
param_get(param_find("SYS_CTRL_ALLOC"), &sys_ctrl_alloc); |
|
|
|
|
|
|
|
_use_dynamic_mixing = sys_ctrl_alloc >= 1; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t *msg) |
|
|
|
void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t *msg) |
|
|
|
{ |
|
|
|
{ |
|
|
|
memset(msg, 0, sizeof(mavlink_hil_actuator_controls_t)); |
|
|
|
memset(msg, 0, sizeof(mavlink_hil_actuator_controls_t)); |
|
|
@ -91,88 +99,96 @@ void Simulator::actuator_controls_from_outputs(mavlink_hil_actuator_controls_t * |
|
|
|
|
|
|
|
|
|
|
|
int _system_type = _param_mav_type.get(); |
|
|
|
int _system_type = _param_mav_type.get(); |
|
|
|
|
|
|
|
|
|
|
|
/* 'pos_thrust_motors_count' indicates number of motor channels which are configured with 0..1 range (positive thrust)
|
|
|
|
if (_use_dynamic_mixing) { |
|
|
|
all other motors are configured for -1..1 range */ |
|
|
|
if (armed) { |
|
|
|
unsigned pos_thrust_motors_count; |
|
|
|
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) { |
|
|
|
bool is_fixed_wing; |
|
|
|
msg->controls[i] = _actuator_outputs.output[i]; |
|
|
|
|
|
|
|
} |
|
|
|
switch (_system_type) { |
|
|
|
} |
|
|
|
case MAV_TYPE_AIRSHIP: |
|
|
|
|
|
|
|
case MAV_TYPE_VTOL_DUOROTOR: |
|
|
|
|
|
|
|
case MAV_TYPE_COAXIAL: |
|
|
|
|
|
|
|
pos_thrust_motors_count = 2; |
|
|
|
|
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_TRICOPTER: |
|
|
|
} else { |
|
|
|
pos_thrust_motors_count = 3; |
|
|
|
/* 'pos_thrust_motors_count' indicates number of motor channels which are configured with 0..1 range (positive thrust)
|
|
|
|
is_fixed_wing = false; |
|
|
|
all other motors are configured for -1..1 range */ |
|
|
|
break; |
|
|
|
unsigned pos_thrust_motors_count; |
|
|
|
|
|
|
|
bool is_fixed_wing; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
switch (_system_type) { |
|
|
|
|
|
|
|
case MAV_TYPE_AIRSHIP: |
|
|
|
|
|
|
|
case MAV_TYPE_VTOL_DUOROTOR: |
|
|
|
|
|
|
|
case MAV_TYPE_COAXIAL: |
|
|
|
|
|
|
|
pos_thrust_motors_count = 2; |
|
|
|
|
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
case MAV_TYPE_TRICOPTER: |
|
|
|
case MAV_TYPE_VTOL_QUADROTOR: |
|
|
|
pos_thrust_motors_count = 3; |
|
|
|
case MAV_TYPE_VTOL_TILTROTOR: |
|
|
|
is_fixed_wing = false; |
|
|
|
pos_thrust_motors_count = 4; |
|
|
|
break; |
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_VTOL_RESERVED2: |
|
|
|
case MAV_TYPE_QUADROTOR: |
|
|
|
pos_thrust_motors_count = 5; |
|
|
|
case MAV_TYPE_VTOL_QUADROTOR: |
|
|
|
is_fixed_wing = false; |
|
|
|
case MAV_TYPE_VTOL_TILTROTOR: |
|
|
|
break; |
|
|
|
pos_thrust_motors_count = 4; |
|
|
|
|
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_HEXAROTOR: |
|
|
|
case MAV_TYPE_VTOL_RESERVED2: |
|
|
|
pos_thrust_motors_count = 6; |
|
|
|
pos_thrust_motors_count = 5; |
|
|
|
is_fixed_wing = false; |
|
|
|
is_fixed_wing = false; |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_VTOL_RESERVED3: |
|
|
|
case MAV_TYPE_HEXAROTOR: |
|
|
|
// this is the tricopter VTOL / quad plane with 3 motors and 2 servos
|
|
|
|
pos_thrust_motors_count = 6; |
|
|
|
pos_thrust_motors_count = 3; |
|
|
|
is_fixed_wing = false; |
|
|
|
is_fixed_wing = false; |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_OCTOROTOR: |
|
|
|
case MAV_TYPE_VTOL_RESERVED3: |
|
|
|
pos_thrust_motors_count = 8; |
|
|
|
// this is the tricopter VTOL / quad plane with 3 motors and 2 servos
|
|
|
|
is_fixed_wing = false; |
|
|
|
pos_thrust_motors_count = 3; |
|
|
|
break; |
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_SUBMARINE: |
|
|
|
case MAV_TYPE_OCTOROTOR: |
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
pos_thrust_motors_count = 8; |
|
|
|
is_fixed_wing = false; |
|
|
|
is_fixed_wing = false; |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
case MAV_TYPE_FIXED_WING: |
|
|
|
case MAV_TYPE_SUBMARINE: |
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
is_fixed_wing = true; |
|
|
|
is_fixed_wing = false; |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
case MAV_TYPE_FIXED_WING: |
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
is_fixed_wing = false; |
|
|
|
is_fixed_wing = true; |
|
|
|
break; |
|
|
|
break; |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
|
|
|
pos_thrust_motors_count = 0; |
|
|
|
|
|
|
|
is_fixed_wing = false; |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) { |
|
|
|
for (unsigned i = 0; i < actuator_outputs_s::NUM_ACTUATOR_OUTPUTS; i++) { |
|
|
|
if (!armed) { |
|
|
|
if (!armed) { |
|
|
|
/* send 0 when disarmed and for disabled channels */ |
|
|
|
/* send 0 when disarmed and for disabled channels */ |
|
|
|
msg->controls[i] = 0.0f; |
|
|
|
msg->controls[i] = 0.0f; |
|
|
|
|
|
|
|
|
|
|
|
} else if ((is_fixed_wing && i == 4) || |
|
|
|
} else if ((is_fixed_wing && i == 4) || |
|
|
|
(!is_fixed_wing && i < pos_thrust_motors_count)) { //multirotor, rotor channel
|
|
|
|
(!is_fixed_wing && i < pos_thrust_motors_count)) { //multirotor, rotor channel
|
|
|
|
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to 0..1 for rotors */ |
|
|
|
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to 0..1 for rotors */ |
|
|
|
msg->controls[i] = (_actuator_outputs.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN); |
|
|
|
msg->controls[i] = (_actuator_outputs.output[i] - PWM_DEFAULT_MIN) / (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN); |
|
|
|
msg->controls[i] = math::constrain(msg->controls[i], 0.f, 1.f); |
|
|
|
msg->controls[i] = math::constrain(msg->controls[i], 0.f, 1.f); |
|
|
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
} else { |
|
|
|
const float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2; |
|
|
|
const float pwm_center = (PWM_DEFAULT_MAX + PWM_DEFAULT_MIN) / 2; |
|
|
|
const float pwm_delta = (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2; |
|
|
|
const float pwm_delta = (PWM_DEFAULT_MAX - PWM_DEFAULT_MIN) / 2; |
|
|
|
|
|
|
|
|
|
|
|
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to -1..1 for other channels */ |
|
|
|
/* scale PWM out PWM_DEFAULT_MIN..PWM_DEFAULT_MAX us to -1..1 for other channels */ |
|
|
|
msg->controls[i] = (_actuator_outputs.output[i] - pwm_center) / pwm_delta; |
|
|
|
msg->controls[i] = (_actuator_outputs.output[i] - pwm_center) / pwm_delta; |
|
|
|
msg->controls[i] = math::constrain(msg->controls[i], -1.f, 1.f); |
|
|
|
msg->controls[i] = math::constrain(msg->controls[i], -1.f, 1.f); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
msg->mode = mode_flag_custom; |
|
|
|
msg->mode = mode_flag_custom; |
|
|
@ -694,7 +710,12 @@ void Simulator::send() |
|
|
|
|
|
|
|
|
|
|
|
// Subscribe to topics.
|
|
|
|
// Subscribe to topics.
|
|
|
|
// Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS.
|
|
|
|
// Only subscribe to the first actuator_outputs to fill a single HIL_ACTUATOR_CONTROLS.
|
|
|
|
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0); |
|
|
|
if (_use_dynamic_mixing) { |
|
|
|
|
|
|
|
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs_sim), 0); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
|
|
|
_actuator_outputs_sub = orb_subscribe_multi(ORB_ID(actuator_outputs), 0); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// Before starting, we ought to send a heartbeat to initiate the SITL
|
|
|
|
// Before starting, we ought to send a heartbeat to initiate the SITL
|
|
|
|
// simulator to start sending sensor data which will set the time and
|
|
|
|
// simulator to start sending sensor data which will set the time and
|
|
|
|