PX4 Firmware
PX4 Autopilot Software http://px4.io
voxlpm.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2019 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 voxlpm.hpp
36  *
37  * Shared defines for the voxlpm (QTY2 LTC2946) driver.
38  *
39  * This is roughly what's goin on:
40  *
41  * +~~~~~~~~~~~~~~+
42  * VBATT -----| RSENSE_VBATT | ----------+---------------------> VBATT TO ESCS
43  * | +~~~~~~~~~~~~~~+ |
44  * | | +--------+------+
45  * +----+ +----+ | 5V REGULATOR |
46  * | | +--------+------+
47  * | | | +~~~~~~~~~~~~~~+
48  * | | +---| RSENSE_5VOUT |---> 5VDC TO COMPUTE
49  * | | | +~~~~~~~~~~~~~~+
50  * | | | |
51  * V| |A V| |A
52  * ################# #################
53  * # LTC2946, 0x6a # # LTC2946, 0x6b #
54  * ################# #################
55  *
56  * Publishes: Publishes:
57  * - ORB_ID(battery_status)
58  * - ORB_ID(power_monitor) - ORB_ID(power_monitor)
59  *
60  */
61 #pragma once
62 
63 #include <drivers/device/i2c.h>
64 #include <perf/perf_counter.h>
65 
66 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
67 
68 #include <battery/battery.h>
69 
70 #include <uORB/uORB.h>
73 
74 /*
75  * Note that these are unshifted addresses.
76  */
77 #define VOXLPM_LTC2946_ADDR_VBATT 0x6a // 0x6a = 0xd4 >> 1
78 #define VOXLPM_LTC2946_ADDR_P5VD 0x6b // 0x6b = 0xd6 >> 1
79 
80 #define VOXLPM_LTC2946_CTRLA_REG 0x00
81 #define VOXLPM_LTC2946_CTRLB_REG 0x01
82 
83 #define VOXLPM_LTC2946_POWER_MSB2_REG 0x05
84 #define VOXLPM_LTC2946_CTRLB_MSG1_REG 0x06
85 #define VOXLPM_LTC2946_CTRLB_LSB_REG 0x07
86 
87 #define VOXLPM_LTC2946_DELTA_SENSE_MSB_REG 0x14
88 #define VOXLPM_LTC2946_DELTA_SENSE_LSB_REG 0x15
89 
90 #define VOXLPM_LTC2946_VIN_MSB_REG 0x1E
91 #define VOXLPM_LTC2946_VIN_LSB_REG 0x1F
92 
93 /*
94  * CTRLA (Address 0x00 - LTC2946_CTRLA_REG)
95  *
96  * 7 - [ADIN Configuration]
97  * 0 --> ADIN Measured with Respect to GND
98  * 6:5 - [Offset Calibratoin Configuration]
99  * 00 --> Every Conversion
100  * 4:3 - [Voltage Selection]
101  * 11 --> SENSE+
102  * 2:0 - [Channel Configuration]
103  * 000 --> Alternate Voltage, Current Measurement
104  */
105 #define DEFAULT_CTRLA_REG_VAL 0x18
106 
107 /*
108  * CTRLB (Address 0x01 - LTC2946_CTRLA_REG)
109  *
110  * 7 - [!ALERT Clear Enable ]
111  * 0 --> Disable
112  * 6 - [Shutdown]
113  * 0 --> Power-Up
114  * 5 - [Cleared on Read Control]
115  * 0 --> Registers Not Affected by Reading
116  * 4 - [Stuck Bus Timeout Auto Wake-Up]
117  * 0 --> Disable
118  * 3:2 - [Enable Accumulation]
119  * 00 --> Accumulate
120  * 1:0 - [Auto-Reset Mode/Reset]
121  * 01 --> Enable Auto-Reset
122  */
123 #define DEFAULT_CTRLB_REG_VAL 0x01
124 
125 /* 12 bits */
126 #define VOXLPM_LTC2946_RESOLUTION 4095.0f
127 
128 /* VFS Full-Scale Voltage, SENSE+ */
129 #define VOXLPM_LTC2946_VFS_SENSE 102.4f
130 
131 /* VFS Full-Scale Voltage, delta sense */
132 #define VOXLPM_LTC2946_VFS_DELTA_SENSE 0.1024f
133 
134 /* Power sense resistor for battery current */
135 #define VOXLPM_RSENSE_VBATT 0.0005f
136 
137 /* Power sense resistor for 5VDC output current */
138 #define VOXLPM_RSENSE_5VOUT 0.005f
139 
143 };
144 
145 class VOXLPM : public device::I2C, public px4::ScheduledWorkItem
146 {
147 public:
148  VOXLPM(const char *path, int bus, int address, VOXLPM_CH_TYPE ch_type);
149  virtual ~VOXLPM();
150 
151  virtual int init();
152  void print_info();
153 
154 private:
155  unsigned _meas_interval{100000}; // 100ms
156  void Run() override;
157  void start();
158  void stop();
159  int measure();
160 
162 
165 
168 
170  float _voltage;
171  float _amperage;
172  float _rsense;
173 
175 
176  uint8_t read_reg(uint8_t addr);
177  int read_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len);
178  int write_reg(uint8_t value, uint8_t addr);
179 };
float _amperage
Definition: voxlpm.hpp:171
perf_counter_t _sample_perf
Definition: voxlpm.hpp:161
void print_info()
Definition: voxlpm.cpp:93
API for the uORB lightweight object broker.
VOXLPM_CH_TYPE
Definition: voxlpm.hpp:140
struct power_monitor_s _pm_status
Definition: voxlpm.hpp:167
int read_reg_buf(uint8_t addr, uint8_t *buf, uint8_t len)
Definition: voxlpm.cpp:225
unsigned _meas_interval
Definition: voxlpm.hpp:155
int write_reg(uint8_t value, uint8_t addr)
Definition: voxlpm.cpp:232
float _voltage
Definition: voxlpm.hpp:170
struct battery_status_s _bat_status
Definition: voxlpm.hpp:166
VOXLPM_CH_TYPE _ch_type
Definition: voxlpm.hpp:169
Library calls for battery functionality.
void Run() override
Definition: voxlpm.cpp:128
Battery _battery
Definition: voxlpm.hpp:174
Header common to all counters.
orb_advert_t _bat_pub_topic
Definition: voxlpm.hpp:163
void stop()
Definition: voxlpm.cpp:122
VOXLPM(const char *path, int bus, int address, VOXLPM_CH_TYPE ch_type)
Definition: voxlpm.cpp:46
float _rsense
Definition: voxlpm.hpp:172
void start()
Definition: voxlpm.cpp:111
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
uint8_t read_reg(uint8_t addr)
Definition: voxlpm.cpp:216
virtual int init()
Definition: voxlpm.cpp:73
int measure()
Definition: voxlpm.cpp:134
orb_advert_t _pm_pub_topic
Definition: voxlpm.hpp:164
virtual ~VOXLPM()
Definition: voxlpm.cpp:65
Performance measuring tools.
Base class for devices connected via I2C.