diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/71000_gazebo-classic_2d_spacecraft b/ROMFS/px4fmu_common/init.d-posix/airframes/71000_gazebo-classic_2d_spacecraft deleted file mode 100644 index 38d9587dde..0000000000 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/71000_gazebo-classic_2d_spacecraft +++ /dev/null @@ -1,127 +0,0 @@ -#!/bin/sh -# -# @name 3DoF Spacecraft Model -# -# @type 2D Freeflyer with 8 thrusters - Planar motion -# -# @maintainer Pedro Roque -# - -. ${R}etc/init.d/rc.sc_defaults - -param set-default CA_AIRFRAME 13 -param set-default MAV_TYPE 99 - -param set-default CA_THRUSTER_CNT 8 -param set-default CA_R_REV 255 - -# param set-default FW_ARSP_MODE 1 -param set-default UXRCE_DDS_CFG 1000 -param set-default MAV_2_CONFIG 1000 -param set-default MAV_2_REMOTE_PRT 14550 -param set-default MAV_2_UDP 14550 - -# Auto to be provided by Custom Airframe -param set-default CA_METHOD 0 - -# Set proper failsafes -param set-default COM_ACT_FAIL_ACT 0 -param set-default COM_LOW_BAT_ACT 0 -param set-default NAV_DLL_ACT 0 -param set-default GF_ACTION 1 -param set-default NAV_RCL_ACT 1 -param set-default COM_POSCTL_NAVL 2 - -# disable attitude failure detection -param set-default FD_FAIL_P 0 -param set-default FD_FAIL_R 0 - -param set-default CA_THRUSTER0_PX -0.12 -param set-default CA_THRUSTER0_PY -0.12 -param set-default CA_THRUSTER0_PZ 0.0 -param set-default CA_THRUSTER0_CT 1.4 -param set-default CA_THRUSTER0_AX 1.0 -param set-default CA_THRUSTER0_AY 0.0 -param set-default CA_THRUSTER0_AZ 0.0 - -param set-default CA_THRUSTER1_PX 0.12 -param set-default CA_THRUSTER1_PY -0.12 -param set-default CA_THRUSTER1_PZ 0.0 -param set-default CA_THRUSTER1_CT 1.4 -param set-default CA_THRUSTER1_AX -1.0 -param set-default CA_THRUSTER1_AY 0.0 -param set-default CA_THRUSTER1_AZ 0.0 - -param set-default CA_THRUSTER2_PX -0.12 -param set-default CA_THRUSTER2_PY 0.12 -param set-default CA_THRUSTER2_PZ 0.0 -param set-default CA_THRUSTER2_CT 1.4 -param set-default CA_THRUSTER2_AX 1.0 -param set-default CA_THRUSTER2_AY 0.0 -param set-default CA_THRUSTER2_AZ 0.0 - -param set-default CA_THRUSTER3_PX 0.12 -param set-default CA_THRUSTER3_PY 0.12 -param set-default CA_THRUSTER3_PZ 0.0 -param set-default CA_THRUSTER3_CT 1.4 -param set-default CA_THRUSTER3_AX -1.0 -param set-default CA_THRUSTER3_AY 0.0 -param set-default CA_THRUSTER3_AZ 0.0 - -param set-default CA_THRUSTER4_PX 0.12 -param set-default CA_THRUSTER4_PY -0.12 -param set-default CA_THRUSTER4_PZ 0.0 -param set-default CA_THRUSTER4_CT 1.4 -param set-default CA_THRUSTER4_AX 0.0 -param set-default CA_THRUSTER4_AY 1.0 -param set-default CA_THRUSTER4_AZ 0.0 - -param set-default CA_THRUSTER5_PX 0.12 -param set-default CA_THRUSTER5_PY 0.12 -param set-default CA_THRUSTER5_PZ 0.0 -param set-default CA_THRUSTER5_CT 1.4 -param set-default CA_THRUSTER5_AX 0.0 -param set-default CA_THRUSTER5_AY -1.0 -param set-default CA_THRUSTER5_AZ 0.0 - -param set-default CA_THRUSTER6_PX -0.12 -param set-default CA_THRUSTER6_PY -0.12 -param set-default CA_THRUSTER6_PZ 0.0 -param set-default CA_THRUSTER6_CT 1.4 -param set-default CA_THRUSTER6_AX 0.0 -param set-default CA_THRUSTER6_AY 1.0 -param set-default CA_THRUSTER6_AZ 0.0 - -param set-default CA_THRUSTER7_PX -0.12 -param set-default CA_THRUSTER7_PY 0.12 -param set-default CA_THRUSTER7_PZ 0.0 -param set-default CA_THRUSTER7_CT 1.4 -param set-default CA_THRUSTER7_AX 0.0 -param set-default CA_THRUSTER7_AY -1.0 -param set-default CA_THRUSTER7_AZ 0.0 - -param set-default PWM_MAIN_FUNC1 501 -param set-default PWM_MAIN_FUNC2 502 -param set-default PWM_MAIN_FUNC3 503 -param set-default PWM_MAIN_FUNC4 504 -param set-default PWM_MAIN_FUNC5 505 -param set-default PWM_MAIN_FUNC6 506 -param set-default PWM_MAIN_FUNC7 507 -param set-default PWM_MAIN_FUNC8 508 - -# PWM Simulation -param set PWM_SIM_PWM_MAX 10000 -param set PWM_SIM_PWM_MIN 0 - -# Controller Tunings -param set SC_YAWRATE_P 3.335 -param set SC_YAWRATE_I 0.87 -param set SC_YAWRATE_D 0.15 -param set SC_YR_INT_LIM 0.2 -param set SC_YAW_P 3.0 - -param set SPC_POS_P 0.20 -param set SPC_VEL_P 6.55 -param set SPC_VEL_I 0.0 -param set SPC_VEL_D 0.0 -param set SPC_VEL_MAX 12.0 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/71001_gazebo-classic_spacecraft_dart b/ROMFS/px4fmu_common/init.d-posix/airframes/71001_gazebo-classic_spacecraft_dart index 4cb64da954..7c3449fca4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/71001_gazebo-classic_spacecraft_dart +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/71001_gazebo-classic_spacecraft_dart @@ -152,4 +152,4 @@ param set-default SC_PITCHRATE_P 0.14 param set-default SC_ROLLRATE_I 0.3 param set-default SC_PITCHRATE_I 0.3 param set-default SC_ROLLRATE_D 0.004 -param set-default SC_PITCHRATE_D 0.004 \ No newline at end of file +param set-default SC_PITCHRATE_D 0.004 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 06ab8cb3dc..6a8a3eb6e0 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -113,7 +113,6 @@ px4_add_romfs_files( 17001_flightgear_tf-g1 17002_flightgear_tf-g2 - 71000_gazebo-classic_2d_spacecraft 71001_gazebo-classic_spacecraft_dart 71002_gz_spacecraft_2d