diff --git a/src/drivers/uavcan/sensors/gnss.cpp b/src/drivers/uavcan/sensors/gnss.cpp index fb02f1d274..36b57786f6 100644 --- a/src/drivers/uavcan/sensors/gnss.cpp +++ b/src/drivers/uavcan/sensors/gnss.cpp @@ -533,8 +533,7 @@ void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure sensor_gps.vdop = msg.pdop; } - // 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)) { + if (_rel_heading_valid) { sensor_gps.heading = _rel_heading; sensor_gps.heading_offset = NAN; sensor_gps.heading_accuracy = _rel_heading_accuracy;