mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: added get_address()
allows AP_Periph to supply sensor_id for multiple CAN rangefinders
This commit is contained in:
parent
5100c9fb8c
commit
603e5c4b55
|
@ -144,6 +144,11 @@ public:
|
|||
return id >= RANGEFINDER_MAX_INSTANCES? Type::NONE : Type(params[id].type.get());
|
||||
}
|
||||
|
||||
// get rangefinder address (for AP_Periph CAN)
|
||||
uint8_t get_address(uint8_t id) const {
|
||||
return id >= RANGEFINDER_MAX_INSTANCES? 0 : uint8_t(params[id].address.get());
|
||||
}
|
||||
|
||||
// methods to return a distance on a particular orientation from
|
||||
// any sensor which can current supply it
|
||||
uint16_t distance_cm_orient(enum Rotation orientation) const;
|
||||
|
|
Loading…
Reference in New Issue