Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DAC/AP_DAC_TIx3204.cpp
4182 views
1
/*
2
DAC backend for TIx3204 I2C DACs
3
*/
4
#include "AP_DAC_config.h"
5
6
#if AP_DAC_TIX3204_ENABLED
7
8
#include "AP_DAC.h"
9
#include "AP_DAC_TIx3204.h"
10
11
#include <AP_HAL/utility/sparse-endian.h>
12
#include <GCS_MAVLink/GCS.h>
13
#include <AP_HAL/I2CDevice.h>
14
15
// common registers
16
#define REG_TIx3204_NOP 0x00
17
#define REG_TIx3204_COMMON_CONFIG 0x1F
18
19
#define REG_TIx3204_CHAN_BASE 0x01 // offset to first channel
20
#define REG_TIx3204_CHAN_SKIP 6 // 6 registers per channel
21
22
// per channel config registers
23
#define REG_TIx3204_OFS_MARGIN_HIGH 0x00
24
#define REG_TIx3204_OFS_MARGIN_LOW 0x01
25
#define REG_TIx3204_OFS_VOUT_CMP_CONFIG 0x02
26
#define REG_TIx3204_OFS_IOUT_MISC_CONFIG 0x03
27
#define REG_TIx3204_OFS_CMP_MODE_CONFIG 0x04
28
#define REG_TIx3204_OFS_FUNC_CONFIG 0x05
29
30
// data registers
31
#define REG_TIx3204_DAC_DATA(chan) ((chan)+0x19)
32
33
extern const AP_HAL::HAL &hal;
34
35
void AP_DAC_TIx3204::init(void)
36
{
37
if (params.bus_address <= 0) {
38
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 address is 0");
39
return;
40
}
41
dev = std::move(hal.i2c_mgr->get_device(params.bus, params.bus_address));
42
if (!dev) {
43
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 device is null at %u:%", unsigned(params.bus), unsigned(params.bus_address));
44
return;
45
}
46
47
WITH_SEMAPHORE(dev->get_semaphore());
48
49
dev->set_retries(10);
50
51
uint16_t val = 17;
52
if (!register_read(REG_TIx3204_NOP, val) || val != 0) {
53
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 not found 0x%x at %u:%u", unsigned(val), unsigned(params.bus), unsigned(params.bus_address));
54
return;
55
}
56
57
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 found");
58
59
dev->set_retries(1);
60
}
61
62
// set voltage for a channel
63
bool AP_DAC_TIx3204::set_voltage(uint8_t chan, float v)
64
{
65
if (chan >= 4) {
66
return false;
67
}
68
69
// convert voltage to 12-bit value
70
uint16_t val = uint16_t(v * 4095.0f / params.voltage_reference);
71
if (val > 4095) {
72
val = 4095;
73
}
74
75
WITH_SEMAPHORE(dev->get_semaphore());
76
77
// write to data register first
78
if (!register_write(REG_TIx3204_DAC_DATA(chan), val<<4)) {
79
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 data write fail");
80
return false;
81
}
82
83
if (!configured[chan]) {
84
uint16_t config;
85
if (!register_read(REG_TIx3204_COMMON_CONFIG, config)) {
86
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 chan config read %u fail", unsigned(chan));
87
return false;
88
}
89
const uint8_t config_shift = chan*3;
90
const uint16_t config_mask = 0x7 << config_shift;
91
const uint16_t config_val = 0x1; // enable Vout
92
config = (config & ~config_mask) | (config_val << config_shift);
93
if (!register_write(REG_TIx3204_COMMON_CONFIG, config)) {
94
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 chan config %u fail", unsigned(chan));
95
return false;
96
}
97
configured[chan] = true;
98
}
99
return true;
100
}
101
102
bool AP_DAC_TIx3204::register_read(uint8_t reg, uint16_t &val)
103
{
104
uint16_t v;
105
if (!dev->read_registers(reg, (uint8_t*)&v, sizeof(v))) {
106
return false;
107
}
108
val = be16toh(v);
109
return true;
110
}
111
112
bool AP_DAC_TIx3204::register_write(uint8_t reg, uint16_t val)
113
{
114
uint8_t buf[3] { reg, uint8_t(val >> 8), uint8_t(val) };
115
return dev->transfer(buf, sizeof(buf), nullptr, 0);
116
}
117
118
#endif // AP_DAC_TIX3204_ENABLED
119
120