diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 9dc49f4af2..eddc79356e 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -81,6 +81,7 @@ const AP_Param::GroupInfo SITL::var_info[] = { AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000), AP_GROUPINFO("MAG_ALY", 48, SITL, mag_anomaly_ned, 0), AP_GROUPINFO("MAG_ALY_HGT", 49, SITL, mag_anomaly_hgt, 1.0f), + AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0), AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 269ef55c0d..ded2d0e7cd 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -103,6 +103,7 @@ public: AP_Int16 flow_rate; // optflow data rate (Hz) AP_Int8 flow_delay; // optflow data delay AP_Int8 terrain_enable; // enable using terrain for height + AP_Int8 pin_mask; // for GPIO emulation // wind control float wind_speed_active;