Replay: fix build error due to missing noreturn

Add noreturn attribute to field_not_found(). This function always call
abort() if the field was not found. The compiler may not know about it
and may think some variables are used uninitialized:

../../Tools/Replay/LR_MsgHandler.cpp: In member function ‘void LR_MsgHandler_GPA_Base::update_from_msg_gpa(uint8_t, uint8_t*)’:
../../Tools/Replay/LR_MsgHandler.cpp:212:24: error: ‘sacc’ may be used uninitialized in this function [-Werror=maybe-uninitialized]
     gps.setHIL_Accuracy(gps_offset, vdop*0.01f, hacc*0.01f, vacc*0.01f, sacc*0.01f, have_vertical_velocity, sample_ms);
                        ^

Instead of just initializing the variable (which is pointless in this case),
teach the compiler that this function never returns so require_field() works
properly.
This commit is contained in:
Lucas De Marchi 2016-05-10 11:42:01 -03:00
parent 68ae619448
commit cb0ffc0e07

View File

@ -85,7 +85,7 @@ protected:
const char *label_roll,
const char *label_pitch,
const char *label_yaw);
void field_not_found(uint8_t *msg, const char *label);
[[noreturn]] void field_not_found(uint8_t *msg, const char *label);
};
template<typename R>