mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: correct checking of valid instance in various getters
This commit is contained in:
parent
21a5618517
commit
b57b69685a
|
@ -214,15 +214,11 @@ void AP_Proximity::init(void)
|
||||||
void AP_Proximity::update(void)
|
void AP_Proximity::update(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<num_instances; i++) {
|
for (uint8_t i=0; i<num_instances; i++) {
|
||||||
if (drivers[i] != nullptr) {
|
if (!valid_instance(i)) {
|
||||||
if (get_type(i) == Type::None) {
|
|
||||||
// allow user to disable a proximity sensor at runtime
|
|
||||||
state[i].status = Proximity_NotConnected;
|
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
drivers[i]->update();
|
drivers[i]->update();
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
// work out primary instance - first sensor returning good data
|
// work out primary instance - first sensor returning good data
|
||||||
for (int8_t i=num_instances-1; i>=0; i--) {
|
for (int8_t i=num_instances-1; i>=0; i--) {
|
||||||
|
@ -235,7 +231,7 @@ void AP_Proximity::update(void)
|
||||||
// return sensor orientation
|
// return sensor orientation
|
||||||
uint8_t AP_Proximity::get_orientation(uint8_t instance) const
|
uint8_t AP_Proximity::get_orientation(uint8_t instance) const
|
||||||
{
|
{
|
||||||
if (instance >= PROXIMITY_MAX_INSTANCES) {
|
if (!valid_instance(instance)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -245,7 +241,7 @@ uint8_t AP_Proximity::get_orientation(uint8_t instance) const
|
||||||
// return sensor yaw correction
|
// return sensor yaw correction
|
||||||
int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const
|
int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const
|
||||||
{
|
{
|
||||||
if (instance >= PROXIMITY_MAX_INSTANCES) {
|
if (!valid_instance(instance)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -256,7 +252,7 @@ int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const
|
||||||
AP_Proximity::Proximity_Status AP_Proximity::get_status(uint8_t instance) const
|
AP_Proximity::Proximity_Status AP_Proximity::get_status(uint8_t instance) const
|
||||||
{
|
{
|
||||||
// sanity check instance number
|
// sanity check instance number
|
||||||
if (instance >= num_instances) {
|
if (!valid_instance(instance)) {
|
||||||
return Proximity_NotConnected;
|
return Proximity_NotConnected;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue