mirror of https://github.com/ArduPilot/ardupilot
parent
1a04eadb63
commit
1603869140
|
@ -81,6 +81,7 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
|||
// @Units: deg
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_DIR", 10, SIM, wind_direction, 180),
|
||||
|
||||
// @Param: WIND_TURB
|
||||
// @DisplayName: Simulated Wind variation
|
||||
// @Description: Allows you to emulate random wind variations in sim
|
||||
|
@ -88,6 +89,13 @@ const AP_Param::GroupInfo SIM::var_info[] = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_TURB", 11, SIM, wind_turbulance, 0),
|
||||
|
||||
// @Param: WIND_TC
|
||||
// @DisplayName: Wind variation time constant
|
||||
// @Description: this controls the time over which wind changes take effect
|
||||
// @Units: s
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("WIND_TC", 12, SIM, wind_change_tc, 5),
|
||||
|
||||
// @Group: SERVO_
|
||||
// @Path: ./ServoModel.cpp
|
||||
AP_SUBGROUPINFO(servo, "SERVO_", 16, SIM, ServoParams),
|
||||
|
|
|
@ -349,6 +349,7 @@ public:
|
|||
AP_Float wind_direction;
|
||||
AP_Float wind_turbulance;
|
||||
AP_Float wind_dir_z;
|
||||
AP_Float wind_change_tc;
|
||||
AP_Int8 wind_type; // enum WindLimitType
|
||||
AP_Float wind_type_alt;
|
||||
AP_Float wind_type_coef;
|
||||
|
|
Loading…
Reference in New Issue