Browse Source

batt_smbus: variable init cleanup + remove unused declarations

sbg
Beat Küng 5 years ago
parent
commit
3f3304fefc
  1. 37
      src/drivers/batt_smbus/batt_smbus.cpp
  2. 77
      src/drivers/batt_smbus/batt_smbus.h

37
src/drivers/batt_smbus/batt_smbus.cpp

@ -47,20 +47,7 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]); @@ -47,20 +47,7 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]);
BATT_SMBUS::BATT_SMBUS(SMBus *interface, const char *path) :
ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
_interface(interface),
_cycle(perf_alloc(PC_ELAPSED, "batt_smbus_cycle")),
_batt_topic(nullptr),
_cell_count(4),
_batt_capacity(0),
_batt_startup_capacity(0),
_cycle_count(0),
_serial_number(0),
_crit_thr(0.0f),
_emergency_thr(0.0f),
_low_thr(0.0f),
_manufacturer_name(nullptr),
_lifetime_max_delta_cell_voltage(0.0f),
_cell_undervoltage_protection_status(1)
_interface(interface)
{
battery_status_s new_report = {};
_batt_topic = orb_advertise(ORB_ID(battery_status), &new_report);
@ -90,8 +77,6 @@ BATT_SMBUS::~BATT_SMBUS() @@ -90,8 +77,6 @@ BATT_SMBUS::~BATT_SMBUS()
int battsource = 0;
param_set(param_find("BAT_SOURCE"), &battsource);
PX4_WARN("Exiting.");
}
int BATT_SMBUS::task_spawn(int argc, char *argv[])
@ -494,9 +479,11 @@ int BATT_SMBUS::manufacturer_name(uint8_t *man_name, const uint8_t length) @@ -494,9 +479,11 @@ int BATT_SMBUS::manufacturer_name(uint8_t *man_name, const uint8_t length)
return result;
}
void BATT_SMBUS::print_report()
int BATT_SMBUS::print_status()
{
PX4_INFO("Running");
print_message(_last_report);
return 0;
}
int BATT_SMBUS::manufacturer_read(const uint16_t cmd_code, void *data, const unsigned length)
@ -618,11 +605,6 @@ int BATT_SMBUS::custom_command(int argc, char *argv[]) @@ -618,11 +605,6 @@ int BATT_SMBUS::custom_command(int argc, char *argv[])
return 0;
}
if (!strcmp(input, "report")) {
obj->print_report();
return 0;
}
if (!strcmp(input, "suspend")) {
obj->suspend();
return 0;
@ -688,14 +670,13 @@ $ batt_smbus -X write_flash 19069 2 27 0 @@ -688,14 +670,13 @@ $ batt_smbus -X write_flash 19069 2 27 0
PRINT_MODULE_USAGE_NAME("batt_smbus", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAM_STRING('X', "BATT_SMBUS_BUS_I2C_EXTERNAL", nullptr, nullptr, true);
PRINT_MODULE_USAGE_PARAM_STRING('T', "BATT_SMBUS_BUS_I2C_EXTERNAL1", nullptr, nullptr, true);
PRINT_MODULE_USAGE_PARAM_STRING('R', "BATT_SMBUS_BUS_I2C_EXTERNAL2", nullptr, nullptr, true);
PRINT_MODULE_USAGE_PARAM_STRING('I', "BATT_SMBUS_BUS_I2C_INTERNAL", nullptr, nullptr, true);
PRINT_MODULE_USAGE_PARAM_STRING('A', "BATT_SMBUS_BUS_ALL", nullptr, nullptr, true);
PRINT_MODULE_USAGE_PARAM_FLAG('X', "BATT_SPARD_BUS_I2C_EXTERNAL", true);
PRINT_MODULE_USAGE_PARAM_FLAG('T', "BATT_SPARD_BUS_I2C_EXTERNAL1", true);
PRINT_MODULE_USAGE_PARAM_FLAG('R', "BATT_SPARD_BUS_I2C_EXTERNAL2", true);
PRINT_MODULE_USAGE_PARAM_FLAG('I', "BATT_SPARD_BUS_I2C_INTERNAL", true);
PRINT_MODULE_USAGE_PARAM_FLAG('A', "BATT_SPARD_BUS_ALL", true);
PRINT_MODULE_USAGE_COMMAND_DESCR("man_info", "Prints manufacturer info.");
PRINT_MODULE_USAGE_COMMAND_DESCR("report", "Prints the last report.");
PRINT_MODULE_USAGE_COMMAND_DESCR("unseal", "Unseals the devices flash memory to enable write_flash commands.");
PRINT_MODULE_USAGE_COMMAND_DESCR("seal", "Seals the devices flash memory to disbale write_flash commands.");
PRINT_MODULE_USAGE_COMMAND_DESCR("suspend", "Suspends the driver from rescheduling the cycle.");

77
src/drivers/batt_smbus/batt_smbus.h

@ -125,26 +125,6 @@ struct batt_smbus_bus_option { @@ -125,26 +125,6 @@ struct batt_smbus_bus_option {
#endif
};
/**
* @brief Nuttshell accessible method to return the battery manufacture date.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
*/
int manufacture_date();
/**
* @brief Nuttshell accessible method to return the battery manufacturer name.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
*/
int manufacturer_name();
/**
* @brief Nuttshell accessible method to return the battery serial number.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
*/
int serial_number();
class BATT_SMBUS : public ModuleBase<BATT_SMBUS>, public px4::ScheduledWorkItem
{
public:
@ -164,6 +144,9 @@ public: @@ -164,6 +144,9 @@ public:
/** @see ModuleBase */
static int task_spawn(int argc, char *argv[]);
/** @see ModuleBase::print_status() */
int print_status() override;
/**
* @brief Reads data from flash.
* @param address The address to start the read from.
@ -193,12 +176,6 @@ public: @@ -193,12 +176,6 @@ public:
*/
int get_startup_info();
/**
* @brief Prints the latest report.
*/
void print_report();
/**
* @brief Gets the SBS manufacture date of the battery.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
@ -232,12 +209,6 @@ public: @@ -232,12 +209,6 @@ public:
*/
int manufacturer_write(const uint16_t cmd_code, void *data, const unsigned length);
/**
* @brief Search all possible slave addresses for a smart battery.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
*/
int search_addresses();
/**
* @brief Unseals the battery to allow writing to restricted flash.
* @return Returns PX4_OK on success, PX4_ERROR on failure.
@ -273,19 +244,20 @@ public: @@ -273,19 +244,20 @@ public:
*/
void set_undervoltage_protection(float average_current);
SMBus *_interface;
void suspend();
void resume();
private:
protected:
void Run() override;
perf_counter_t _cycle;
private:
SMBus *_interface;
perf_counter_t _cycle{perf_alloc(PC_ELAPSED, "batt_smbus_cycle")};
float _cell_voltages[4] = {};
float _cell_voltages[4] {};
float _max_cell_voltage_delta{0};
@ -294,45 +266,44 @@ private: @@ -294,45 +266,44 @@ private:
bool _should_suspend{false};
/** @param _last_report Last published report, used for test(). */
battery_status_s _last_report = battery_status_s{};
battery_status_s _last_report{};
/** @param _batt_topic uORB battery topic. */
orb_advert_t _batt_topic;
orb_advert_t _batt_topic{nullptr};
/** @param _cell_count Number of series cell. */
uint8_t _cell_count;
uint8_t _cell_count{4};
/** @param _batt_capacity Battery design capacity in mAh (0 means unknown). */
uint16_t _batt_capacity;
uint16_t _batt_capacity{0};
/** @param _batt_startup_capacity Battery remaining capacity in mAh on startup. */
uint16_t _batt_startup_capacity;
uint16_t _batt_startup_capacity{0};
/** @param _cycle_count The number of cycles the battery has experienced. */
uint16_t _cycle_count;
uint16_t _cycle_count{0};
/** @param _serial_number Serial number register. */
uint16_t _serial_number;
uint16_t _serial_number{0};
/** @param _crit_thr Critical battery threshold param. */
float _crit_thr;
float _crit_thr{0.f};
/** @param _emergency_thr Emergency battery threshold param. */
float _emergency_thr;
float _emergency_thr{0.f};
/** @param _low_thr Low battery threshold param. */
float _low_thr;
float _low_thr{0.f};
/** @param _manufacturer_name Name of the battery manufacturer. */
char *_manufacturer_name;
char *_manufacturer_name{nullptr};
/** @param _lifetime_max_delta_cell_voltage Max lifetime delta of the battery cells */
float _lifetime_max_delta_cell_voltage;
float _lifetime_max_delta_cell_voltage{0.f};
/** @param _cell_undervoltage_protection_status 0 if protection disabled, 1 if enabled */
uint8_t _cell_undervoltage_protection_status;
uint8_t _cell_undervoltage_protection_status{1};
/** Do not allow copy construction or move assignment of this class. */
BATT_SMBUS(const BATT_SMBUS &);
BATT_SMBUS operator=(const BATT_SMBUS &);
BATT_SMBUS(const BATT_SMBUS &) = delete;
BATT_SMBUS operator=(const BATT_SMBUS &) = delete;
};

Loading…
Cancel
Save