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

Pr tiltrotor sim #8936

Merged
merged 8 commits into from
Feb 22, 2018
Merged
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
41 changes: 41 additions & 0 deletions ROMFS/sitl/mixers/tiltrotor_sitl.main.mix
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
Mixer for quad tiltrotor (x motor configuration)
================================================

This file defines a single mixer for a tiltrotor (SITL gazebo) with motors in X configuration. The plane has two ailerons and one elevator.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add as a generic tiltrotor mixer?


R: 4x 10000 10000 10000 0

# tilt servo motor 1
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 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

# tilt servo motor 3
M: 1
O: 10000 10000 0 -10000 10000
S: 1 4 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

# mixer for the left aileron
M: 1
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000

# mixer for the right aileron
M: 1
O: 10000 10000 0 -10000 10000
S: 1 0 -10000 -10000 0 -10000 10000

# mixer for the elevator
M: 1
O: 10000 10000 0 -10000 10000
S: 1 1 10000 10000 0 -10000 10000
2 changes: 1 addition & 1 deletion Tools/sitl_gazebo
2 changes: 1 addition & 1 deletion platforms/posix/cmake/sitl_target.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ ExternalProject_Add_Step(sitl_gazebo forceconfigure
# create targets for each viewer/model/debugger combination
set(viewers none jmavsim gazebo replay)
set(debuggers none ide gdb lldb ddd valgrind callgrind)
set(models none iris iris_opt_flow iris_rplidar iris_irlock standard_vtol plane solo tailsitter typhoon_h480 rover hippocampus)
set(models none iris iris_opt_flow iris_rplidar iris_irlock standard_vtol plane solo tailsitter typhoon_h480 rover hippocampus tiltrotor)
set(all_posix_vmd_make_targets)
foreach(viewer ${viewers})
foreach(debugger ${debuggers})
Expand Down
99 changes: 99 additions & 0 deletions posix-configs/SITL/init/ekf2/tiltrotor
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
uorb start
param load
dataman start
param set BAT_N_CELLS 3
param set CAL_ACC0_ID 1376264
param set CAL_ACC0_XOFF 0.01
param set CAL_ACC0_XSCALE 1.01
param set CAL_ACC0_YOFF -0.01
param set CAL_ACC0_YSCALE 1.01
param set CAL_ACC0_ZOFF 0.01
param set CAL_ACC0_ZSCALE 1.01
param set CAL_ACC1_ID 1310728
param set CAL_ACC1_XOFF 0.01
param set CAL_GYRO0_ID 2293768
param set CAL_GYRO0_XOFF 0.01
param set CAL_MAG0_ID 196616
param set CAL_MAG0_XOFF 0.01
param set COM_DISARM_LAND 5
param set COM_RC_IN_MODE 1
param set EKF2_AID_MASK 1
param set EKF2_ANGERR_INIT 0.01
param set EKF2_GBIAS_INIT 0.01
param set EKF2_HGT_MODE 0
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MAX 25
param set FW_AIRSPD_MIN 14
param set FW_AIRSPD_TRIM 16
param set MAV_TYPE 21
param set MC_PITCH_P 6
param set MC_PITCHRATE_P 0.2
param set MC_ROLL_P 6
param set MC_ROLLRATE_P 0.3
param set MIS_LTRMIN_ALT 10
param set MIS_TAKEOFF_ALT 10
param set MIS_YAW_TMT 10
param set MPC_ACC_HOR_MAX 2
param set MPC_ACC_HOR_MAX 2.0
param set MPC_TKO_SPEED 1.0
param set MPC_XY_P 0.8
param set MPC_XY_VEL_D 0.005
param set MPC_XY_VEL_I 0.2
param set MPC_XY_VEL_P 0.15
param set MPC_Z_VEL_I 0.15
param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_Z_VEL_P 0.6
param set NAV_ACC_RAD 5.0
param set NAV_DLL_ACT 2
param set NAV_LOITER_RAD 80
param set RTL_DESCEND_ALT 10.0
param set RTL_LAND_DELAY 0
param set RTL_RETURN_ALT 30.0
param set SDLOG_DIRS_MAX 7
param set SENS_BOARD_ROT 0
param set SENS_BOARD_X_OFF 0.000001
param set SENS_DPRES_OFF 0.001
param set SYS_AUTOSTART 13006
param set SYS_MC_EST_GROUP 2
param set SYS_RESTART_TYPE 2
param set VT_MOT_COUNT 4
param set VT_TRANS_THR 0.75
param set VT_TYPE 1
param set VT_TILT_FW 3.1415
param set VT_TILT_TRANS 1.2
replay tryapplyparams
simulator start -s
tone_alarm start
gyrosim start
accelsim start
barosim start
adcsim start
gpssim start
measairspeedsim start
pwm_out_sim mode_pwm
sensors start
commander start
land_detector start vtol
navigator start
ekf2 start
vtol_att_control start
mc_pos_control start
mc_att_control start
fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 ROMFS/sitl/mixers/tiltrotor_sitl.main.mix
mavlink start -x -u 14556 -r 2000000 -f
mavlink start -x -u 14557 -r 2000000 -m onboard -o 14540 -f
mavlink stream -r 20 -s EXTENDED_SYS_STATE -u 14557
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556
mavlink stream -r 80 -s ATTITUDE -u 14556
mavlink stream -r 80 -s ATTITUDE_QUATERNION -u 14556
mavlink stream -r 80 -s ATTITUDE_TARGET -u 14556
mavlink stream -r 20 -s RC_CHANNELS -u 14556
mavlink stream -r 250 -s HIGHRES_IMU -u 14556
mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
logger start -e -t
mavlink boot_complete
replay trystart
55 changes: 53 additions & 2 deletions src/drivers/pwm_out_sim/pwm_out_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ class PWMSim : public device::CDev
{
const uint32_t PWM_SIM_DISARMED_MAGIC = 900;
const uint32_t PWM_SIM_FAILSAFE_MAGIC = 600;
const uint32_t PWM_SIM_PWM_MIN_MAGIC = 1000;
const uint32_t PWM_SIM_PWM_MAX_MAGIC = 2000;
public:
enum Mode {
MODE_2PWM,
Expand All @@ -108,7 +110,7 @@ class PWMSim : public device::CDev
int _task;

private:
static const unsigned _max_actuators = 8;
static const unsigned _max_actuators = 16;

Mode _mode;
int _update_rate;
Expand All @@ -120,6 +122,8 @@ class PWMSim : public device::CDev
orb_advert_t _outputs_pub;
unsigned _num_outputs;
bool _primary_pwm_device;
unsigned _pwm_min[_max_actuators];
unsigned _pwm_max[_max_actuators];

uint32_t _groups_required;
uint32_t _groups_subscribed;
Expand Down Expand Up @@ -192,6 +196,11 @@ PWMSim::PWMSim() :
{
memset(_controls, 0, sizeof(_controls));

for (unsigned i = 0; i < _max_actuators; i++) {
_pwm_min[i] = PWM_SIM_PWM_MIN_MAGIC;
_pwm_max[i] = PWM_SIM_PWM_MAX_MAGIC;
}

_control_topics[0] = ORB_ID(actuator_controls_0);
_control_topics[1] = ORB_ID(actuator_controls_1);
_control_topics[2] = ORB_ID(actuator_controls_2);
Expand Down Expand Up @@ -463,6 +472,10 @@ PWMSim::task_main()
num_outputs = 8;
break;

case MODE_12PWM:
num_outputs = 12;
break;

case MODE_16PWM:
num_outputs = 16;
break;
Expand Down Expand Up @@ -494,6 +507,14 @@ PWMSim::task_main()
/* scale for PWM output 1000 - 2000us */
outputs.output[i] = 1500 + (500 * outputs.output[i]);

if (outputs.output[i] > _pwm_max[i]) {
outputs.output[i] = _pwm_max[i];
}

if (outputs.output[i] < _pwm_min[i]) {
outputs.output[i] = _pwm_min[i];
}

} else {
/*
* Value is NaN, INF or out of band - set to the minimum value.
Expand Down Expand Up @@ -618,6 +639,32 @@ PWMSim::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
// up_pwm_servo_arm(false);
break;

case PWM_SERVO_SET_MIN_PWM: {
struct pwm_output_values *pwm = (struct pwm_output_values *)arg;

for (unsigned i = 0; i < pwm->channel_count; i++) {

if (i <= _max_actuators) {
_pwm_min[i] = pwm->values[i];
}
}

break;
}

case PWM_SERVO_SET_MAX_PWM: {
struct pwm_output_values *pwm = (struct pwm_output_values *)arg;

for (unsigned i = 0; i < pwm->channel_count; i++) {

if (i <= _max_actuators) {
_pwm_max[i] = pwm->values[i];
}
}

break;
}

case PWM_SERVO_SET_UPDATE_RATE:
// PWMSim always outputs at the alternate (usually faster) rate
g_pwm_sim->set_pwm_rate(arg);
Expand Down Expand Up @@ -754,6 +801,10 @@ PWMSim::pwm_ioctl(device::file_t *filp, int cmd, unsigned long arg)
if (_mode == MODE_16PWM) {
*(unsigned *)arg = 16;

} else if (_mode == MODE_12PWM) {

*(unsigned *)arg = 12;

} else if (_mode == MODE_8PWM) {

*(unsigned *)arg = 8;
Expand Down Expand Up @@ -993,7 +1044,7 @@ pwm_out_sim_main(int argc, char *argv[])

// this was all cut-and-pasted from the FMU driver; it's junk
if (!strcmp(verb, "mode_pwm")) {
new_mode = PORT1_FULL_PWM;
new_mode = PORT2_12PWM;

} else if (!strcmp(verb, "mode_port2_pwm8")) {
new_mode = PORT2_8PWM;
Expand Down
15 changes: 7 additions & 8 deletions src/modules/simulator/simulator_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,26 +94,21 @@ 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 */

unsigned n;

switch (_system_type) {
case MAV_TYPE_QUADROTOR:
n = 4;
break;

case MAV_TYPE_HEXAROTOR:
n = 6;
break;

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;

Expand All @@ -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;
Expand Down
10 changes: 2 additions & 8 deletions src/modules/systemlib/param/param.c
Original file line number Diff line number Diff line change
Expand Up @@ -1275,8 +1275,8 @@ param_import_internal(int fd, bool mark_saved)
int result = -1;

if (bson_decoder_init_file(&decoder, fd, param_import_callback, &state)) {
PX4_ERR("decoder init failed");
goto out;
PX4_WARN("decoder init failed");
return -ENODATA;
}

state.mark_saved = mark_saved;
Expand All @@ -1287,12 +1287,6 @@ param_import_internal(int fd, bool mark_saved)

} while (result > 0);

out:

if (result < 0) {
PX4_ERR("BSON error decoding parameters");
}

return result;
}

Expand Down