diff --git a/src/drivers/uavcan/sensors/fuel_tank_status.cpp b/src/drivers/uavcan/sensors/fuel_tank_status.cpp index 3a8e74344461..7834ef64258b 100644 --- a/src/drivers/uavcan/sensors/fuel_tank_status.cpp +++ b/src/drivers/uavcan/sensors/fuel_tank_status.cpp @@ -57,6 +57,12 @@ int UavcanFuelTankStatusBridge::init() return res; } + // Fetch maximum fuel capacity (in liters) + param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); + + // Fetching fuel type + param_get(param_find("UAVCAN_ECU_FUELT"), &_fuel_type); + return 0; } @@ -65,16 +71,7 @@ void UavcanFuelTankStatusBridge::fuel_tank_status_sub_cb(const { auto report = ::fuel_tank_status_s(); report.timestamp = hrt_absolute_time(); - - // Fetching maximum fuel capacity (in liters) from a parameter - param_get(param_find("UAVCAN_ECU_MAXF"), &_max_fuel_capacity); - - _max_fuel_capacity *= 1000.0f; // convert to ml - report.maximum_fuel_capacity = _max_fuel_capacity; - - // Fetching fuel type - param_get(param_find("UAVCAN_ECU_FUELT"), &_fuel_type); - + report.maximum_fuel_capacity = _max_fuel_capacity * 1000.0f; // convert to ml report.fuel_type = static_cast(_fuel_type); report.consumed_fuel = NAN; // only the remaining fuel is measured report.fuel_consumption_rate = msg.fuel_consumption_rate_cm3pm / 60.0f; // convert to ml/s diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index ad8765470c13..edd2c41ea4c3 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -107,6 +107,7 @@ PARAM_DEFINE_FLOAT(UAVCAN_RNG_MAX, 200.0f); * @unit liters * @decimal 1 * @increment 0.1 + * @reboot_required true * @group UAVCAN */ PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f); @@ -125,6 +126,7 @@ PARAM_DEFINE_FLOAT(UAVCAN_ECU_MAXF, 15.0f); * @value 0 Unknown * @value 1 Liquid * @value 2 Gas + * @reboot_required true * @group UAVCAN */ PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1);