Skip to content

Commit

Permalink
Spacecraft build and bare control allocator (#24221)
Browse files Browse the repository at this point in the history
  • Loading branch information
Pedro-Roque authored Feb 7, 2025
1 parent de1ade8 commit e7e76e2
Show file tree
Hide file tree
Showing 21 changed files with 1,037 additions and 2 deletions.
1 change: 0 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -129,5 +129,4 @@
"yaml.schemas": {
"${workspaceFolder}/validation/module_schema.yaml": "${workspaceFolder}/src/modules/*/module.yaml"
},
"ros.distro": "humble"
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
#!/bin/sh
#
# @name 6DoF Spacecraft Model
#
# @type Freeflyer with 8 thrusters
#
# @maintainer Pedro Roque <[email protected]>
#

. ${R}etc/init.d/rc.sc_defaults

param set-default CA_AIRFRAME 15
param set-default MAV_TYPE 99

param set-default CA_THRUSTER_CNT 12
param set-default CA_R_REV 0

# param set-default FW_ARSP_MODE 1

# Auto to be provided by Custom Airframe
param set-default CA_METHOD 0

# disable attitude failure detection
param set-default FD_FAIL_P 0
param set-default FD_FAIL_R 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

# Set thrusters
param set-default CA_THRUSTER0_PX -0.50
param set-default CA_THRUSTER0_PY 0.50
param set-default CA_THRUSTER0_PZ 0.0
param set-default CA_THRUSTER0_CT 0.237
param set-default CA_THRUSTER0_AX 0.0
param set-default CA_THRUSTER0_AY -1.0
param set-default CA_THRUSTER0_AZ 0.0

param set-default CA_THRUSTER1_PX 0.50
param set-default CA_THRUSTER1_PY 0.50
param set-default CA_THRUSTER1_PZ 0.0
param set-default CA_THRUSTER1_CT 0.237
param set-default CA_THRUSTER1_AX 0.0
param set-default CA_THRUSTER1_AY -1.0
param set-default CA_THRUSTER1_AZ 0.0

param set-default CA_THRUSTER2_PX 0.50
param set-default CA_THRUSTER2_PY -0.50
param set-default CA_THRUSTER2_PZ 0.0
param set-default CA_THRUSTER2_CT 0.237
param set-default CA_THRUSTER2_AX 0.0
param set-default CA_THRUSTER2_AY 1.0
param set-default CA_THRUSTER2_AZ 0.0

param set-default CA_THRUSTER3_PX -0.50
param set-default CA_THRUSTER3_PY -0.50
param set-default CA_THRUSTER3_PZ 0.0
param set-default CA_THRUSTER3_CT 0.237
param set-default CA_THRUSTER3_AX 0.0
param set-default CA_THRUSTER3_AY 1.0
param set-default CA_THRUSTER3_AZ 0.0

param set-default CA_THRUSTER4_PX -0.50
param set-default CA_THRUSTER4_PY 0.0
param set-default CA_THRUSTER4_PZ -0.50
param set-default CA_THRUSTER4_CT 0.237
param set-default CA_THRUSTER4_AX 1.0
param set-default CA_THRUSTER4_AY 0.0
param set-default CA_THRUSTER4_AZ 0.0

param set-default CA_THRUSTER5_PX 0.50
param set-default CA_THRUSTER5_PY 0.0
param set-default CA_THRUSTER5_PZ -0.50
param set-default CA_THRUSTER5_CT 0.237
param set-default CA_THRUSTER5_AX -1.0
param set-default CA_THRUSTER5_AY 0.0
param set-default CA_THRUSTER5_AZ 0.0

param set-default CA_THRUSTER6_PX 0.50
param set-default CA_THRUSTER6_PY 0.0
param set-default CA_THRUSTER6_PZ 0.50
param set-default CA_THRUSTER6_CT 0.237
param set-default CA_THRUSTER6_AX -1.0
param set-default CA_THRUSTER6_AY 0.0
param set-default CA_THRUSTER6_AZ 0.0

param set-default CA_THRUSTER7_PX -0.50
param set-default CA_THRUSTER7_PY 0.0
param set-default CA_THRUSTER7_PZ 0.50
param set-default CA_THRUSTER7_CT 0.237
param set-default CA_THRUSTER7_AX 1.0
param set-default CA_THRUSTER7_AY 0.0
param set-default CA_THRUSTER7_AZ 0.0

param set-default CA_THRUSTER8_PX 0.0
param set-default CA_THRUSTER8_PY -0.50
param set-default CA_THRUSTER8_PZ -0.50
param set-default CA_THRUSTER8_CT 0.237
param set-default CA_THRUSTER8_AX 0.0
param set-default CA_THRUSTER8_AY 0.0
param set-default CA_THRUSTER8_AZ 1.0

param set-default CA_THRUSTER9_PX 0.0
param set-default CA_THRUSTER9_PY 0.50
param set-default CA_THRUSTER9_PZ -0.50
param set-default CA_THRUSTER9_CT 0.237
param set-default CA_THRUSTER9_AX 0.0
param set-default CA_THRUSTER9_AY 0.0
param set-default CA_THRUSTER9_AZ 1.0

param set-default CA_THRUSTER10_PX 0.0
param set-default CA_THRUSTER10_PY 0.50
param set-default CA_THRUSTER10_PZ 0.50
param set-default CA_THRUSTER10_CT 0.237
param set-default CA_THRUSTER10_AX 0.0
param set-default CA_THRUSTER10_AY 0.0
param set-default CA_THRUSTER10_AZ -1.0

param set-default CA_THRUSTER11_PX 0.0
param set-default CA_THRUSTER11_PY -0.50
param set-default CA_THRUSTER11_PZ 0.50
param set-default CA_THRUSTER11_CT 0.237
param set-default CA_THRUSTER11_AX 0.0
param set-default CA_THRUSTER11_AY 0.0
param set-default CA_THRUSTER11_AZ -1.0

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108
param set-default PWM_MAIN_FUNC9 109
param set-default PWM_MAIN_FUNC10 110
param set-default PWM_MAIN_FUNC11 111
param set-default PWM_MAIN_FUNC12 112

# PWM Simulation
param set PWM_SIM_PWM_MAX 10000
param set PWM_SIM_PWM_MIN 0

# Controller Tunings
param set-default SC_ROLLRATE_P 0.14
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
149 changes: 149 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/71002_gz_spacecraft_2d
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
#!/bin/sh
#
# @name 3DoF Spacecraft Model
#
# @type 2D Freeflyer with 8 thrusters - Planar motion
#
# @maintainer Pedro Roque <[email protected]>
#

. ${R}etc/init.d/rc.sc_defaults

PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=spacecraft_2d}

