mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_Compass: cope with NULL dev pointer in driver probe functions
This commit is contained in:
parent
ba9b475782
commit
bd8867be38
@ -69,6 +69,9 @@ AP_Compass_Backend *AP_Compass_AK8963::probe(Compass &compass,
|
|||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
enum Rotation rotation)
|
enum Rotation rotation)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_AK8963_BusDriver *bus = new AP_AK8963_BusDriver_HALDevice(std::move(dev));
|
AP_AK8963_BusDriver *bus = new AP_AK8963_BusDriver_HALDevice(std::move(dev));
|
||||||
if (!bus) {
|
if (!bus) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
@ -87,6 +90,9 @@ AP_Compass_Backend *AP_Compass_AK8963::probe_mpu9250(Compass &compass,
|
|||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
||||||
enum Rotation rotation)
|
enum Rotation rotation)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
AP_InertialSensor &ins = *AP_InertialSensor::get_instance();
|
||||||
|
|
||||||
/* Allow MPU9250 to shortcut auxiliary bus and host bus */
|
/* Allow MPU9250 to shortcut auxiliary bus and host bus */
|
||||||
|
@ -65,6 +65,9 @@ extern const AP_HAL::HAL &hal;
|
|||||||
AP_Compass_Backend *AP_Compass_BMM150::probe(Compass &compass,
|
AP_Compass_Backend *AP_Compass_BMM150::probe(Compass &compass,
|
||||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(compass, std::move(dev));
|
AP_Compass_BMM150 *sensor = new AP_Compass_BMM150(compass, std::move(dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
|
@ -113,6 +113,9 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe(Compass &compass,
|
|||||||
bool force_external,
|
bool force_external,
|
||||||
enum Rotation rotation)
|
enum Rotation rotation)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
|
AP_HMC5843_BusDriver *bus = new AP_HMC5843_BusDriver_HALDevice(std::move(dev));
|
||||||
if (!bus) {
|
if (!bus) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
|
@ -162,6 +162,9 @@ AP_Compass_LSM303D::AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::
|
|||||||
AP_Compass_Backend *AP_Compass_LSM303D::probe(Compass &compass,
|
AP_Compass_Backend *AP_Compass_LSM303D::probe(Compass &compass,
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(compass, std::move(dev));
|
AP_Compass_LSM303D *sensor = new AP_Compass_LSM303D(compass, std::move(dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
|
@ -60,6 +60,9 @@ extern const AP_HAL::HAL &hal;
|
|||||||
AP_Compass_Backend *AP_Compass_LSM9DS1::probe(Compass &compass,
|
AP_Compass_Backend *AP_Compass_LSM9DS1::probe(Compass &compass,
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
AP_HAL::OwnPtr<AP_HAL::Device> dev)
|
||||||
{
|
{
|
||||||
|
if (!dev) {
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(compass, std::move(dev));
|
AP_Compass_LSM9DS1 *sensor = new AP_Compass_LSM9DS1(compass, std::move(dev));
|
||||||
if (!sensor || !sensor->init()) {
|
if (!sensor || !sensor->init()) {
|
||||||
delete sensor;
|
delete sensor;
|
||||||
|
Loading…
Reference in New Issue
Block a user