Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow more than 4 MC motors in VTOL Simulator #12166

Closed
wants to merge 4 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/1040_standard_vtol
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ then
param set VT_F_TRANS_DUR 5
param set VT_F_TRANS_THR 0.75
param set VT_ARSP_TRANS 16
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_TYPE 2

param set WEST_EN 1
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/1041_tailsitter
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ then

param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.7
param set VT_MOT_COUNT 0
param set VT_MC_MOT_COUNT 0
param set VT_TYPE 0

param set WEST_EN 1
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d-posix/1042_tiltrotor
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ then

param set VT_F_TRANS_DUR 1.5
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
param set VT_ELEV_MC_LOCK 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ then
param set SYS_RESTART_TYPE 2

param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_TYPE 2

# Indicate that FW roll direction was fixed in mixer, to be removed in v1.10
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ then
param set PWM_RATE 400

param set VT_TYPE 2
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4

# Indicate that FW roll direction was fixed in mixer, to be removed in v1.10
param set V19_VT_ROLLDIR 0
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ then

param set VT_IDLE_PWM_MC 1080
param set VT_ELEV_MC_LOCK 0
param set VT_MOT_COUNT 2
param set VT_MC_MOT_COUNT 2
param set VT_TYPE 0

# Indicate that FW roll direction was fixed in mixer, to be removed in v1.10
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13002_firefly6
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ then

param set VT_FW_MOT_OFFID 34
param set VT_IDLE_PWM_MC 1080
param set VT_MOT_COUNT 6
param set VT_MC_MOT_COUNT 6
param set VT_TILT_MC 0.08
param set VT_TILT_TRANS 0.5
param set VT_TILT_FW 0.9
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ then
param set PWM_MAX 2000
param set PWM_RATE 400

param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 0
param set VT_ELEV_MC_LOCK 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ then
param set PWM_MAX 2000
param set PWM_RATE 400

param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 0
param set VT_ELEV_MC_LOCK 1
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ then
param set VT_ARSP_BLEND 6
param set VT_ARSP_TRANS 12
param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 2

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ then
param set PWM_AUX_DIS3 950
param set PWM_RATE 400

param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_F_TRANS_THR 0.75
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 2
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ then
param set PWM_RATE 400

param set VT_F_TRANS_THR 0.75
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_IDLE_PWM_MC 1080
param set VT_TYPE 2

Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ then
param set VT_B_TRANS_DUR 4
param set VT_F_TRANS_THR 0.75
param set VT_IDLE_PWM_MC 1080
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_TYPE 2

# Indicate that FW roll direction was fixed in mixer, to be removed in v1.10
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ then
param set VT_B_TRANS_DUR 4
param set VT_F_TRANS_THR 0.6
param set VT_IDLE_PWM_MC 1180
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_TRANS_MIN_TM 5
param set VT_TRANS_TIMEOUT 30
param set VT_TYPE 2
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13010_claire
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ then
param set PWM_MAX 2000
param set PWM_RATE 400

param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_FW_MOT_OFFID 13
param set VT_IDLE_PWM_MC 1080
param set VT_TILT_FW 0.9
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13012_convergence
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ then
param set VT_FW_MOT_OFFID 3
param set VT_FW_PERM_STAB 0
param set VT_IDLE_PWM_MC 1200
param set VT_MOT_COUNT 3
param set VT_MC_MOT_COUNT 3
param set VT_TILT_FW 1
param set VT_TILT_MC 0
param set VT_TILT_TRANS 0.45
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ then
param set SER_TEL2_BAUD 57600

param set VT_TYPE 2
param set VT_MOT_COUNT 4
param set VT_MC_MOT_COUNT 4
param set VT_F_TRANS_THR 1
param set VT_DWN_PITCH_MAX 8
param set VT_FW_QC_P 55
Expand Down
2 changes: 1 addition & 1 deletion ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ then
param set VT_F_TRANS_THR 0.85
param set VT_F_TR_OL_TM 7
param set VT_IDLE_PWM_MC 1000
param set VT_MOT_COUNT 8
param set VT_MC_MOT_COUNT 8
param set VT_PSHER_RMP_DT 2
param set VT_TRANS_MIN_TM 6
param set VT_TYPE 2
Expand Down
28 changes: 26 additions & 2 deletions src/modules/mavlink/mavlink_messages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2961,12 +2961,29 @@ class MavlinkStreamHILActuatorControls : public MavlinkStream
MavlinkStreamHILActuatorControls(MavlinkStreamHILActuatorControls &) = delete;
MavlinkStreamHILActuatorControls &operator = (const MavlinkStreamHILActuatorControls &) = delete;

