forked from Archive/PX4-Autopilot
batt_smbus readd to configurations and fix compilation errors
This commit is contained in:
parent
b69a4df20c
commit
64fa1ec6a5
|
@ -12,31 +12,32 @@ set(config_module_list
|
|||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
drivers/mpu6000
|
||||
drivers/mpu9250
|
||||
drivers/oreoled
|
||||
drivers/pwm_input
|
||||
drivers/pwm_out_sim
|
||||
drivers/px4flow
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/rgbled
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/boards
|
||||
drivers/rgbled
|
||||
drivers/mpu6000
|
||||
drivers/mpu9250
|
||||
drivers/gps
|
||||
drivers/pwm_out_sim
|
||||
drivers/hott
|
||||
drivers/blinkm
|
||||
drivers/airspeed
|
||||
drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
drivers/mkblctrl
|
||||
drivers/px4flow
|
||||
drivers/oreoled
|
||||
drivers/vmount
|
||||
drivers/pwm_input
|
||||
drivers/camera_trigger
|
||||
drivers/bst
|
||||
modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
|
|
|
@ -12,6 +12,7 @@ set(config_module_list
|
|||
drivers/distance_sensor
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
|
|
|
@ -13,16 +13,16 @@ set(config_module_list
|
|||
drivers/magnetometer
|
||||
|
||||
drivers/airspeed
|
||||
drivers/barometer/mpl3115a2
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
#NOT Supported drivers/bma180
|
||||
#NOT Supported drivers/bmi160
|
||||
drivers/boards
|
||||
drivers/bst
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
drivers/frsky_telemetry
|
||||
drivers/fxos8701cq
|
||||
drivers/fxas21002c
|
||||
drivers/fxos8701cq
|
||||
drivers/gps
|
||||
drivers/hott
|
||||
drivers/iridiumsbd
|
||||
|
@ -32,7 +32,6 @@ set(config_module_list
|
|||
drivers/l3gd20
|
||||
drivers/led
|
||||
drivers/mkblctrl
|
||||
drivers/barometer/mpl3115a2
|
||||
drivers/mpu6000
|
||||
drivers/mpu9250
|
||||
drivers/oreoled
|
||||
|
|
|
@ -20,6 +20,7 @@ set(config_module_list
|
|||
|
||||
drivers/adis16448
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/bmi160
|
||||
drivers/boards
|
||||
|
|
|
@ -13,6 +13,7 @@ set(config_module_list
|
|||
drivers/magnetometer
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/bma180
|
||||
drivers/bmi055
|
||||
|
|
|
@ -13,6 +13,7 @@ set(config_module_list
|
|||
drivers/magnetometer
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/bma180
|
||||
drivers/bmi160
|
||||
|
|
|
@ -13,6 +13,7 @@ set(config_module_list
|
|||
drivers/magnetometer
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/bma180
|
||||
drivers/bmi055
|
||||
|
|
|
@ -16,18 +16,20 @@ set(config_module_list
|
|||
# Board support modules
|
||||
#
|
||||
drivers/airspeed
|
||||
drivers/device
|
||||
drivers/distance_sensor
|
||||
#drivers/barometer
|
||||
drivers/batt_smbus
|
||||
drivers/device
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
|
||||
modules/sensors
|
||||
platforms/posix/drivers/df_mpu9250_wrapper
|
||||
platforms/posix/drivers/df_lsm9ds1_wrapper
|
||||
platforms/posix/drivers/df_ms5611_wrapper
|
||||
|
||||
platforms/posix/drivers/df_hmc5883_wrapper
|
||||
platforms/posix/drivers/df_trone_wrapper
|
||||
platforms/posix/drivers/df_isl29501_wrapper
|
||||
platforms/posix/drivers/df_lsm9ds1_wrapper
|
||||
platforms/posix/drivers/df_mpu9250_wrapper
|
||||
platforms/posix/drivers/df_ms5611_wrapper
|
||||
platforms/posix/drivers/df_trone_wrapper
|
||||
|
||||
#
|
||||
# System commands
|
||||
|
|
|
@ -7,6 +7,7 @@ set(config_module_list
|
|||
drivers/distance_sensor
|
||||
|
||||
drivers/airspeed
|
||||
drivers/batt_smbus
|
||||
drivers/boards
|
||||
drivers/camera_trigger
|
||||
drivers/device
|
||||
|
|
|
@ -10,7 +10,7 @@ bool connected # Whether or not a battery is connected, based on a voltage thr
|
|||
bool system_source # Whether or not a this battery is the active power source for VDD_5V_IN
|
||||
uint8 priority # Zerro based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
|
||||
|
||||
#bool is_powering_off # Power off event imminent indication, false if unknown
|
||||
bool is_powering_off # Power off event imminent indication, false if unknown
|
||||
|
||||
|
||||
uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
|
||||
|
|
|
@ -39,43 +39,20 @@
|
|||
* @author Randy Mackay <rmackay9@yahoo.com>
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <sched.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
|
||||
#include <float.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_batt_smbus.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
#include <drivers/drv_batt_smbus.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4_config.h>
|
||||
#include <px4_workqueue.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
#define BATT_SMBUS_ADDR_MIN 0x08 ///< lowest possible address
|
||||
#define BATT_SMBUS_ADDR_MAX 0x7F ///< highest possible address
|
||||
|
@ -137,7 +114,7 @@ public:
|
|||
/**
|
||||
* ioctl for retrieving battery capacity and time to empty
|
||||
*/
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Test device
|
||||
|
@ -261,7 +238,7 @@ private:
|
|||
* Calculate PEC for a read or write from the battery
|
||||
* @param buff is the data that was read or will be written
|
||||
*/
|
||||
uint8_t get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const;
|
||||
uint8_t get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len);
|
||||
|
||||
/**
|
||||
* Write a word to Manufacturer Access register (0x00)
|
||||
|
@ -277,7 +254,7 @@ private:
|
|||
|
||||
// internal variables
|
||||
bool _enabled; ///< true if we have successfully connected to battery
|
||||
work_s _work; ///< work queue for scheduling reads
|
||||
work_s _work{}; ///< work queue for scheduling reads
|
||||
ringbuffer::RingBuffer *_reports; ///< buffer of recorded voltages, currents
|
||||
struct battery_status_s _last_report; ///< last published report, used for test()
|
||||
orb_advert_t _batt_topic; ///< uORB battery topic
|
||||
|
@ -310,7 +287,6 @@ int solo_battery_check();
|
|||
BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
|
||||
I2C("batt_smbus", BATT_SMBUS0_DEVICE_PATH, bus, batt_smbus_addr, 100000),
|
||||
_enabled(false),
|
||||
_work{},
|
||||
_reports(nullptr),
|
||||
_batt_topic(nullptr),
|
||||
_batt_orb_id(nullptr),
|
||||
|
@ -322,9 +298,6 @@ BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) :
|
|||
_is_solo_battery(false),
|
||||
_button_press_counts(0)
|
||||
{
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
|
||||
// capture startup time
|
||||
_start_time = hrt_absolute_time();
|
||||
}
|
||||
|
@ -360,7 +333,7 @@ BATT_SMBUS::init()
|
|||
ret = I2C::init();
|
||||
|
||||
if (ret != OK) {
|
||||
errx(1, "failed to init I2C");
|
||||
PX4_ERR("failed to init I2C");
|
||||
return ret;
|
||||
|
||||
} else {
|
||||
|
@ -383,7 +356,7 @@ BATT_SMBUS::init()
|
|||
}
|
||||
|
||||
int
|
||||
BATT_SMBUS::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
BATT_SMBUS::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
int ret = -ENODEV;
|
||||
|
||||
|
@ -423,8 +396,8 @@ BATT_SMBUS::test()
|
|||
|
||||
if (updated) {
|
||||
if (orb_copy(ORB_ID(battery_status), sub, &status) == OK) {
|
||||
warnx("V=%4.2f C=%4.2f DismAh=%4.2f Cap:%d Shutdown:%d", (double)status.voltage_v, (double)status.current_a,
|
||||
(double)status.discharged_mah, (int)_batt_capacity, (int)status.is_powering_off);
|
||||
PX4_INFO("V=%4.2f C=%4.2f DismAh=%4.2f Cap:%d Shutdown:%d", (double)status.voltage_v, (double)status.current_a,
|
||||
(double)status.discharged_mah, (int)_batt_capacity, (int)status.is_powering_off);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -447,7 +420,7 @@ BATT_SMBUS::search()
|
|||
set_device_address(i);
|
||||
|
||||
if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
|
||||
warnx("battery found at 0x%x", (int)i);
|
||||
PX4_INFO("battery found at 0x%x", (int)i);
|
||||
found_slave = true;
|
||||
}
|
||||
|
||||
|
@ -460,10 +433,10 @@ BATT_SMBUS::search()
|
|||
|
||||
// display completion message
|
||||
if (found_slave) {
|
||||
warnx("Done.");
|
||||
PX4_INFO("Done.");
|
||||
|
||||
} else {
|
||||
warnx("No smart batteries found.");
|
||||
PX4_WARN("No smart batteries found.");
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
@ -591,7 +564,7 @@ BATT_SMBUS::cycle()
|
|||
|
||||
// exit without rescheduling if we have failed to find a battery after 10 seconds
|
||||
if (!_enabled && (now - _start_time > BATT_SMBUS_TIMEOUT_US)) {
|
||||
warnx("did not find smart battery");
|
||||
PX4_WARN("did not find smart battery");
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -633,12 +606,12 @@ BATT_SMBUS::cycle()
|
|||
|
||||
// If necessary, check if the battery is a 3DR Solo Battery
|
||||
if (perform_solo_battry_check) {
|
||||
warnx("Checking solo battery");
|
||||
PX4_INFO("Checking solo battery");
|
||||
check_if_solo_battery();
|
||||
}
|
||||
|
||||
// read data from sensor
|
||||
struct battery_status_s new_report;
|
||||
battery_status_s new_report = {};
|
||||
|
||||
// set time of reading
|
||||
new_report.timestamp = now;
|
||||
|
@ -647,9 +620,6 @@ BATT_SMBUS::cycle()
|
|||
uint16_t tmp;
|
||||
|
||||
if (read_reg(BATT_SMBUS_VOLTAGE, tmp) == OK) {
|
||||
// initialise new_report
|
||||
memset(&new_report, 0, sizeof(new_report));
|
||||
|
||||
// convert millivolts to volts
|
||||
new_report.voltage_v = ((float)tmp) / 1000.0f;
|
||||
|
||||
|
@ -689,7 +659,7 @@ BATT_SMBUS::cycle()
|
|||
|
||||
// warn only once
|
||||
if (_button_press_counts++ == ((BATT_SMBUS_BUTTON_DEBOUNCE_MS * 1000) / BATT_SMBUS_MEASUREMENT_INTERVAL_US)) {
|
||||
warnx("system is shutting down NOW...");
|
||||
PX4_WARN("system is shutting down NOW...");
|
||||
}
|
||||
|
||||
} else if (pressed) {
|
||||
|
@ -713,7 +683,8 @@ BATT_SMBUS::cycle()
|
|||
_batt_topic = orb_advertise(_batt_orb_id, &new_report);
|
||||
|
||||
if (_batt_topic == nullptr) {
|
||||
errx(1, "ADVERT FAIL");
|
||||
PX4_ERR("ADVERT FAIL");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -773,7 +744,7 @@ BATT_SMBUS::write_reg(uint8_t reg, uint16_t val)
|
|||
int ret = transfer(buff, 3, nullptr, 0);
|
||||
|
||||
if (ret != OK) {
|
||||
debug("Register write error");
|
||||
PX4_DEBUG("Register write error");
|
||||
}
|
||||
|
||||
// return success or failure
|
||||
|
@ -837,7 +808,7 @@ BATT_SMBUS::write_block(uint8_t reg, uint8_t *data, uint8_t len)
|
|||
|
||||
// return zero on failure
|
||||
if (ret != OK) {
|
||||
debug("Block write error\n");
|
||||
PX4_DEBUG("Block write error");
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -846,7 +817,7 @@ BATT_SMBUS::write_block(uint8_t reg, uint8_t *data, uint8_t len)
|
|||
}
|
||||
|
||||
uint8_t
|
||||
BATT_SMBUS::get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const
|
||||
BATT_SMBUS::get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len)
|
||||
{
|
||||
// exit immediately if no data
|
||||
if (len <= 0) {
|
||||
|
@ -913,7 +884,7 @@ BATT_SMBUS::ManufacturerAccess(uint16_t cmd)
|
|||
int ret = write_reg(BATT_SMBUS_MANUFACTURER_ACCESS, cmd);
|
||||
|
||||
if (ret != OK) {
|
||||
debug("Manufacturer Access error");
|
||||
PX4_WARN("Manufacturer Access error");
|
||||
}
|
||||
|
||||
return ret;
|
||||
|
@ -934,10 +905,10 @@ BATT_SMBUS::check_if_solo_battery()
|
|||
void
|
||||
batt_smbus_usage()
|
||||
{
|
||||
warnx("missing command: try 'start', 'test', 'stop', 'search', 'man_name', 'man_date', 'dev_name', 'serial_num', 'dev_chem', 'sbs_info'");
|
||||
warnx("options:");
|
||||
warnx(" -b i2cbus (%d)", BATT_SMBUS_I2C_BUS);
|
||||
warnx(" -a addr (0x%x)", BATT_SMBUS_ADDR);
|
||||
PX4_INFO("missing command: try 'start', 'test', 'stop', 'search', 'man_name', 'man_date', 'dev_name', 'serial_num', 'dev_chem', 'sbs_info'");
|
||||
PX4_INFO("options:");
|
||||
PX4_INFO(" -b i2cbus (%d)", BATT_SMBUS_I2C_BUS);
|
||||
PX4_INFO(" -a addr (0x%x)", BATT_SMBUS_ADDR);
|
||||
}
|
||||
|
||||
int
|
||||
|
@ -947,11 +918,11 @@ manufacturer_name()
|
|||
uint8_t len = g_batt_smbus->manufacturer_name(man_name, sizeof(man_name));
|
||||
|
||||
if (len > 0) {
|
||||
warnx("The manufacturer name: %s", man_name);
|
||||
PX4_INFO("The manufacturer name: %s", man_name);
|
||||
return OK;
|
||||
|
||||
} else {
|
||||
warnx("Unable to read manufacturer name.");
|
||||
PX4_WARN("Unable to read manufacturer name.");
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
@ -967,11 +938,11 @@ manufacture_date()
|
|||
uint16_t year = ((man_date >> 9) & 0xFF) + 1980;
|
||||
uint8_t month = (man_date >> 5) & 0xF;
|
||||
uint8_t day = man_date & 0x1F;
|
||||
warnx("The manufacturer date is: %d which is %4d-%02d-%02d", man_date, year, month, day);
|
||||
PX4_INFO("The manufacturer date is: %d which is %4d-%02d-%02d", man_date, year, month, day);
|
||||
return OK;
|
||||
|
||||
} else {
|
||||
warnx("Unable to read the manufacturer date.");
|
||||
PX4_WARN("Unable to read the manufacturer date.");
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
@ -984,11 +955,11 @@ device_name()
|
|||
uint8_t len = g_batt_smbus->device_name(device_name, sizeof(device_name));
|
||||
|
||||
if (len > 0) {
|
||||
warnx("The device name: %s", device_name);
|
||||
PX4_INFO("The device name: %s", device_name);
|
||||
return OK;
|
||||
|
||||
} else {
|
||||
warnx("Unable to read device name.");
|
||||
PX4_WARN("Unable to read device name.");
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
@ -998,7 +969,7 @@ int
|
|||
serial_number()
|
||||
{
|
||||
uint16_t serial_num = g_batt_smbus->serial_number();
|
||||
warnx("The serial number: 0x%04x (%d in decimal)", serial_num, serial_num);
|
||||
PX4_INFO("The serial number: 0x%04x (%d in decimal)", serial_num, serial_num);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
@ -1010,11 +981,11 @@ device_chemistry()
|
|||
uint8_t len = g_batt_smbus->device_chemistry(device_chemistry, sizeof(device_chemistry));
|
||||
|
||||
if (len > 0) {
|
||||
warnx("The device chemistry: %s", device_chemistry);
|
||||
PX4_INFO("The device chemistry: %s", device_chemistry);
|
||||
return OK;
|
||||
|
||||
} else {
|
||||
warnx("Unable to read device chemistry.");
|
||||
PX4_INFO("Unable to read device chemistry.");
|
||||
}
|
||||
|
||||
return -1;
|
||||
|
@ -1024,10 +995,10 @@ int
|
|||
solo_battery_check()
|
||||
{
|
||||
if (g_batt_smbus->is_solo_battery()) {
|
||||
warnx("The battery corresponds to a 3DR Solo Battery");
|
||||
PX4_INFO("The battery corresponds to a 3DR Solo Battery");
|
||||
|
||||
} else {
|
||||
warnx("The battery does not correspond to a 3DR Solo Battery");
|
||||
PX4_INFO("The battery does not correspond to a 3DR Solo Battery");
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
@ -1045,11 +1016,11 @@ batt_smbus_main(int argc, char *argv[])
|
|||
while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'a':
|
||||
batt_smbusadr = strtol(optarg, NULL, 0);
|
||||
batt_smbusadr = strtol(optarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
case 'b':
|
||||
i2cdevice = strtol(optarg, NULL, 0);
|
||||
i2cdevice = strtol(optarg, nullptr, 0);
|
||||
break;
|
||||
|
||||
default:
|
||||
|
@ -1067,20 +1038,23 @@ batt_smbus_main(int argc, char *argv[])
|
|||
|
||||
if (!strcmp(verb, "start")) {
|
||||
if (g_batt_smbus != nullptr) {
|
||||
errx(1, "already started");
|
||||
PX4_ERR("already started");
|
||||
return 1;
|
||||
|
||||
} else {
|
||||
// create new global object
|
||||
g_batt_smbus = new BATT_SMBUS(i2cdevice, batt_smbusadr);
|
||||
|
||||
if (g_batt_smbus == nullptr) {
|
||||
errx(1, "new failed");
|
||||
PX4_ERR("new failed");
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (OK != g_batt_smbus->init()) {
|
||||
delete g_batt_smbus;
|
||||
g_batt_smbus = nullptr;
|
||||
errx(1, "init failed");
|
||||
PX4_ERR("init failed");
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1089,50 +1063,50 @@ batt_smbus_main(int argc, char *argv[])
|
|||
|
||||
// need the driver past this point
|
||||
if (g_batt_smbus == nullptr) {
|
||||
warnx("not started");
|
||||
PX4_INFO("not started");
|
||||
batt_smbus_usage();
|
||||
exit(1);
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "test")) {
|
||||
g_batt_smbus->test();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
delete g_batt_smbus;
|
||||
g_batt_smbus = nullptr;
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "search")) {
|
||||
g_batt_smbus->search();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "man_name")) {
|
||||
manufacturer_name();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "man_date")) {
|
||||
manufacture_date();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "dev_name")) {
|
||||
device_name();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "serial_num")) {
|
||||
serial_number();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "dev_chem")) {
|
||||
device_chemistry();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "sbs_info")) {
|
||||
|
@ -1146,5 +1120,5 @@ batt_smbus_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
batt_smbus_usage();
|
||||
exit(0);
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
*/
|
||||
|
||||
#define _BATT_SMBUS_IOCBASE (0x2e00)
|
||||
#define _BATT_SMBUS_IOC(_n) (_IOC(_BATT_SMBUS_IOCBASE, _n))
|
||||
#define _BATT_SMBUS_IOC(_n) (_PX4_IOC(_BATT_SMBUS_IOCBASE, _n))
|
||||
|
||||
/** retrieve battery capacity */
|
||||
#define BATT_SMBUS_GET_CAPACITY _BATT_SMBUS_IOC(1)
|
||||
|
|
Loading…
Reference in New Issue