mirror of https://github.com/ArduPilot/ardupilot
SITL: Create gps_hdt_enabled varible for enable/disable HDT GPS sentence
This commit is contained in:
parent
d58783664d
commit
2ce7955614
|
@ -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
|
||||
|
||||
};
|
||||
|
|
|
@ -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 {
|
||||
|
|
Loading…
Reference in New Issue