Skip to content

Commit

Permalink
SITL: create GPS heading offset parameter
Browse files Browse the repository at this point in the history
  • Loading branch information
Williangalvani committed Jan 31, 2024
1 parent b119a2a commit d3a9cd0
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ void GPS::update()

d.latitude = latitude;
d.longitude = longitude;
d.yaw_deg = _sitl->state.yawDeg;
d.yaw_deg = _sitl->state.yawDeg + _sitl->gps_heading_offset[idx];;
d.roll_deg = _sitl->state.rollDeg;
d.pitch_deg = _sitl->state.pitchDeg;

Expand Down
13 changes: 13 additions & 0 deletions libraries/SITL/SITL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -575,6 +575,11 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @User: Advanced
// @Values: 0:Disabled, 1:Enabled
AP_GROUPINFO("GPS_JAM", 16, SIM, gps_jam[0], 0),
// @Param: GPS_HDG_OFS
// @DisplayName: GPS heading offset
// @Description: GPS heading offset in degrees. how off the GPS heading is from the actual heading
// @User: Advanced
AP_GROUPINFO("GPS_HDG_OFS", 17, SIM, gps_heading_offset[0], 0),
// @Param: GPS2_DISABLE
// @DisplayName: GPS 2 disable
// @Description: Disables GPS 2
Expand Down Expand Up @@ -678,12 +683,20 @@ const AP_Param::GroupInfo SIM::var_gps[] = {
// @Description: Log number for GPS:update_file()
AP_GROUPINFO("GPS_LOG_NUM", 48, SIM, gps_log_num, 0),

<<<<<<< HEAD
// @Param: GPS2_JAM
// @DisplayName: GPS jamming enable
// @Description: Enable simulated GPS jamming
// @User: Advanced
// @Values: 0:Disabled, 1:Enabled
AP_GROUPINFO("GPS2_JAM", 49, SIM, gps_jam[1], 0),
=======
// @Param: GPS2_HDG_OFS
// @DisplayName: GPS2 heading offset
// @Description: GPS heading offset in degrees. how off the GPS heading is from the actual heading
// @User: Advanced
AP_GROUPINFO("GPS2_HDG_OFS", 49, SIM, gps_heading_offset[1], 0),
>>>>>>> c519c9d26f (SITL: create GPS heading offset parameter)

AP_GROUPEND
};
Expand Down
1 change: 1 addition & 0 deletions libraries/SITL/SITL.h
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,7 @@ class SIM {
AP_Vector3f gps_glitch[2]; // glitch offsets in lat, lon and altitude
AP_Int8 gps_hertz[2]; // GPS update rate in Hz
AP_Int8 gps_hdg_enabled[2]; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED
AP_Float gps_heading_offset[2]; // heading offset for GpsForYaw
AP_Float gps_drift_alt[2]; // altitude drift error
AP_Vector3f gps_pos_offset[2]; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
AP_Float gps_accuracy[2];
Expand Down

0 comments on commit d3a9cd0

Please sign in to comment.