AP_Airspeed: added DEVID parameters for airspeed

this makes log analysis easier
This commit is contained in:
Andrew Tridgell 2021-06-30 12:35:45 +10:00
parent 7f85b413f2
commit ca1508b02e
11 changed files with 60 additions and 6 deletions

View File

@ -257,6 +257,23 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
// Note that 21, 22 and 23 are used above by the _OPTIONS, _WIND_MAX and _WIND_WARN parameters. Do not use them!!
// @Param: _DEVID
// @DisplayName: Airspeed ID
// @Description: Airspeed sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
AP_GROUPINFO_FLAGS("_DEVID", 24, AP_Airspeed, param[0].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#if AIRSPEED_MAX_SENSORS > 1
// @Param: 2_DEVID
// @DisplayName: Airspeed2 ID
// @Description: Airspeed2 sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
AP_GROUPINFO_FLAGS("2_DEVID", 25, AP_Airspeed, param[1].bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),
#endif
AP_GROUPEND
};

View File

@ -205,6 +205,7 @@ private:
AP_Int8 autocal;
AP_Int8 tube_order;
AP_Int8 skip_cal;
AP_Int32 bus_id;
} param[AIRSPEED_MAX_SENSORS];
struct airspeed_state {

View File

@ -54,6 +54,9 @@ bool AP_Airspeed_ASP5033::init()
continue;
}
dev->set_device_type(uint8_t(DevType::ASP5033));
set_bus_id(dev->get_bus_id());
dev->register_periodic_callback(1000000UL/80U,
FUNCTOR_BIND_MEMBER(&AP_Airspeed_ASP5033::timer, void));
return true;

View File

@ -86,6 +86,24 @@ protected:
frontend.param[instance].use.set(use);
}
// set bus ID of this instance, for ARSPD_DEVID parameters
void set_bus_id(uint32_t id) {
frontend.param[instance].bus_id.set(int32_t(id));
}
enum class DevType {
SITL = 0x01,
MS4525 = 0x02,
MS5525 = 0x03,
DLVR = 0x04,
MSP = 0x05,
SDP3X = 0x06,
UAVCAN = 0x07,
ANALOG = 0x08,
NMEA = 0x09,
ASP5033 = 0x0A,
};
private:
AP_Airspeed &frontend;
uint8_t instance;

View File

@ -43,10 +43,12 @@ bool AP_Airspeed_DLVR::init()
if (!dev) {
return false;
}
dev->get_semaphore()->take_blocking();
WITH_SEMAPHORE(dev->get_semaphore());
dev->set_speed(AP_HAL::Device::SPEED_LOW);
dev->set_retries(2);
dev->get_semaphore()->give();
dev->set_device_type(uint8_t(DevType::DLVR));
set_bus_id(dev->get_bus_id());
dev->register_periodic_callback(1000000UL/50U,
FUNCTOR_BIND_MEMBER(&AP_Airspeed_DLVR::timer, void));
return true;

View File

@ -90,6 +90,9 @@ bool AP_Airspeed_MS4525::init()
return false;
found_sensor:
_dev->set_device_type(uint8_t(DevType::MS4525));
set_bus_id(_dev->get_bus_id());
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS4525[%u]: Found bus %u addr 0x%02x", get_instance(), _dev->bus_num(), _dev->get_bus_address());
// drop to 2 retries for runtime

View File

@ -72,7 +72,7 @@ bool AP_Airspeed_MS5525::init()
if (!dev) {
continue;
}
dev->get_semaphore()->take_blocking();
WITH_SEMAPHORE(dev->get_semaphore());
// lots of retries during probe
dev->set_retries(5);
@ -83,7 +83,6 @@ bool AP_Airspeed_MS5525::init()
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: Found on bus %u addr 0x%02x", get_instance(), get_bus(), addresses[i]);
break;
}
dev->get_semaphore()->give();
}
if (!found) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: no sensor found", get_instance());
@ -91,16 +90,18 @@ bool AP_Airspeed_MS5525::init()
}
// Send a command to read temperature first
WITH_SEMAPHORE(dev->get_semaphore());
uint8_t reg = REG_CONVERT_TEMPERATURE;
dev->transfer(&reg, 1, nullptr, 0);
state = 0;
command_send_us = AP_HAL::micros();
dev->set_device_type(uint8_t(DevType::MS5525));
set_bus_id(dev->get_bus_id());
// drop to 2 retries for runtime
dev->set_retries(2);
dev->get_semaphore()->give();
// read at 80Hz
dev->register_periodic_callback(1000000UL/80U,
FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS5525::timer, void));

View File

@ -6,6 +6,7 @@ AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint
AP_Airspeed_Backend(_frontend, _instance),
msp_instance(_msp_instance)
{
set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_MSP,0,msp_instance,0));
}
// return the current differential_pressure in Pascal

View File

@ -42,6 +42,8 @@ bool AP_Airspeed_NMEA::init()
return false;
}
set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SERIAL,0,0,0));
_uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_AirSpeed, 0));
// make sure this sensor cannot be used in the EKF

View File

@ -143,6 +143,9 @@ bool AP_Airspeed_SDP3X::init()
set_skip_cal();
set_offset(0);
_dev->set_device_type(uint8_t(DevType::SDP3X));
set_bus_id(_dev->get_bus_id());
// drop to 2 retries for runtime
_dev->set_retries(2);

View File

@ -63,6 +63,9 @@ AP_Airspeed_Backend* AP_Airspeed_UAVCAN::probe(AP_Airspeed &_frontend, uint8_t _
"Registered UAVCAN Airspeed Node %d on Bus %d\n",
_detected_modules[i].node_id,
_detected_modules[i].ap_uavcan->get_driver_index());
backend->set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_UAVCAN,
_detected_modules[i].ap_uavcan->get_driver_index(),
_detected_modules[i].node_id, 0));
}
break;
}