param set-default SIM_GZ_EN 1

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default COM_ARM_CHK_ESCS 0 # We don't have ESCs
param set-default FD_ESCS_EN 0 # We don't have ESCs - but maybe we need this later?

param set-default CA_AIRFRAME 14
param set-default MAV_TYPE 99

param set-default CA_THRUSTER_CNT 8
param set-default CA_R_REV 0

# param set-default FW_ARSP_MODE 1

# Auto to be provided by Custom Airframe
param set-default CA_METHOD 0 # 0 is PseudoInverse, 3 is Metric

# 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 SIM_GZ_TH_FUNC1 101
param set-default SIM_GZ_TH_FUNC2 102
param set-default SIM_GZ_TH_FUNC3 103
param set-default SIM_GZ_TH_FUNC4 104
param set-default SIM_GZ_TH_FUNC5 105
param set-default SIM_GZ_TH_FUNC6 106
param set-default SIM_GZ_TH_FUNC7 107
param set-default SIM_GZ_TH_FUNC8 108

param set-default SIM_GZ_TH_MIN1 0
param set-default SIM_GZ_TH_MIN2 0
param set-default SIM_GZ_TH_MIN3 0
param set-default SIM_GZ_TH_MIN4 0
param set-default SIM_GZ_TH_MIN5 0
param set-default SIM_GZ_TH_MIN6 0
param set-default SIM_GZ_TH_MIN7 0
param set-default SIM_GZ_TH_MIN8 0

param set-default SIM_GZ_TH_MAX1 10000
param set-default SIM_GZ_TH_MAX2 10000
param set-default SIM_GZ_TH_MAX3 10000
param set-default SIM_GZ_TH_MAX4 10000
param set-default SIM_GZ_TH_MAX5 10000
param set-default SIM_GZ_TH_MAX6 10000
param set-default SIM_GZ_TH_MAX7 10000
param set-default SIM_GZ_TH_MAX8 10000

# 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
3 changes: 3 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -114,5 +114,8 @@ px4_add_romfs_files(
17001_flightgear_tf-g1
17002_flightgear_tf-g2

71001_gazebo-classic_spacecraft_dart
71002_gz_spacecraft_2d

# [22000, 22999] Reserve for custom models
)
7 changes: 7 additions & 0 deletions ROMFS/px4fmu_common/init.d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,13 @@ if(CONFIG_MODULES_ROVER_ACKERMANN)
)
endif()

if(CONFIG_MODULES_SPACECRAFT)
px4_add_romfs_files(
rc.sc_apps
rc.sc_defaults
)
endif()

if(CONFIG_MODULES_ROVER_MECANUM)
px4_add_romfs_files(
rc.rover_mecanum_apps
Expand Down
Loading

0 comments on commit e7e76e2

Please sign in to comment.