SITL: Create gps_hdt_enabled varible for enable/disable HDT GPS sentence

This commit is contained in:
Grant Morphett 2017-05-28 14:08:14 +10:00 committed by Andrew Tridgell
parent d58783664d
commit 2ce7955614
2 changed files with 3 additions and 0 deletions

View File

@ -168,6 +168,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
AP_GROUPINFO("GND_BEHAV", 41, SITL, gnd_behav, -1),
AP_GROUPINFO("BARO_COUNT", 42, SITL, baro_count, 1),
AP_GROUPINFO("GPS_HDG", 43, SITL, gps_hdg_enabled, 0),
AP_GROUPEND
};

View File

@ -175,6 +175,7 @@ public:
AP_Int8 telem_baudlimit_enable; // enable baudrate limiting on links
AP_Float flow_noise; // optical flow measurement noise (rad/sec)
AP_Int8 baro_count; // number of simulated baros to create
AP_Int8 gps_hdg_enabled; // enable the output of a NMEA heading HDT sentence
// wind control
enum WindType {