int32_t _param_vtol_mc_mot_count_val;
int32_t _param_vtol_fw_mot_count_val;

protected:
explicit MavlinkStreamHILActuatorControls(Mavlink *mavlink) : MavlinkStream(mavlink),
_status_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_status))),
_act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_outputs))),
_act_time(0)
{}
{
param_t ph;

ph = param_find_no_notification("VT_MC_MOT_COUNT");

if (ph == PARAM_INVALID || param_get(ph, &_param_vtol_mc_mot_count_val) != PX4_OK) {
_param_vtol_mc_mot_count_val = 0;
}

ph = param_find_no_notification("VT_FW_MOT_COUNT");

if (ph == PARAM_INVALID || param_get(ph, &_param_vtol_fw_mot_count_val) != PX4_OK) {
_param_vtol_fw_mot_count_val = 1;
}
}

bool send(const hrt_abstime t)
{
Expand Down Expand Up @@ -2995,7 +3012,8 @@ class MavlinkStreamHILActuatorControls : public MavlinkStream
system_type == MAV_TYPE_OCTOROTOR ||
system_type == MAV_TYPE_VTOL_DUOROTOR ||
system_type == MAV_TYPE_VTOL_QUADROTOR ||
system_type == MAV_TYPE_VTOL_RESERVED2) {
system_type == MAV_TYPE_VTOL_RESERVED2 ||
system_type == MAV_TYPE_VTOL_RESERVED3) {

/* multirotors: set number of rotor outputs depending on type */

Expand All @@ -3022,6 +3040,12 @@ class MavlinkStreamHILActuatorControls : public MavlinkStream
n = 8;
break;

case MAV_TYPE_VTOL_RESERVED3:
// this is the nonstandard VTOL plane with one or more push / pull propellers
n = _param_vtol_mc_mot_count_val;
n += _param_vtol_fw_mot_count_val;
break;

default:
n = 8;
break;
Expand Down
4 changes: 3 additions & 1 deletion src/modules/simulator/simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,9 @@ class Simulator : public ModuleParams
(ParamFloat<px4::params::SIM_BAT_DRAIN>) _param_sim_bat_drain, ///< battery drain interval
(ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
(ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
(ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id
(ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id,
(ParamInt<px4::params::VT_MC_MOT_COUNT>) _param_vtol_mc_mot_count,
(ParamInt<px4::params::VT_FW_MOT_COUNT>) _param_vtol_fw_mot_count
)

#endif
Expand Down
9 changes: 8 additions & 1 deletion src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,8 @@ mavlink_hil_actuator_controls_t Simulator::actuator_controls_from_outputs(const
_system_type == MAV_TYPE_VTOL_DUOROTOR ||
_system_type == MAV_TYPE_VTOL_QUADROTOR ||
_system_type == MAV_TYPE_VTOL_TILTROTOR ||
_system_type == MAV_TYPE_VTOL_RESERVED2) {
_system_type == MAV_TYPE_VTOL_RESERVED2 ||
_system_type == MAV_TYPE_VTOL_RESERVED3) {

/* multirotors: set number of rotor outputs depending on type */

Expand All @@ -116,6 +117,12 @@ mavlink_hil_actuator_controls_t Simulator::actuator_controls_from_outputs(const
n = 5;
break;

case MAV_TYPE_VTOL_RESERVED3:
// this is the nonstandard VTOL plane with one or more push / pull propellers
n = _param_vtol_mc_mot_count.get();
n += _param_vtol_fw_mot_count.get();
break;

case MAV_TYPE_HEXAROTOR:
n = 6;
break;
Expand Down
6 changes: 3 additions & 3 deletions src/modules/vtol_att_control/vtol_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,10 +62,10 @@ VtolAttitudeControl::VtolAttitudeControl()
_vtol_vehicle_status.vtol_in_rw_mode = true; /* start vtol in rotary wing mode*/

_params.idle_pwm_mc = PWM_DEFAULT_MIN;
_params.vtol_motor_count = 0;
_params.vtol_mc_motor_count = 0;

_params_handles.idle_pwm_mc = param_find("VT_IDLE_PWM_MC");
_params_handles.vtol_motor_count = param_find("VT_MOT_COUNT");
_params_handles.vtol_mc_motor_count = param_find("VT_MC_MOT_COUNT");
_params_handles.vtol_fw_permanent_stab = param_find("VT_FW_PERM_STAB");
_params_handles.vtol_type = param_find("VT_TYPE");
_params_handles.elevons_mc_lock = param_find("VT_ELEV_MC_LOCK");
Expand Down Expand Up @@ -438,7 +438,7 @@ VtolAttitudeControl::parameters_update()
param_get(_params_handles.idle_pwm_mc, &_params.idle_pwm_mc);

/* vtol motor count */
param_get(_params_handles.vtol_motor_count, &_params.vtol_motor_count);
param_get(_params_handles.vtol_mc_motor_count, &_params.vtol_mc_motor_count);

/* vtol fw permanent stabilization */
param_get(_params_handles.vtol_fw_permanent_stab, &l);
Expand Down
2 changes: 1 addition & 1 deletion src/modules/vtol_att_control/vtol_att_control_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ class VtolAttitudeControl

struct {
param_t idle_pwm_mc;
param_t vtol_motor_count;
param_t vtol_mc_motor_count;
param_t vtol_fw_permanent_stab;
param_t vtol_type;
param_t elevons_mc_lock;
Expand Down
15 changes: 13 additions & 2 deletions src/modules/vtol_att_control/vtol_att_control_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,26 @@
*/

/**
* VTOL number of engines
* VTOL number of engines when in multicopter mode
*
* @min 0
* @max 8
* @increment 1
* @decimal 0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_MOT_COUNT, 0);
PARAM_DEFINE_INT32(VT_MC_MOT_COUNT, 0);

/**
* VTOL number of push / pull engines
*
* @min 1
* @max 8
* @increment 1
* @decimal 0
* @group VTOL Attitude Control
*/
PARAM_DEFINE_INT32(VT_FW_MOT_COUNT, 1);

/**
* Idle speed of VTOL when in multicopter mode
Expand Down
16 changes: 8 additions & 8 deletions src/modules/vtol_att_control/vtol_type.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,7 @@ bool VtolType::set_idle_mc()
struct pwm_output_values pwm_values;
memset(&pwm_values, 0, sizeof(pwm_values));

for (int i = 0; i < _params->vtol_motor_count; i++) {
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
if (is_motor_off_channel(i)) {
pwm_values.values[i] = pwm_value;

Expand All @@ -268,7 +268,7 @@ bool VtolType::set_idle_fw()

memset(&pwm_values, 0, sizeof(pwm_values));

for (int i = 0; i < _params->vtol_motor_count; i++) {
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
if (is_motor_off_channel(i)) {
pwm_values.values[i] = PWM_MOTOR_OFF;

Expand Down Expand Up @@ -315,10 +315,10 @@ bool VtolType::apply_pwm_limits(struct pwm_output_values &pwm_values, pwm_limit_
motor_state VtolType::set_motor_state(const motor_state current_state, const motor_state next_state, const int value)
{
struct pwm_output_values pwm_values = {};
pwm_values.channel_count = _params->vtol_motor_count;
pwm_values.channel_count = _params->vtol_mc_motor_count;

// per default all motors are running
for (int i = 0; i < _params->vtol_motor_count; i++) {
// per default all mc mode motors are running
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
pwm_values.values[i] = _max_mc_pwm_values.values[i];
}

Expand All @@ -327,7 +327,7 @@ motor_state VtolType::set_motor_state(const motor_state current_state, const mot
break;

case motor_state::DISABLED:
for (int i = 0; i < _params->vtol_motor_count; i++) {
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
if (is_motor_off_channel(i)) {
pwm_values.values[i] = _disarmed_pwm_values.values[i];
}
Expand All @@ -337,7 +337,7 @@ motor_state VtolType::set_motor_state(const motor_state current_state, const mot

case motor_state::IDLE:

for (int i = 0; i < _params->vtol_motor_count; i++) {
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
if (is_motor_off_channel(i)) {
pwm_values.values[i] = _params->idle_pwm_mc;
}
Expand All @@ -346,7 +346,7 @@ motor_state VtolType::set_motor_state(const motor_state current_state, const mot
break;

case motor_state::VALUE:
for (int i = 0; i < _params->vtol_motor_count; i++) {
for (int i = 0; i < _params->vtol_mc_motor_count; i++) {
if (is_motor_off_channel(i)) {
pwm_values.values[i] = value;
}
Expand Down
2 changes: 1 addition & 1 deletion src/modules/vtol_att_control/vtol_type.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@

struct Params {
int32_t idle_pwm_mc; // pwm value for idle in mc mode
int32_t vtol_motor_count; // number of motors
int32_t vtol_mc_motor_count; // number of motors in mc mode
int32_t vtol_type;
bool elevons_mc_lock; // lock elevons in multicopter mode
float fw_min_alt; // minimum relative altitude for FW mode (QuadChute)
Expand Down