diff --git a/ja/airframes/airframe_reference.md b/ja/airframes/airframe_reference.md
index 6ae73bce025e..3a0a37ac4947 100644
--- a/ja/airframes/airframe_reference.md
+++ b/ja/airframes/airframe_reference.md
@@ -702,7 +702,7 @@ div.frame_variant td, div.frame_variant th {
SIH Standard VTOL QuadPlane |
- Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Aileron
- Servo2: Elevator
- Servo3: Rudder
|
+ Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Ailerons (single channel)
- Servo2: Elevator
- Servo3: Rudder
|
diff --git a/ja/sim_sih/index.md b/ja/sim_sih/index.md
index e9918d7a607b..6a3855a0e55a 100644
--- a/ja/sim_sih/index.md
+++ b/ja/sim_sih/index.md
@@ -168,6 +168,63 @@ export PX4_HOME_ALT=28.5
make px4_sitl sihsim_quadx
```
+## Adding New Airframes
+
+[Adding a new airframe](../dev_airframes/adding_a_new_frame.md) for use in SIH simulation is much the same as for other use cases.
+You still need to configure your vehicle type and [geometry](../config/actuators.md) (`CA_` parameters) and start any other defaults for that specific vehicle.
+
+:::warning
+Not every vehicle can be simulated with SIH — there are currently [four supported vehicle types](../advanced_config/parameter_reference.md#SIH_VEHICLE_TYPE), each of which has a relatively rigid implementation in [`sih.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_sih/sih.cpp).
+:::
+
+The specific differences for SIH simulation airframes are listed in the sections below.
+
+For all variants of SIH:
+
+- Set all the [Simulation In Hardware](../advanced_config/parameter_reference.md#simulation-in-hardware) parameters (prefixed with `SIH_`) in order to configure the physical model of the vehicle.
+
+ ::: tip
+ Make sure that the `SIH_*` parameters and the `CA_*` parameters describe the same vehicle.
+ Note that some of these parameters are redundant!
+
+:::
+
+- `param set-default SYS_HITL 2` to enable SIH on the next boot.
+
+ ::: info
+ This also disables input from real sensors.
+ For SIH on the FC (only), it also enables the simulated GPS, barometer, magnetometer, and airspeed sensor.
+
+ For SIH on SITL you will need to explicitly enable these sensors as shown below.
+
+:::
+
+- `param set-default EKF2_GPS_DELAY 0` to improve state estimator performance (the assumption of instant GPS measurements would normally be unrealistic, but is accurate for SIH).
+
+For SIH on FC:
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d/airframes` and follows the naming template `${ID}_${model_name}.hil`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured with `HIL_ACT_FUNC*` parameters (not the usual `PWM_MAIN_FUNC*` parameters).
+ This is to avoid using the real actuator outputs in SIH.
+ Similarly, the bitfield for inverting individual actuator output ranges is `HIL_ACT_REV`, rather than `PWM_MAIN_REV`.
+
+For SIH as SITL (no FC):
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d-posix/airframes` and follows the naming template `${ID}_sihsim_${model_name}`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `src/modules/simulation/simulator_sih/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured as usual with `PWM_MAIN_FUNC*` and `PWM_MAIN_REV`.
+- Additionally, set:
+ - `PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}`
+ - `PX4_SIM_MODEL=${PX4_SIM_MODEL:=svtol}` (replacing `svtol` with the airframe model name)
+- Enable the simulated sensors using [SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM), and [SENS_EN_ARSPDSIM](../advanced_config/parameter_reference.md#SENS_EN_ARSPDSIM) (this is only needed for SIH-as-SITL):
+ - `param set-default SENS_EN_GPSSIM 1`
+ - `param set-default SENS_EN_BAROSIM 1`
+ - `param set-default SENS_EN_MAGSIM 1`
+ - `param set-default SENS_EN_ARSPDSIM 1` (if it is a fixed-wing or VTOL airframe with airspeed sensor)
+
+For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
+
## Dynamic Models
The dynamic models for the various vehicles are:
diff --git a/ko/airframes/airframe_reference.md b/ko/airframes/airframe_reference.md
index 0e2f21c712db..09e2b95016c6 100644
--- a/ko/airframes/airframe_reference.md
+++ b/ko/airframes/airframe_reference.md
@@ -706,7 +706,7 @@ div.frame_variant td, div.frame_variant th {
SIH Standard VTOL QuadPlane |
- 유지보수: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Aileron
- Servo2: Elevator
- Servo3: Rudder
|
+ 유지보수: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Ailerons (single channel)
- Servo2: Elevator
- Servo3: Rudder
|
diff --git a/ko/sim_sih/index.md b/ko/sim_sih/index.md
index b2ca76ee5c2f..d1ef8b5d9a89 100644
--- a/ko/sim_sih/index.md
+++ b/ko/sim_sih/index.md
@@ -168,6 +168,63 @@ export PX4_HOME_ALT=28.5
make px4_sitl sihsim_quadx
```
+## Adding New Airframes
+
+[Adding a new airframe](../dev_airframes/adding_a_new_frame.md) for use in SIH simulation is much the same as for other use cases.
+You still need to configure your vehicle type and [geometry](../config/actuators.md) (`CA_` parameters) and start any other defaults for that specific vehicle.
+
+:::warning
+Not every vehicle can be simulated with SIH — there are currently [four supported vehicle types](../advanced_config/parameter_reference.md#SIH_VEHICLE_TYPE), each of which has a relatively rigid implementation in [`sih.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_sih/sih.cpp).
+:::
+
+The specific differences for SIH simulation airframes are listed in the sections below.
+
+For all variants of SIH:
+
+- Set all the [Simulation In Hardware](../advanced_config/parameter_reference.md#simulation-in-hardware) parameters (prefixed with `SIH_`) in order to configure the physical model of the vehicle.
+
+ ::: tip
+ Make sure that the `SIH_*` parameters and the `CA_*` parameters describe the same vehicle.
+ Note that some of these parameters are redundant!
+
+:::
+
+- `param set-default SYS_HITL 2` to enable SIH on the next boot.
+
+ ::: info
+ This also disables input from real sensors.
+ For SIH on the FC (only), it also enables the simulated GPS, barometer, magnetometer, and airspeed sensor.
+
+ For SIH on SITL you will need to explicitly enable these sensors as shown below.
+
+:::
+
+- `param set-default EKF2_GPS_DELAY 0` to improve state estimator performance (the assumption of instant GPS measurements would normally be unrealistic, but is accurate for SIH).
+
+For SIH on FC:
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d/airframes` and follows the naming template `${ID}_${model_name}.hil`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured with `HIL_ACT_FUNC*` parameters (not the usual `PWM_MAIN_FUNC*` parameters).
+ This is to avoid using the real actuator outputs in SIH.
+ Similarly, the bitfield for inverting individual actuator output ranges is `HIL_ACT_REV`, rather than `PWM_MAIN_REV`.
+
+For SIH as SITL (no FC):
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d-posix/airframes` and follows the naming template `${ID}_sihsim_${model_name}`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `src/modules/simulation/simulator_sih/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured as usual with `PWM_MAIN_FUNC*` and `PWM_MAIN_REV`.
+- Additionally, set:
+ - `PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}`
+ - `PX4_SIM_MODEL=${PX4_SIM_MODEL:=svtol}` (replacing `svtol` with the airframe model name)
+- Enable the simulated sensors using [SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM), and [SENS_EN_ARSPDSIM](../advanced_config/parameter_reference.md#SENS_EN_ARSPDSIM) (this is only needed for SIH-as-SITL):
+ - `param set-default SENS_EN_GPSSIM 1`
+ - `param set-default SENS_EN_BAROSIM 1`
+ - `param set-default SENS_EN_MAGSIM 1`
+ - `param set-default SENS_EN_ARSPDSIM 1` (if it is a fixed-wing or VTOL airframe with airspeed sensor)
+
+For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
+
## Dynamic Models
The dynamic models for the various vehicles are:
diff --git a/tr/airframes/airframe_reference.md b/tr/airframes/airframe_reference.md
index 72a3d91b6ec4..5d8af1e0ba34 100644
--- a/tr/airframes/airframe_reference.md
+++ b/tr/airframes/airframe_reference.md
@@ -702,7 +702,7 @@ div.frame_variant td, div.frame_variant th {
SIH Standard VTOL QuadPlane |
- Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Aileron
- Servo2: Elevator
- Servo3: Rudder
|
+ Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Ailerons (single channel)
- Servo2: Elevator
- Servo3: Rudder
|
diff --git a/tr/sim_sih/index.md b/tr/sim_sih/index.md
index e9918d7a607b..6a3855a0e55a 100644
--- a/tr/sim_sih/index.md
+++ b/tr/sim_sih/index.md
@@ -168,6 +168,63 @@ export PX4_HOME_ALT=28.5
make px4_sitl sihsim_quadx
```
+## Adding New Airframes
+
+[Adding a new airframe](../dev_airframes/adding_a_new_frame.md) for use in SIH simulation is much the same as for other use cases.
+You still need to configure your vehicle type and [geometry](../config/actuators.md) (`CA_` parameters) and start any other defaults for that specific vehicle.
+
+:::warning
+Not every vehicle can be simulated with SIH — there are currently [four supported vehicle types](../advanced_config/parameter_reference.md#SIH_VEHICLE_TYPE), each of which has a relatively rigid implementation in [`sih.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_sih/sih.cpp).
+:::
+
+The specific differences for SIH simulation airframes are listed in the sections below.
+
+For all variants of SIH:
+
+- Set all the [Simulation In Hardware](../advanced_config/parameter_reference.md#simulation-in-hardware) parameters (prefixed with `SIH_`) in order to configure the physical model of the vehicle.
+
+ ::: tip
+ Make sure that the `SIH_*` parameters and the `CA_*` parameters describe the same vehicle.
+ Note that some of these parameters are redundant!
+
+:::
+
+- `param set-default SYS_HITL 2` to enable SIH on the next boot.
+
+ ::: info
+ This also disables input from real sensors.
+ For SIH on the FC (only), it also enables the simulated GPS, barometer, magnetometer, and airspeed sensor.
+
+ For SIH on SITL you will need to explicitly enable these sensors as shown below.
+
+:::
+
+- `param set-default EKF2_GPS_DELAY 0` to improve state estimator performance (the assumption of instant GPS measurements would normally be unrealistic, but is accurate for SIH).
+
+For SIH on FC:
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d/airframes` and follows the naming template `${ID}_${model_name}.hil`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured with `HIL_ACT_FUNC*` parameters (not the usual `PWM_MAIN_FUNC*` parameters).
+ This is to avoid using the real actuator outputs in SIH.
+ Similarly, the bitfield for inverting individual actuator output ranges is `HIL_ACT_REV`, rather than `PWM_MAIN_REV`.
+
+For SIH as SITL (no FC):
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d-posix/airframes` and follows the naming template `${ID}_sihsim_${model_name}`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `src/modules/simulation/simulator_sih/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured as usual with `PWM_MAIN_FUNC*` and `PWM_MAIN_REV`.
+- Additionally, set:
+ - `PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}`
+ - `PX4_SIM_MODEL=${PX4_SIM_MODEL:=svtol}` (replacing `svtol` with the airframe model name)
+- Enable the simulated sensors using [SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM), and [SENS_EN_ARSPDSIM](../advanced_config/parameter_reference.md#SENS_EN_ARSPDSIM) (this is only needed for SIH-as-SITL):
+ - `param set-default SENS_EN_GPSSIM 1`
+ - `param set-default SENS_EN_BAROSIM 1`
+ - `param set-default SENS_EN_MAGSIM 1`
+ - `param set-default SENS_EN_ARSPDSIM 1` (if it is a fixed-wing or VTOL airframe with airspeed sensor)
+
+For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
+
## Dynamic Models
The dynamic models for the various vehicles are:
diff --git a/uk/airframes/airframe_reference.md b/uk/airframes/airframe_reference.md
index 95eb7240ec01..1892e246feba 100644
--- a/uk/airframes/airframe_reference.md
+++ b/uk/airframes/airframe_reference.md
@@ -702,7 +702,7 @@ div.frame_variant td, div.frame_variant th {
SIH Standard VTOL QuadPlane |
- Підтримувач: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Aileron
- Servo2: Elevator
- Servo3: Rudder
|
+ Підтримувач: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Ailerons (single channel)
- Servo2: Elevator
- Servo3: Rudder
|
diff --git a/uk/sim_sih/index.md b/uk/sim_sih/index.md
index c09d4efb7131..b16c99ab2df7 100644
--- a/uk/sim_sih/index.md
+++ b/uk/sim_sih/index.md
@@ -168,6 +168,63 @@ export PX4_HOME_ALT=28.5
make px4_sitl sihsim_quadx
```
+## Adding New Airframes
+
+[Adding a new airframe](../dev_airframes/adding_a_new_frame.md) for use in SIH simulation is much the same as for other use cases.
+You still need to configure your vehicle type and [geometry](../config/actuators.md) (`CA_` parameters) and start any other defaults for that specific vehicle.
+
+:::warning
+Not every vehicle can be simulated with SIH — there are currently [four supported vehicle types](../advanced_config/parameter_reference.md#SIH_VEHICLE_TYPE), each of which has a relatively rigid implementation in [`sih.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_sih/sih.cpp).
+:::
+
+The specific differences for SIH simulation airframes are listed in the sections below.
+
+For all variants of SIH:
+
+- Set all the [Simulation In Hardware](../advanced_config/parameter_reference.md#simulation-in-hardware) parameters (prefixed with `SIH_`) in order to configure the physical model of the vehicle.
+
+ ::: tip
+ Make sure that the `SIH_*` parameters and the `CA_*` parameters describe the same vehicle.
+ Note that some of these parameters are redundant!
+
+:::
+
+- `param set-default SYS_HITL 2` to enable SIH on the next boot.
+
+ ::: info
+ This also disables input from real sensors.
+ For SIH on the FC (only), it also enables the simulated GPS, barometer, magnetometer, and airspeed sensor.
+
+ For SIH on SITL you will need to explicitly enable these sensors as shown below.
+
+:::
+
+- `param set-default EKF2_GPS_DELAY 0` to improve state estimator performance (the assumption of instant GPS measurements would normally be unrealistic, but is accurate for SIH).
+
+For SIH on FC:
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d/airframes` and follows the naming template `${ID}_${model_name}.hil`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured with `HIL_ACT_FUNC*` parameters (not the usual `PWM_MAIN_FUNC*` parameters).
+ This is to avoid using the real actuator outputs in SIH.
+ Similarly, the bitfield for inverting individual actuator output ranges is `HIL_ACT_REV`, rather than `PWM_MAIN_REV`.
+
+For SIH as SITL (no FC):
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d-posix/airframes` and follows the naming template `${ID}_sihsim_${model_name}`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `src/modules/simulation/simulator_sih/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured as usual with `PWM_MAIN_FUNC*` and `PWM_MAIN_REV`.
+- Additionally, set:
+ - `PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}`
+ - `PX4_SIM_MODEL=${PX4_SIM_MODEL:=svtol}` (replacing `svtol` with the airframe model name)
+- Enable the simulated sensors using [SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM), and [SENS_EN_ARSPDSIM](../advanced_config/parameter_reference.md#SENS_EN_ARSPDSIM) (this is only needed for SIH-as-SITL):
+ - `param set-default SENS_EN_GPSSIM 1`
+ - `param set-default SENS_EN_BAROSIM 1`
+ - `param set-default SENS_EN_MAGSIM 1`
+ - `param set-default SENS_EN_ARSPDSIM 1` (if it is a fixed-wing or VTOL airframe with airspeed sensor)
+
+For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
+
## Dynamic Models
Динамічні моделі для різних транспортних засобів:
diff --git a/zh/airframes/airframe_reference.md b/zh/airframes/airframe_reference.md
index 5b07490c5563..bebee64cdb0d 100644
--- a/zh/airframes/airframe_reference.md
+++ b/zh/airframes/airframe_reference.md
@@ -702,7 +702,7 @@ div.frame_variant td, div.frame_variant th {
SIH Standard VTOL QuadPlane |
- Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Aileron
- Servo2: Elevator
- Servo3: Rudder
|
+ Maintainer: John Doe <john@example.com> SYS_AUTOSTART = 1103
Specific Outputs:- Motor1: MC motor front right
- Motor2: MC motor back left
- Motor3: MC motor front left
- Motor4: MC motor back right
- Motor5: Forward thrust motor
- Servo1: Ailerons (single channel)
- Servo2: Elevator
- Servo3: Rudder
|
diff --git a/zh/sim_sih/index.md b/zh/sim_sih/index.md
index 29dea22e00e2..f6f9b43ddf2b 100644
--- a/zh/sim_sih/index.md
+++ b/zh/sim_sih/index.md
@@ -168,6 +168,63 @@ export PX4_HOME_ALT=28.5
make px4_sitl sihsim_quadx
```
+## Adding New Airframes
+
+[Adding a new airframe](../dev_airframes/adding_a_new_frame.md) for use in SIH simulation is much the same as for other use cases.
+You still need to configure your vehicle type and [geometry](../config/actuators.md) (`CA_` parameters) and start any other defaults for that specific vehicle.
+
+:::warning
+Not every vehicle can be simulated with SIH — there are currently [four supported vehicle types](../advanced_config/parameter_reference.md#SIH_VEHICLE_TYPE), each of which has a relatively rigid implementation in [`sih.cpp`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/simulator_sih/sih.cpp).
+:::
+
+The specific differences for SIH simulation airframes are listed in the sections below.
+
+For all variants of SIH:
+
+- Set all the [Simulation In Hardware](../advanced_config/parameter_reference.md#simulation-in-hardware) parameters (prefixed with `SIH_`) in order to configure the physical model of the vehicle.
+
+ ::: tip
+ Make sure that the `SIH_*` parameters and the `CA_*` parameters describe the same vehicle.
+ Note that some of these parameters are redundant!
+
+:::
+
+- `param set-default SYS_HITL 2` to enable SIH on the next boot.
+
+ ::: info
+ This also disables input from real sensors.
+ For SIH on the FC (only), it also enables the simulated GPS, barometer, magnetometer, and airspeed sensor.
+
+ For SIH on SITL you will need to explicitly enable these sensors as shown below.
+
+:::
+
+- `param set-default EKF2_GPS_DELAY 0` to improve state estimator performance (the assumption of instant GPS measurements would normally be unrealistic, but is accurate for SIH).
+
+For SIH on FC:
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d/airframes` and follows the naming template `${ID}_${model_name}.hil`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured with `HIL_ACT_FUNC*` parameters (not the usual `PWM_MAIN_FUNC*` parameters).
+ This is to avoid using the real actuator outputs in SIH.
+ Similarly, the bitfield for inverting individual actuator output ranges is `HIL_ACT_REV`, rather than `PWM_MAIN_REV`.
+
+For SIH as SITL (no FC):
+
+- Airframe file goes in `ROMFS/px4fmu_common/init.d-posix/airframes` and follows the naming template `${ID}_sihsim_${model_name}`, where `ID` is the `SYS_AUTOSTART_ID` used to select the airframe, and `model_name` is the airframe model name.
+- Add the model name in `src/modules/simulation/simulator_sih/CMakeLists.txt` to generate a corresponding make target.
+- Actuators are configured as usual with `PWM_MAIN_FUNC*` and `PWM_MAIN_REV`.
+- Additionally, set:
+ - `PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}`
+ - `PX4_SIM_MODEL=${PX4_SIM_MODEL:=svtol}` (replacing `svtol` with the airframe model name)
+- Enable the simulated sensors using [SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM), and [SENS_EN_ARSPDSIM](../advanced_config/parameter_reference.md#SENS_EN_ARSPDSIM) (this is only needed for SIH-as-SITL):
+ - `param set-default SENS_EN_GPSSIM 1`
+ - `param set-default SENS_EN_BAROSIM 1`
+ - `param set-default SENS_EN_MAGSIM 1`
+ - `param set-default SENS_EN_ARSPDSIM 1` (if it is a fixed-wing or VTOL airframe with airspeed sensor)
+
+For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC).
+
## Dynamic Models
The dynamic models for the various vehicles are: