mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Rangefinder: preserve new address
This commit is contained in:
parent
a22bf84cae
commit
85d2acc7ba
@ -84,6 +84,11 @@ bool AP_RangeFinder_VL53L1X::check_id(void)
|
||||
}
|
||||
|
||||
bool AP_RangeFinder_VL53L1X::reset(void) {
|
||||
if (dev->get_bus_id()!=0x29) {
|
||||
// if sensor is on a different port than the default do not reset sensor otherwise we will lose the addess.
|
||||
// we assume it is already confirgured.
|
||||
return true;
|
||||
}
|
||||
if (!write_register(SOFT_RESET, 0x00)) {
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user