diff --git a/src/drivers/uavcan/sensors/gnss.cpp b/src/drivers/uavcan/sensors/gnss.cpp index db88941a56..7fa9e843f7 100644 --- a/src/drivers/uavcan/sensors/gnss.cpp +++ b/src/drivers/uavcan/sensors/gnss.cpp @@ -46,6 +46,7 @@ #include #include #include +#include #include using namespace time_literals; @@ -58,6 +59,7 @@ UavcanGnssBridge::UavcanGnssBridge(uavcan::INode &node) : _sub_auxiliary(node), _sub_fix(node), _sub_fix2(node), + _sub_gnss_heading(node), _pub_moving_baseline_data(node), _pub_rtcm_stream(node), _channel_using_fix2(new bool[_max_channels]) @@ -100,6 +102,12 @@ UavcanGnssBridge::init() return res; } + res = _sub_gnss_heading.start(RelPosHeadingCbBinder(this, &UavcanGnssBridge::gnss_relative_sub_cb)); + + if (res < 0) { + PX4_WARN("GNSS relative sub failed %i", res); + return res; + } // UAVCAN_PUB_RTCM int32_t uavcan_pub_rtcm = 0; @@ -295,6 +303,7 @@ UavcanGnssBridge::gnss_fix2_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + _rel_heading_valid = msg.reported_heading_acc_available; + _rel_heading = math::radians(msg.reported_heading_deg); + _rel_heading_accuracy = math::radians(msg.reported_heading_acc_deg); +} template void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure &msg, uint8_t fix_type, @@ -463,9 +480,21 @@ void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure report.vdop = msg.pdop; } - report.heading = heading; - report.heading_offset = heading_offset; - report.heading_accuracy = heading_accuracy; + // Use heading from RelPosHeading message if available and we have RTK Fixed solution. + if (_rel_heading_valid && (fix_type == sensor_gps_s::FIX_TYPE_RTK_FIXED)) { + report.heading = _rel_heading; + report.heading_offset = NAN; + report.heading_accuracy = _rel_heading_accuracy; + + _rel_heading = NAN; + _rel_heading_accuracy = NAN; + _rel_heading_valid = false; + + } else { + report.heading = heading; + report.heading_offset = heading_offset; + report.heading_accuracy = heading_accuracy; + } report.noise_per_ms = noise_per_ms; report.jamming_indicator = jamming_indicator; diff --git a/src/drivers/uavcan/sensors/gnss.hpp b/src/drivers/uavcan/sensors/gnss.hpp index f2f28eb5bc..f8205c3b38 100644 --- a/src/drivers/uavcan/sensors/gnss.hpp +++ b/src/drivers/uavcan/sensors/gnss.hpp @@ -55,6 +55,7 @@ #include #include #include +#include #include #include @@ -82,6 +83,7 @@ private: void gnss_auxiliary_sub_cb(const uavcan::ReceivedDataStructure &msg); void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure &msg); void gnss_fix2_sub_cb(const uavcan::ReceivedDataStructure &msg); + void gnss_relative_sub_cb(const uavcan::ReceivedDataStructure &msg); template void process_fixx(const uavcan::ReceivedDataStructure &msg, @@ -113,11 +115,16 @@ private: void (UavcanGnssBridge::*)(const uavcan::TimerEvent &)> TimerCbBinder; + typedef uavcan::MethodBinder < UavcanGnssBridge *, + void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure &) > + RelPosHeadingCbBinder; + uavcan::INode &_node; uavcan::Subscriber _sub_auxiliary; uavcan::Subscriber _sub_fix; uavcan::Subscriber _sub_fix2; + uavcan::Subscriber _sub_gnss_heading; uavcan::Publisher _pub_moving_baseline_data; uavcan::Publisher _pub_rtcm_stream; @@ -137,6 +144,10 @@ private: bool _publish_rtcm_stream{false}; bool _publish_moving_baseline_data{false}; + float _rel_heading_accuracy{NAN}; + float _rel_heading{NAN}; + bool _rel_heading_valid{false}; + perf_counter_t _rtcm_stream_pub_perf{nullptr}; perf_counter_t _moving_baseline_data_pub_perf{nullptr}; }; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index f83ba6e1e9..a40289f7b3 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2405,6 +2405,15 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps) return; //TODO: change and set to NAN } + if (fabsf(_param_ekf2_gps_yaw_off.get()) > 0.f) { + if (!PX4_ISFINITE(vehicle_gps_position.heading_offset) && PX4_ISFINITE(vehicle_gps_position.heading)) { + // Apply offset + float yaw_offset = matrix::wrap_pi(math::radians(_param_ekf2_gps_yaw_off.get())); + vehicle_gps_position.heading_offset = yaw_offset; + vehicle_gps_position.heading = matrix::wrap_pi(vehicle_gps_position.heading - yaw_offset); + } + } + const float altitude_amsl = static_cast(vehicle_gps_position.altitude_msl_m); const float altitude_ellipsoid = static_cast(vehicle_gps_position.altitude_ellipsoid_m); diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 61105a3c9b..0bec478e0d 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -537,6 +537,7 @@ private: // Used by EKF-GSF experimental yaw estimator (ParamExtFloat) _param_ekf2_gsf_tas_default, + (ParamFloat) _param_ekf2_gps_yaw_off, #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_BAROMETER) diff --git a/src/modules/ekf2/params_gnss.yaml b/src/modules/ekf2/params_gnss.yaml index 55c530a125..957d2d70a7 100644 --- a/src/modules/ekf2/params_gnss.yaml +++ b/src/modules/ekf2/params_gnss.yaml @@ -46,6 +46,15 @@ parameters: min: 1.0 unit: SD decimal: 1 + EKF2_GPS_YAW_OFF: + description: + short: Heading/Yaw offset for dual antenna GPS + type: float + default: 0.0 + min: 0.0 + max: 360.0 + unit: deg + decimal: 1 EKF2_GPS_V_GATE: description: short: Gate size for GNSS velocity fusion