AP_Baro: fix get_last_update(instance)

The method was not using the instance parameter. Instead it always use
primary barometer. Bug was not detected because method
get_last_update() is used where instance is _primary.

Detected with warnings, warnings are useful :-)
This commit is contained in:
Victor Lambret 2017-01-04 15:08:26 +01:00 committed by Francisco Ferreira
parent e32ddaa7fa
commit a4108251e3

View File

@ -92,7 +92,7 @@ public:
// get last time sample was taken (in ms)
uint32_t get_last_update(void) const { return get_last_update(_primary); }
uint32_t get_last_update(uint8_t instance) const { return sensors[_primary].last_update_ms; }
uint32_t get_last_update(uint8_t instance) const { return sensors[instance].last_update_ms; }
// settable parameters
static const struct AP_Param::GroupInfo var_info[];