AP_Baro: don't panic when we can't find MS5611

this makes booting a PH2 without its sensor hat on much easier
This commit is contained in:
Andrew Tridgell 2016-11-09 20:42:29 +11:00
parent e27a76e460
commit fea7040aff

View File

@ -15,6 +15,7 @@
#include "AP_Baro_MS5611.h" #include "AP_Baro_MS5611.h"
#include <utility> #include <utility>
#include <stdio.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
@ -61,23 +62,24 @@ AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev
void AP_Baro_MS56XX::_init() void AP_Baro_MS56XX::_init()
{ {
if (!_dev) { if (!_dev) {
AP_HAL::panic("AP_Baro_MS56XX: failed to use device"); printf("MS5611: no device available");
return;
} }
_instance = _frontend.register_sensor();
if (!_dev->get_semaphore()->take(10)) { if (!_dev->get_semaphore()->take(10)) {
AP_HAL::panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init"); AP_HAL::panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init");
} }
_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
hal.scheduler->delay(4);
uint16_t prom[8]; uint16_t prom[8];
if (!_read_prom(prom)) { if (!_read_prom(prom)) {
AP_HAL::panic("Can't read PROM"); printf("MS5611: Can't read PROM on bus %d", _dev->get_bus_id());
_dev->get_semaphore()->give();
return;
} }
_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
hal.scheduler->delay(4);
// Save factory calibration coefficients // Save factory calibration coefficients
_cal_reg.c1 = prom[1]; _cal_reg.c1 = prom[1];
_cal_reg.c2 = prom[2]; _cal_reg.c2 = prom[2];
@ -92,6 +94,8 @@ void AP_Baro_MS56XX::_init()
memset(&_accum, 0, sizeof(_accum)); memset(&_accum, 0, sizeof(_accum));
_instance = _frontend.register_sensor();
_dev->get_semaphore()->give(); _dev->get_semaphore()->give();
/* Request 100Hz update */ /* Request 100Hz update */