PX4 Firmware
PX4 Autopilot Software http://px4.io
batt_smbus.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file batt_smbus.h
36  *
37  * Header for a battery monitor connected via SMBus (I2C).
38  * Designed for BQ40Z50-R1/R2
39  *
40  * @author Jacob Dahl <dahl.jakejacob@gmail.com>
41  * @author Alex Klimaj <alexklimaj@gmail.com>
42  */
43 
44 #pragma once
45 
46 #include <ecl/geo/geo.h>
48 #include <mathlib/mathlib.h>
49 #include <perf/perf_counter.h>
50 #include <px4_platform_common/module.h>
51 #include <px4_platform_common/getopt.h>
52 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
54 
55 #include "board_config.h"
56 
57 #define DATA_BUFFER_SIZE 32
58 
59 #define BATT_CELL_VOLTAGE_THRESHOLD_RTL 0.5f ///< Threshold in volts to RTL if cells are imbalanced
60 #define BATT_CELL_VOLTAGE_THRESHOLD_FAILED 1.5f ///< Threshold in volts to Land if cells are imbalanced
61 
62 #define BATT_CURRENT_UNDERVOLTAGE_THRESHOLD 5.0f ///< Threshold in amps to disable undervoltage protection
63 #define BATT_VOLTAGE_UNDERVOLTAGE_THRESHOLD 3.4f ///< Threshold in volts to re-enable undervoltage protection
64 
65 #define BATT_SMBUS_ADDR 0x0B ///< Default 7 bit address I2C address. 8 bit = 0x16
66 
67 #define BATT_SMBUS_CURRENT 0x0A ///< current register
68 #define BATT_SMBUS_AVERAGE_CURRENT 0x0B ///< current register
69 #define BATT_SMBUS_TEMP 0x08 ///< temperature register
70 #define BATT_SMBUS_VOLTAGE 0x09 ///< voltage register
71 #define BATT_SMBUS_FULL_CHARGE_CAPACITY 0x10 ///< capacity when fully charged
72 #define BATT_SMBUS_RUN_TIME_TO_EMPTY 0x11 ///< predicted remaining battery capacity based on the present rate of discharge in min
73 #define BATT_SMBUS_AVERAGE_TIME_TO_EMPTY 0x12 ///< predicted remaining battery capacity based on the present rate of discharge in min
74 #define BATT_SMBUS_REMAINING_CAPACITY 0x0F ///< predicted remaining battery capacity as a percentage
75 #define BATT_SMBUS_CYCLE_COUNT 0x17 ///< number of cycles the battery has experienced
76 #define BATT_SMBUS_DESIGN_CAPACITY 0x18 ///< design capacity register
77 #define BATT_SMBUS_DESIGN_VOLTAGE 0x19 ///< design voltage register
78 #define BATT_SMBUS_MANUFACTURER_NAME 0x20 ///< manufacturer name
79 #define BATT_SMBUS_MANUFACTURE_DATE 0x1B ///< manufacture date register
80 #define BATT_SMBUS_SERIAL_NUMBER 0x1C ///< serial number register
81 #define BATT_SMBUS_MEASUREMENT_INTERVAL_US 100000 ///< time in microseconds, measure at 10Hz
82 #define BATT_SMBUS_MANUFACTURER_ACCESS 0x00
83 #define BATT_SMBUS_MANUFACTURER_DATA 0x23
84 #define BATT_SMBUS_MANUFACTURER_BLOCK_ACCESS 0x44
85 #define BATT_SMBUS_SECURITY_KEYS 0x0035
86 #define BATT_SMBUS_CELL_1_VOLTAGE 0x3F
87 #define BATT_SMBUS_CELL_2_VOLTAGE 0x3E
88 #define BATT_SMBUS_CELL_3_VOLTAGE 0x3D
89 #define BATT_SMBUS_CELL_4_VOLTAGE 0x3C
90 #define BATT_SMBUS_LIFETIME_FLUSH 0x002E
91 #define BATT_SMBUS_LIFETIME_BLOCK_ONE 0x0060
92 #define BATT_SMBUS_ENABLED_PROTECTIONS_A_ADDRESS 0x4938
93 #define BATT_SMBUS_SEAL 0x0030
94 
95 #define BATT_SMBUS_ENABLED_PROTECTIONS_A_DEFAULT 0xcf
96 #define BATT_SMBUS_ENABLED_PROTECTIONS_A_CUV_DISABLED 0xce
97 
98 #define NUM_BUS_OPTIONS (sizeof(smbus_bus_options)/sizeof(smbus_bus_options[0]))
99 
106 };
107 
110  const char *devpath;
111  uint8_t busnum;
112 } const smbus_bus_options[] = {
113  { BATT_SMBUS_BUS_I2C_EXTERNAL, "/dev/batt_smbus_ext", PX4_I2C_BUS_EXPANSION},
114 #ifdef PX4_I2C_BUS_EXPANSION1
115  { BATT_SMBUS_BUS_I2C_EXTERNAL1, "/dev/batt_smbus_ext1", PX4_I2C_BUS_EXPANSION1},
116 #endif
117 #ifdef PX4_I2C_BUS_EXPANSION2
118  { BATT_SMBUS_BUS_I2C_EXTERNAL2, "/dev/batt_smbus_ext2", PX4_I2C_BUS_EXPANSION2},
119 #endif
120 #ifdef PX4_I2C_BUS_ONBOARD
121  { BATT_SMBUS_BUS_I2C_INTERNAL, "/dev/batt_smbus_int", PX4_I2C_BUS_ONBOARD},
122 #endif
123 };
124 
125 class BATT_SMBUS : public ModuleBase<BATT_SMBUS>, public px4::ScheduledWorkItem
126 {
127 public:
128 
129  BATT_SMBUS(SMBus *interface, const char *path);
130 
131  ~BATT_SMBUS();
132 
133  friend SMBus;
134 
135  /** @see ModuleBase */
136  static int print_usage();
137 
138  /** @see ModuleBase */
139  static int custom_command(int argc, char *argv[]);
140 
141  /** @see ModuleBase */
142  static int task_spawn(int argc, char *argv[]);
143 
144  /** @see ModuleBase::print_status() */
145  int print_status() override;
146 
147  /**
148  * @brief Reads data from flash.
149  * @param address The address to start the read from.
150  * @param data The returned data.
151  * @return Returns PX4_OK on success, PX4_ERROR on failure.
152  */
153  int dataflash_read(uint16_t &address, void *data);
154 
155  /**
156  * @brief Writes data to flash.
157  * @param address The start address of the write.
158  * @param data The data to be written.
159  * @param length The number of bytes being written.
160  * @return Returns PX4_OK on success, PX4_ERROR on failure.
161  */
162  int dataflash_write(uint16_t &address, void *data, const unsigned length);
163 
164  /**
165  * @brief Returns the SBS serial number of the battery device.
166  * @return Returns the SBS serial number of the battery device.
167  */
168  uint16_t get_serial_number();
169 
170  /**
171  * @brief Read info from battery on startup.
172  * @return Returns PX4_OK on success, PX4_ERROR on failure.
173  */
174  int get_startup_info();
175 
176  /**
177  * @brief Gets the SBS manufacture date of the battery.
178  * @return Returns PX4_OK on success, PX4_ERROR on failure.
179  */
180  int manufacture_date();
181 
182  /**
183  * @brief Gets the SBS manufacturer name of the battery device.
184  * @param manufacturer_name Pointer to a buffer into which the manufacturer name is to be written.
185  * @param max_length The maximum number of bytes to attempt to read from the manufacturer name register,
186  * including the null character that is appended to the end.
187  * @return Returns PX4_OK on success, PX4_ERROR on failure.
188  */
189  int manufacturer_name(uint8_t *manufacturer_name, const uint8_t length);
190 
191  /**
192  * @brief Performs a ManufacturerBlockAccess() read command.
193  * @param cmd_code The command code.
194  * @param data The returned data.
195  * @param length The number of bytes being written.
196  * @return Returns PX4_OK on success, PX4_ERROR on failure.
197  */
198  int manufacturer_read(const uint16_t cmd_code, void *data, const unsigned length);
199 
200  /**
201  * @brief Performs a ManufacturerBlockAccess() write command.
202  * @param cmd_code The command code.
203  * @param data The sent data.
204  * @param length The number of bytes being written.
205  * @return Returns PX4_OK on success, PX4_ERROR on failure.
206  */
207  int manufacturer_write(const uint16_t cmd_code, void *data, const unsigned length);
208 
209  /**
210  * @brief Unseals the battery to allow writing to restricted flash.
211  * @return Returns PX4_OK on success, PX4_ERROR on failure.
212  */
213  int unseal();
214 
215  /**
216  * @brief Seals the battery to disallow writing to restricted flash.
217  * @return Returns PX4_OK on success, PX4_ERROR on failure.
218  */
219  int seal();
220 
221  /**
222  * @brief This command flushes the RAM Lifetime Data to data flash to help streamline evaluation testing.
223  * @return Returns PX4_OK on success, PX4_ERROR on failure.
224  */
225  int lifetime_data_flush();
226 
227  /**
228  * @brief Reads the lifetime data from block 1.
229  * @return Returns PX4_OK on success, PX4_ERROR on failure.
230  */
231  int lifetime_read_block_one();
232 
233  /**
234  * @brief Reads the cell voltages.
235  * @return Returns PX4_OK on success or associated read error code on failure.
236  */
237  int get_cell_voltages();
238 
239  /**
240  * @brief Enables or disables the cell under voltage protection emergency shut off.
241  */
242  void set_undervoltage_protection(float average_current);
243 
244  void suspend();
245 
246  void resume();
247 
248 protected:
249 
250  void Run() override;
251 
252 private:
254 
255  perf_counter_t _cycle{perf_alloc(PC_ELAPSED, "batt_smbus_cycle")};
256 
257  float _cell_voltages[4] {};
258 
259  float _max_cell_voltage_delta{0};
260 
261  float _min_cell_voltage{0};
262 
263  /** @param _last_report Last published report, used for test(). */
264  battery_status_s _last_report{};
265 
266  /** @param _batt_topic uORB battery topic. */
267  orb_advert_t _batt_topic{nullptr};
268 
269  /** @param _cell_count Number of series cell. */
270  uint8_t _cell_count{4};
271 
272  /** @param _batt_capacity Battery design capacity in mAh (0 means unknown). */
273  uint16_t _batt_capacity{0};
274 
275  /** @param _batt_startup_capacity Battery remaining capacity in mAh on startup. */
276  uint16_t _batt_startup_capacity{0};
277 
278  /** @param _cycle_count The number of cycles the battery has experienced. */
279  uint16_t _cycle_count{0};
280 
281  /** @param _serial_number Serial number register. */
282  uint16_t _serial_number{0};
283 
284  /** @param _crit_thr Critical battery threshold param. */
285  float _crit_thr{0.f};
286 
287  /** @param _emergency_thr Emergency battery threshold param. */
288  float _emergency_thr{0.f};
289 
290  /** @param _low_thr Low battery threshold param. */
291  float _low_thr{0.f};
292 
293  /** @param _manufacturer_name Name of the battery manufacturer. */
294  char *_manufacturer_name{nullptr};
295 
296  /** @param _lifetime_max_delta_cell_voltage Max lifetime delta of the battery cells */
297  float _lifetime_max_delta_cell_voltage{0.f};
298 
299  /** @param _cell_undervoltage_protection_status 0 if protection disabled, 1 if enabled */
300  uint8_t _cell_undervoltage_protection_status{1};
301 
302  BATT_SMBUS(const BATT_SMBUS &) = delete;
303  BATT_SMBUS operator=(const BATT_SMBUS &) = delete;
304 };
measure the time elapsed performing an event
Definition: perf_counter.h:56
Definition of geo / math functions to perform geodesic calculations.
void print_status()
Definition: Commander.cpp:517
static void print_usage()
const char * devpath
Definition: batt_smbus.h:110
Header common to all counters.
#define perf_alloc(a, b)
Definition: px4io.h:59
SMBus v2.0 protocol implementation.
uint8_t * data
Definition: dataman.cpp:149
struct batt_smbus_bus_option smbus_bus_options[]
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
friend SMBus
Definition: batt_smbus.h:133
BATT_SMBUS_BUS
Definition: batt_smbus.h:100
enum BATT_SMBUS_BUS busid
Definition: batt_smbus.h:109
Definition: SMBus.hpp:47
SMBus * _interface
Definition: batt_smbus.h:253
Performance measuring tools.