Browse Source

ina23X: Support for ina23X power monitors

master
Thomas Debrunner 3 years ago committed by Beat Küng
parent
commit
b8d0bb44c4
  1. 1
      boards/px4/fmu-v5x/default.cmake
  2. 1
      boards/px4/fmu-v5x/init/rc.board_defaults
  3. 7
      boards/px4/fmu-v5x/init/rc.board_sensors
  4. 1
      boards/px4/fmu-v6x/default.cmake
  5. 3
      boards/px4/fmu-v6x/init/rc.board_defaults
  6. 7
      boards/px4/fmu-v6x/init/rc.board_sensors
  7. 1
      src/drivers/drv_sensor.h
  8. 44
      src/drivers/power_monitor/ina23X/CMakeLists.txt
  9. 341
      src/drivers/power_monitor/ina23X/ina23X.cpp
  10. 375
      src/drivers/power_monitor/ina23X/ina23X.h
  11. 130
      src/drivers/power_monitor/ina23X/ina23X_main.cpp
  12. 76
      src/drivers/power_monitor/ina23X/ina23X_params.c

1
boards/px4/fmu-v5x/default.cmake

@ -41,6 +41,7 @@ px4_add_board( @@ -41,6 +41,7 @@ px4_add_board(
pca9685_pwm_out
power_monitor/ina226
power_monitor/ina228
power_monitor/ina23X
#protocol_splitter
pwm_input
pwm_out_sim

1
boards/px4/fmu-v5x/init/rc.board_defaults

@ -3,6 +3,7 @@ @@ -3,6 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default SENS_EN_INA23X 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1

7
boards/px4/fmu-v5x/init/rc.board_sensors

@ -19,6 +19,13 @@ then @@ -19,6 +19,13 @@ then
ina228 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA23X 1
then
# Start Digital power monitors
ina23X -X -b 1 -t 1 -k start
ina23X -X -b 2 -t 2 -k start
fi
if ver hwtypecmp V5X90 V5X91 V5X92 V5Xa0 V5Xa1 V5Xa2
then
#SKYNODE base fmu board orientation

1
boards/px4/fmu-v6x/default.cmake

@ -42,6 +42,7 @@ px4_add_board( @@ -42,6 +42,7 @@ px4_add_board(
pca9685_pwm_out
power_monitor/ina226
power_monitor/ina228
power_monitor/ina23X
#protocol_splitter
pwm_out_sim
pwm_out

3
boards/px4/fmu-v6x/init/rc.board_defaults

@ -3,7 +3,8 @@ @@ -3,7 +3,8 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default SENS_EN_INA23X 0
param set-default SENS_EN_INA228 0
param set-default SENS_EN_INA226 1
safety_button start
safety_button start

7
boards/px4/fmu-v6x/init/rc.board_sensors

@ -18,6 +18,13 @@ then @@ -18,6 +18,13 @@ then
ina228 -X -b 2 -t 2 -k start
fi
if param compare SENS_EN_INA23X 1
then
# Start Digital power monitors
ina23X -X -b 1 -t 1 -k start
ina23X -X -b 2 -t 2 -k start
fi
# Internal SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start

1
src/drivers/drv_sensor.h

@ -182,6 +182,7 @@ @@ -182,6 +182,7 @@
#define DRV_DIST_DEVTYPE_GY_US42 0x9C
#define DRV_BAT_DEVTYPE_BATMON_SMBUS 0x9d
#define DRV_POWER_DEVTYPE_INA23X 0x9E
#define DRV_GPIO_DEVTYPE_MCP23009 0x9F
#define DRV_GPS_DEVTYPE_ASHTECH 0xA0

44
src/drivers/power_monitor/ina23X/CMakeLists.txt

@ -0,0 +1,44 @@ @@ -0,0 +1,44 @@
############################################################################
#
# Copyright (c) 2021 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__ina23X
MAIN ina23X
COMPILE_FLAGS
-Wno-cast-align # TODO: fix and enable
SRCS
ina23X_main.cpp
ina23X.cpp
DEPENDS
battery
px4_work_queue
)

341
src/drivers/power_monitor/ina23X/ina23X.cpp

@ -0,0 +1,341 @@ @@ -0,0 +1,341 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* Driver for the I2C attached INA23X
*/
#include "ina23X.h"
INA23X::INA23X(const I2CSPIDriverConfig &config, int battery_index) :
I2C(config),
ModuleParams(nullptr),
I2CSPIDriver(config),
_sample_perf(perf_alloc(PC_ELAPSED, "ina23X_read")),
_comms_errors(perf_alloc(PC_COUNT, "ina23X_com_err")),
_collection_errors(perf_alloc(PC_COUNT, "ina23X_collection_err")),
_measure_errors(perf_alloc(PC_COUNT, "ina23X_measurement_err")),
_config(INA23X_ADCCONFIG),
_battery(battery_index, this, INA23X_SAMPLE_INTERVAL_US)
{
float fvalue = DEFAULT_MAX_CURRENT;
_max_current = fvalue;
param_t ph = param_find("INA23X_CURRENT");
if (ph != PARAM_INVALID && param_get(ph, &fvalue) == PX4_OK) {
_max_current = fvalue;
}
_range = _max_current > (DEFAULT_MAX_CURRENT - 1.0f) ? INA23X_ADCRANGE_HIGH : INA23X_ADCRANGE_LOW;
fvalue = DEFAULT_SHUNT;
_rshunt = fvalue;
ph = param_find("INA23X_SHUNT");
if (ph != PARAM_INVALID && param_get(ph, &fvalue) == PX4_OK) {
_rshunt = fvalue;
}
ph = param_find("INA23X_CONFIG");
int32_t value = INA23X_ADCCONFIG;
_config = (uint16_t)value;
if (ph != PARAM_INVALID && param_get(ph, &value) == PX4_OK) {
_config = (uint16_t)value;
}
_mode_triggered = ((_config & INA23X_MODE_MASK) >> INA23X_MODE_SHIFTS) <=
((INA23X_MODE_TEMP_SHUNT_BUS_TRIG & INA23X_MODE_MASK) >>
INA23X_MODE_SHIFTS);
_current_lsb = _max_current / INA23X_DN_MAX;
// We need to publish immediately, to guarantee that the first instance of the driver publishes to uORB instance 0
_battery.updateBatteryStatus(
hrt_absolute_time(),
0.0,
0.0,
false,
battery_status_s::BATTERY_SOURCE_POWER_MODULE,
0,
0.0
);
}
INA23X::~INA23X()
{
/* free perf counters */
perf_free(_sample_perf);
perf_free(_comms_errors);
perf_free(_collection_errors);
perf_free(_measure_errors);
}
int INA23X::read(uint8_t address, uint16_t &data)
{
// read desired little-endian value via I2C
uint16_t received_bytes;
const int ret = transfer(&address, 1, (uint8_t *)&received_bytes, sizeof(received_bytes));
if (ret == PX4_OK) {
data = swap16(received_bytes);
} else {
perf_count(_comms_errors);
PX4_DEBUG("i2c::transfer returned %d", ret);
}
return ret;
}
int INA23X::write(uint8_t address, uint16_t value)
{
uint8_t data[3] = {address, ((uint8_t)((value & 0xff00) >> 8)), (uint8_t)(value & 0xff)};
return transfer(data, sizeof(data), nullptr, 0);
}
int INA23X::init()
{
int ret = PX4_ERROR;
/* do I2C init (and probe) first */
if (I2C::init() != PX4_OK) {
return ret;
}
write(INA23X_REG_CONFIG, (uint16_t)(INA23X_RST_RESET | _range));
uint16_t shunt_calibration = static_cast<uint16_t>(INA23X_CONST * _current_lsb * _rshunt);
if (_range == INA23X_ADCRANGE_LOW) {
shunt_calibration *= 4;
}
if (write(INA23X_REG_SHUNTCAL, shunt_calibration) < 0) {
return -3;
}
// Set the CONFIG for max I
write(INA23X_REG_CONFIG, (uint16_t) _range);
// If we run in continuous mode then start it here
if (!_mode_triggered) {
ret = write(INA23X_REG_ADCCONFIG, _config);
} else {
ret = PX4_OK;
}
start();
_sensor_ok = true;
_initialized = ret == PX4_OK;
return ret;
}
int INA23X::force_init()
{
int ret = init();
start();
return ret;
}
int INA23X::probe()
{
uint16_t value{0};
if (read(INA23X_MANUFACTURER_ID, value) != PX4_OK || value != INA23X_MFG_ID_TI) {
PX4_DEBUG("probe mfgid %d", value);
return -1;
}
if (read(INA23X_DEVICE_ID, value) != PX4_OK || (
INA23X_DEVICEID(value) != INA238_MFG_DIE &&
INA23X_DEVICEID(value) != INA239_MFG_DIE
)) {
PX4_DEBUG("probe die id %d", value);
return -1;
}
return PX4_OK;
}
int INA23X::measure()
{
int ret = PX4_OK;
if (_mode_triggered) {
ret = write(INA23X_REG_ADCCONFIG, _config);
if (ret < 0) {
perf_count(_comms_errors);
PX4_DEBUG("i2c::transfer returned %d", ret);
}
}
return ret;
}
int INA23X::collect()
{
perf_begin(_sample_perf);
if (_parameter_update_sub.updated()) {
// Read from topic to clear updated flag
parameter_update_s parameter_update;
_parameter_update_sub.copy(&parameter_update);
updateParams();
}
// read from the sensor
// Note: If the power module is connected backwards, then the values of _current will be negative but otherwise valid.
bool success{true};
int16_t bus_voltage{0};
int16_t current{0};
success = success && (read(INA23X_REG_VSBUS, bus_voltage) == PX4_OK);
success = success && (read(INA23X_REG_CURRENT, current) == PX4_OK);
if (!success) {
PX4_DEBUG("error reading from sensor");
bus_voltage = current = 0;
}
_actuators_sub.copy(&_actuator_controls);
_battery.updateBatteryStatus(
hrt_absolute_time(),
(float) bus_voltage * INA23X_VSCALE,
(float) current * _current_lsb,
success,
battery_status_s::BATTERY_SOURCE_POWER_MODULE,
0,
_actuator_controls.control[actuator_controls_s::INDEX_THROTTLE]
);
perf_end(_sample_perf);
if (success) {
return PX4_OK;
} else {
return PX4_ERROR;
}
}
void INA23X::start()
{
ScheduleClear();
/* reset the report ring and state machine */
_collect_phase = false;
_measure_interval = INA23X_CONVERSION_INTERVAL;
/* schedule a cycle to start things */
ScheduleDelayed(5);
}
void INA23X::RunImpl()
{
if (_initialized) {
if (_collect_phase) {
/* perform collection */
if (collect() != PX4_OK) {
perf_count(_collection_errors);
/* if error restart the measurement state machine */
start();
return;
}
/* next phase is measurement */
_collect_phase = !_mode_triggered;
if (_measure_interval > INA23X_CONVERSION_INTERVAL) {
/* schedule a fresh cycle call when we are ready to measure again */
ScheduleDelayed(_measure_interval - INA23X_CONVERSION_INTERVAL);
return;
}
}
/* Measurement phase */
/* Perform measurement */
if (measure() != PX4_OK) {
perf_count(_measure_errors);
}
/* next phase is collection */
_collect_phase = true;
/* schedule a fresh cycle call when the measurement is done */
ScheduleDelayed(INA23X_CONVERSION_INTERVAL);
} else {
_battery.updateBatteryStatus(
hrt_absolute_time(),
0.0f,
0.0f,
false,
battery_status_s::BATTERY_SOURCE_POWER_MODULE,
0,
0.0f
);
if (init() != PX4_OK) {
ScheduleDelayed(INA23X_INIT_RETRY_INTERVAL_US);
}
}
}
void INA23X::print_status()
{
I2CSPIDriverBase::print_status();
if (_initialized) {
perf_print_counter(_sample_perf);
perf_print_counter(_comms_errors);
printf("poll interval: %u \n", _measure_interval);
} else {
PX4_INFO("Device not initialized. Retrying every %d ms until battery is plugged in.",
INA23X_INIT_RETRY_INTERVAL_US / 1000);
}
}

375
src/drivers/power_monitor/ina23X/ina23X.h

@ -0,0 +1,375 @@ @@ -0,0 +1,375 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/getopt.h>
#include <drivers/device/i2c.h>
#include <lib/perf/perf_counter.h>
#include <battery/battery.h>
#include <drivers/drv_hrt.h>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/parameter_update.h>
#include <px4_platform_common/i2c_spi_buses.h>
using namespace time_literals;
/* Configuration Constants */
#define INA23X_BASEADDR 0x45 /* 7-bit address. 8-bit address is 0x45 */
// If initialization is forced (with the -f flag on the command line), but it fails, the drive will try again to
// connect to the INA23X every this many microseconds
#define INA23X_INIT_RETRY_INTERVAL_US 500000
/* INA23X Registers addresses */
#define INA23X_REG_CONFIG (0x00)
#define INA23X_REG_ADCCONFIG (0x01)
#define INA23X_REG_SHUNTCAL (0x02)
#define INA23X_REG_SHUNTTEMPCO (0x03)
#define INA23X_REG_VSHUNT (0x04)
#define INA23X_REG_VSBUS (0x05)
#define INA23X_REG_DIETEMP (0x06)
#define INA23X_REG_CURRENT (0x07)
#define INA23X_REG_POWER (0x08)
#define INA23X_REG_ENERGY (0x09)
#define INA23X_REG_CHARGE (0x0a)
#define INA23X_REG_DIAG_ALRT (0x0b)
#define INA23X_REG_SOVL (0x0c)
#define INA23X_REG_SUVL (0x0d)
#define INA23X_REG_BOVL (0x0e)
#define INA23X_REG_BUVL (0x0f)
#define INA23X_REG_TEMP_LIMIT (0x10)
#define INA23X_REG_TPWR_LIMIT (0x11)
#define INA23X_MANUFACTURER_ID (0x3e)
#define INA23X_DEVICE_ID (0x3f)
#define INA23X_MFG_ID_TI (0x5449) // TI
#define INA238_MFG_DIE (0x238) // INA237, INA238
#define INA239_MFG_DIE (0x239) // INA239
/* INA23X Configuration (CONFIG) 16-bit Register (Address = 0h) [reset = 0h] */
#define INA23X_ADCRANGE_SHIFTS (4)
#define INA23X_ADCRANGE_MASK (1 << INA23X_ADCRANGE_SHIFTS)
#define INA23X_ADCRANGE_LOW (1 << INA23X_ADCRANGE_SHIFTS) // ± 40.96 mV
#define INA23X_ADCRANGE_HIGH (0 << INA23X_ADCRANGE_SHIFTS) // ±163.84 mV
#define INA23X_TEMPCOMP_SHIFTS (5)
#define INA23X_TEMPCOMP_MASK (1 << INA23X_TEMPCOMP_SHIFTS)
#define INA23X_TEMPCOMP_ENABLE (1 << INA23X_TEMPCOMP_SHIFTS)
#define INA23X_TEMPCOMP_DISABLE (0 << INA23X_TEMPCOMP_SHIFTS)
#define INA23X_CONVDLY_SHIFTS (6)
#define INA23X_CONVDLY_MASK (0xff << INA23X_CONVDLY_SHIFTS)
#define INA23X_CONVDLY2MS(n) ((n) << INA23X_CONVDLY_SHIFTS)
#define INA23X_RSTACC_SHIFTS (14)
#define INA23X_RSTACC_MASK (1 << INA23X_RSTACC_SHIFTS)
#define INA23X_RSTACC_CLEAR (1 << INA23X_RSTACC_SHIFTS)
#define INA23X_RSTACC_NORMAL (0 << INA23X_RSTACC_SHIFTS)
#define INA23X_RST_SHIFTS (15)
#define INA23X_RST_MASK (1 << INA23X_RST_SHIFTS)
#define INA23X_RST_RESET (1 << INA23X_RST_SHIFTS)
#define INA23X_RST_NORMAL (0 << INA23X_RST_SHIFTS)
/* INA23X ADC Configuration (ADC_CONFIG) 16-bit Register (Address = 1h) [reset = FB68h] */
#define INA23X_MODE_SHIFTS (12)
#define INA23X_MODE_MASK (0xf << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUTDOWN_TRIG (0 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_BUS_TRIG (1 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUNT_TRIG (2 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUNT_BUS_TRIG (3 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_TRIG (4 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_BUS_TRIG (5 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_SHUNT_TRIG (6 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_SHUNT_BUS_TRIG (7 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUTDOWN_CONT (8 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_BUS_CONT (9 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUNT_CONT (10 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_SHUNT_BUS_CONT (11 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_CONT (12 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_BUS_CONT (13 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_SHUNT_CONT (14 << INA23X_MODE_SHIFTS)
#define INA23X_MODE_TEMP_SHUNT_BUS_CONT (15 << INA23X_MODE_SHIFTS)
#define INA23X_VBUSCT_SHIFTS (9)
#define INA23X_VBUSCT_MASK (7 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_50US (0 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_84US (1 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_150US (2 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_280US (3 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_540US (4 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_1052US (5 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_2074US (6 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VBUSCT_4170US (7 << INA23X_VBUSCT_SHIFTS)
#define INA23X_VSHCT_SHIFTS (6)
#define INA23X_VSHCT_MASK (7 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_50US (0 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_84US (1 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_150US (2 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_280US (3 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_540US (4 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_1052US (5 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_2074US (6 << INA23X_VSHCT_SHIFTS)
#define INA23X_VSHCT_4170US (7 << INA23X_VSHCT_SHIFTS)
#define INA23X_VTCT_SHIFTS (3)
#define INA23X_VTCT_MASK (7 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_50US (0 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_84US (1 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_150US (2 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_280US (3 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_540US (4 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_1052US (5 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_2074US (6 << INA23X_VTCT_SHIFTS)
#define INA23X_VTCT_4170US (7 << INA23X_VTCT_SHIFTS)
#define INA23X_AVERAGES_SHIFTS (0)
#define INA23X_AVERAGES_MASK (7 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_1 (0 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_4 (1 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_16 (2 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_64 (3 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_128 (4 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_256 (5 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_512 (6 << INA23X_AVERAGES_SHIFTS)
#define INA23X_AVERAGES_1024 (7 << INA23X_AVERAGES_SHIFTS)
#define INA23X_ADCCONFIG (INA23X_MODE_TEMP_SHUNT_BUS_CONT | INA23X_VBUSCT_540US | INA23X_VSHCT_540US | INA23X_VTCT_540US |INA23X_AVERAGES_64)
/* INA23X Shunt Calibration (SHUNT_CAL) 16-bit Register (Address = 2h) [reset = 1000h] */
#define INA23X_CURRLSB_SHIFTS (0)
#define INA23X_CURRLSB_MASK (0x7fff << INA23X_CURRLSB_SHIFTS)
/* INA23X Shunt Temperature Coefficient (SHUNT_TEMPCO) 16-bit Register (Address = 3h) [reset = 0h] */
#define INA23X_TEMPCO_SHIFTS (0)
#define INA23X_TEMPCO_MASK (0x1fff << INA23X_TEMPCO_SHIFTS)
/* INA23X Shunt Voltage Measurement (VSHUNT) 24-bit Register (Address = 4h) [reset = 0h] */
#define INA23X_VSHUNT_SHIFTS (4)
#define INA23X_VSHUNT_MASK (UINT32_C(0xffffff) << INA23X_VSHUNT_SHIFTS)
/* INA23X Bus Voltage Measurement (VBUS) 24-bit Register (Address = 5h) [reset = 0h] */
#define INA23X_VBUS_SHIFTS (4)
#define INA23X_VBUS_MASK (UINT32_C(0xffffff) << INA23X_VBUS_SHIFTS)
/* INA23X Temperature Measurement (DIETEMP) 16-bit Register (Address = 6h) [reset = 0h] */
#define INA23X_DIETEMP_SHIFTS (0)
#define INA23X_DIETEMP_MASK (0xffff << INA23X_DIETEMP_SHIFTS)
/* INA23X Current Result (CURRENT) 24-bit Register (Address = 7h) [reset = 0h] */
#define INA23X_CURRENT_SHIFTS (4)
#define INA23X_CURRENT_MASK (UINT32_C(0xffffff) << INA23X_CURRENT_SHIFTS)
/* INA23X Power Result (POWER) 24-bit Register (Address = 8h) [reset = 0h] */
#define INA23X_POWER_SHIFTS (0)
#define INA23X_POWER_MASK (UINT32_C(0xffffff) << INA23X_POWER_SHIFTS)
/* INA23X Energy Result (ENERGY) 40-bit Register (Address = 9h) [reset = 0h] */
#define INA23X_ENERGY_SHIFTS (0)
#define INA23X_ENERGY_MASK (UINT64_C(0xffffffffff) << INA23X_ENERGY_SHIFTS)
/* INA23X Energy Result (CHARGE) 40-bit Register (Address = Ah) [reset = 0h] */
#define INA23X_CHARGE_SHIFTS (0)
#define INA23X_CHARGE_MASK (UINT64_C(0xffffffffff) << INA23X_CHARGE_SHIFTS)
/* INA23X Diagnostic Flags and Alert (DIAG_ALRT) 16-bit Register (Address = Bh) [reset = 0001h] */
#define INA23X_MEMSTAT (1 << 0) // This bit is set to 0 if a checksum error is detected in the device trim memory space
#define INA23X_CNVRF (1 << 1) // This bit is set to 1 if the conversion is completed. When ALATCH =1 this bit is cleared by reading the register or starting a new triggered conversion.
#define INA23X_POL (1 << 2) // This bit is set to 1 if the power measurement exceeds the threshold limit in the power limit register.
#define INA23X_BUSUL (1 << 3) // This bit is set to 1 if the bus voltage measurement falls below the threshold limit in the bus under-limit register.
#define INA23X_BUSOL (1 << 4) // This bit is set to 1 if the bus voltage measurement exceeds the threshold limit in the bus over-limit register.
#define INA23X_SHNTUL (1 << 5) // This bit is set to 1 if the shunt voltage measurement falls below the threshold limit in the shunt under-limit register
#define INA23X_SHNTOL (1 << 6) // This bit is set to 1 if the shunt voltage measurement exceeds the threshold limit in the shunt over-limit register.
#define INA23X_TMPOL (1 << 7) // This bit is set to 1 if the temperature measurement exceeds the threshold limit in the temperature over-limit register.
#define INA23X_MATHOF (1 << 9) // This bit is set to 1 if an arithmetic operation resulted in an overflow error.
#define INA23X_CHARGEOF (1 << 10) // This bit indicates the health of the CHARGE register. If the 40 bit CHARGE register has overflowed this bit is set to 1.
#define INA23X_ENERGYOF (1 << 11) // This bit indicates the health of the ENERGY register. If the 40 bit ENERGY register has overflowed this bit is set to 1.
#define INA23X_APOL (1 << 12) // Alert Polarity bit sets the Alert pin polarity.
#define INA23X_SLOWALER (1 << 13) // ALERT function is asserted on the completed averaged value. This gives the flexibility to delay the ALERT after the averaged value.
#define INA23X_CNVR (1 << 14) // Setting this bit high configures the Alert pin to be asserted when the Conversion Ready Flag (bit 1) is asserted, indicating that a conversion cycle has completed
#define INA23X_ALATCH (1 << 15) // When the Alert Latch Enable bit is set to Transparent mode, the Alert pin and Flag bit reset to the idle state when the fault has been
// cleared. When the Alert Latch Enable bit is set to Latch mode, the Alert pin and Alert Flag bit remain active following a fault until
// the DIAG_ALRT Register has been read.
/* Shunt Overvoltage Threshold (SOVL) 16-bit Register (Address = Ch) [reset = 7FFFh] */
#define INA23X_SOVL_SHIFTS (0)
#define INA23X_SOVL_MASK (0xffff << INA23X_SOVL_SHIFTS)
/* Shunt Undervoltage Threshold (SUVL) 16-bit Register (Address = Dh) [reset = 8000h] */
#define INA23X_SUVL_SHIFTS (0)
#define INA23X_SUVL_MASK (0xffff << INA23X_SUVL_SHIFTS)
/* Bus Overvoltage Threshold (BOVL) 16-bit Register (Address = Eh) [reset = 7FFFh] */
#define INA23X_BOVL_SHIFTS (0)
#define INA23X_BOVL_MASK (0xffff << INA23X_BOVL_SHIFTS)
/* Bus Undervoltage Threshold (BUVL) 16-bit Register (Address = Fh) [reset = 0h] */
#define INA23X_BUVL_SHIFTS (0)
#define INA23X_BUVL_MASK (0xffff << INA23X_BUVL_SHIFTS)
/* Temperature Over-Limit Threshold (TEMP_LIMIT) 16-bit Register (Address = 10h) [reset = 7FFFh */
#define INA23X_TEMP_LIMIT_SHIFTS (0)
#define INA23X_TEMP_LIMIT_MASK (0xffff << INA23X_TEMP_LIMIT_SHIFTS)
/* Power Over-Limit Threshold (PWR_LIMIT) 16-bit Register (Address = 11h) [reset = FFFFh] */
#define INA23X_POWER_LIMIT_SHIFTS (0)
#define INA23X_POWER_LIMIT_MASK (0xffff << INA23X_POWER_LIMIT_SHIFTS)
/* Manufacturer ID (MANUFACTURER_ID) 16-bit Register (Address = 3Eh) [reset = 5449h] */
/* Device ID (DEVICE_ID) 16-bit Register (Address = 3Fh) [reset = 23X0h] */
#define INA23X_DEVICE_REV_ID_SHIFTS (0)
#define INA23X_DEVICE_REV_ID_MASK (0xf << INA23X_DEVICE_REV_ID_SHIFTS)
#define INA23X_DEVICEREV_ID(v) (((v) & INA23X_DEVICE_REV_ID_MASK) >> INA23X_DEVICE_REV_ID_SHIFTS)
#define INA23X_DEVICE_ID_SHIFTS (4)
#define INA23X_DEVICE_ID_MASK (0xfff << INA23X_DEVICE_ID_SHIFTS)
#define INA23X_DEVICEID(v) (((v) & INA23X_DEVICE_ID_MASK) >> INA23X_DEVICE_ID_SHIFTS)
#define INA23X_SAMPLE_FREQUENCY_HZ 10
#define INA23X_SAMPLE_INTERVAL_US (1_s / INA23X_SAMPLE_FREQUENCY_HZ)
#define INA23X_CONVERSION_INTERVAL (INA23X_SAMPLE_INTERVAL_US - 7)
#define INA23X_DN_MAX 32768.0f /* 2^15 */
#define INA23X_CONST 819.2e6f /* is an internal fixed value used to ensure scaling is maintained properly */
#define INA23X_VSCALE 3.125e-03f /* LSB of voltage is 3.1255 mV/LSB */
#define DEFAULT_MAX_CURRENT 327.68f /* Amps */
#define DEFAULT_SHUNT 0.0003f /* Shunt is 300 uOhm */
#define swap16(w) __builtin_bswap16((w))
#define swap32(d) __builtin_bswap32((d))
#define swap64(q) __builtin_bswap64((q))
class INA23X : public device::I2C, public ModuleParams, public I2CSPIDriver<INA23X>
{
public:
INA23X(const I2CSPIDriverConfig &config, int battery_index);
virtual ~INA23X();
static I2CSPIDriverBase *instantiate(const I2CSPIDriverConfig &config, int runtime_instance);
static void print_usage();
void RunImpl();
int init() override;
/**
* Tries to call the init() function. If it fails, then it will schedule to retry again in
* INA23X_INIT_RETRY_INTERVAL_US microseconds. It will keep retrying at this interval until initialization succeeds.
*
* @return PX4_OK if initialization succeeded on the first try. Negative value otherwise.
*/
int force_init();
/**
* Diagnostics - print some basic information about the driver.
*/
void print_status() override;
protected:
int probe() override;
private:
bool _sensor_ok{false};
unsigned int _measure_interval{0};
bool _collect_phase{false};
bool _initialized{false};
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _collection_errors;
perf_counter_t _measure_errors;
// Configuration state, computed from params
float _max_current;
float _rshunt;
float _current_lsb;
uint16_t _config;
int16_t _range;
bool _mode_triggered;
actuator_controls_s _actuator_controls{};
Battery _battery;
uORB::Subscription _actuators_sub{ORB_ID(actuator_controls_0)};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
int read(uint8_t address, uint16_t &data);
int write(uint8_t address, uint16_t data);
int read(uint8_t address, int16_t &data)
{
return read(address, (uint16_t &)data);
}
int write(uint8_t address, int16_t data)
{
return write(address, (uint16_t)data);
}
/**
* Initialise the automatic measurement state machine and start it.
*
* @note This function is called at open and error time. It might make sense
* to make it more aggressive about resetting the bus in case of errors.
*/
void start();
int measure();
int collect();
};

130
src/drivers/power_monitor/ina23X/ina23X_main.cpp

@ -0,0 +1,130 @@ @@ -0,0 +1,130 @@
/****************************************************************************
*
* Copyright (C) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include "ina23X.h"
I2CSPIDriverBase *INA23X::instantiate(const I2CSPIDriverConfig &config, int runtime_instance)
{
INA23X *instance = new INA23X(config, config.custom1);
if (instance == nullptr) {
PX4_ERR("alloc failed");
return nullptr;
}
if (config.keep_running) {
if (instance->force_init() != PX4_OK) {
PX4_INFO("Failed to init INA23X on bus %d, but will try again periodically.", config.bus);
}
} else if (instance->init() != PX4_OK) {
delete instance;
return nullptr;
}
return instance;
}
void
INA23X::print_usage()
{
PRINT_MODULE_DESCRIPTION(
R"DESCR_STR(
### Description
Driver for the INA23X power monitor.
Multiple instances of this driver can run simultaneously, if each instance has a separate bus OR I2C address.
For example, one instance can run on Bus 2, address 0x45, and one can run on Bus 2, address 0x45.
If the INA23X module is not powered, then by default, initialization of the driver will fail. To change this, use
the -f flag. If this flag is set, then if initialization fails, the driver will keep trying to initialize again
every 0.5 seconds. With this flag set, you can plug in a battery after the driver starts, and it will work. Without
this flag set, the battery must be plugged in before starting the driver.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("ina23X", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x45);
PRINT_MODULE_USAGE_PARAMS_I2C_KEEP_RUNNING_FLAG();
PRINT_MODULE_USAGE_PARAM_INT('t', 1, 1, 2, "battery index for calibration values (1 or 2)", true);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
extern "C" int
ina23X_main(int argc, char *argv[])
{
int ch;
using ThisDriver = INA23X;
BusCLIArguments cli{true, false};
cli.i2c_address = INA23X_BASEADDR;
cli.default_i2c_frequency = 100000;
cli.support_keep_running = true;
cli.custom1 = 1;
while ((ch = cli.getOpt(argc, argv, "t:")) != EOF) {
switch (ch) {
case 't': // battery index
cli.custom1 = (int)strtol(cli.optArg(), NULL, 0);
break;
}
}
const char *verb = cli.optArg();
if (!verb) {
ThisDriver::print_usage();
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_POWER_DEVTYPE_INA23X);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);
}
if (!strcmp(verb, "stop")) {
return ThisDriver::module_stop(iterator);
}
if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
ThisDriver::print_usage();
return -1;
}

76
src/drivers/power_monitor/ina23X/ina23X_params.c

@ -0,0 +1,76 @@ @@ -0,0 +1,76 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* Enable INA23X Power Monitor
*
* For systems a INA23X Power Monitor, this should be set to true
*
* @group Sensors
* @boolean
* @reboot_required true
*/
PARAM_DEFINE_INT32(SENS_EN_INA23X, 0);
/**
* INA23X Power Monitor Config
*
* @group Sensors
* @min 0
* @max 65535
* @decimal 1
* @increment 1
*/
PARAM_DEFINE_INT32(INA23X_CONFIG, 63779);
/**
* INA23X Power Monitor Max Current
*
* @group Sensors
* @min 0.1
* @max 327.68
* @decimal 2
* @increment 0.1
*/
PARAM_DEFINE_FLOAT(INA23X_CURRENT, 327.68f);
/**
* INA23X Power Monitor Shunt
*
* @group Sensors
* @min 0.000000001
* @max 0.1
* @decimal 10
* @increment .000000001
*/
PARAM_DEFINE_FLOAT(INA23X_SHUNT, 0.0003f);
Loading…
Cancel
Save