Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_DAC/AP_DAC_MCP40D1x.cpp
4182 views
1
/*
2
DAC backend for MCP40D1x I2C DACs
3
*/
4
#include "AP_DAC_config.h"
5
6
#if AP_DAC_MCP40D1X_ENABLED
7
8
#include "AP_DAC.h"
9
#include "AP_DAC_MCP40D1x.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
17
#define MCP40D1x_ADDR 0x2E
18
#define REG_MCP40D1x_NOP 0x00
19
#define REG_MCP40D1x_WIPER_DEFAULT 0x3F
20
21
#ifndef AP_DAC_MCP40D1X_CONVERSION_EQ
22
#define AP_DAC_MCP40D1X_CONVERSION_EQ(vo,vr) (vo * 127 / vr)
23
#endif
24
25
extern const AP_HAL::HAL &hal;
26
27
void AP_DAC_MCP40D1x::init(void)
28
{
29
if (params.bus_address <= 0) {
30
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MCP40D1x must be >0");
31
return;
32
}
33
if (!dev) {
34
dev = hal.i2c_mgr->get_device_ptr(params.bus, params.bus_address, 100000, true, 20);
35
}
36
37
if (!dev) {
38
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MCP40D1x device is null at %u:%", unsigned(params.bus), unsigned(params.bus_address));
39
return;
40
}
41
42
WITH_SEMAPHORE(dev->get_semaphore());
43
44
dev->set_speed(AP_HAL::Device::SPEED_HIGH);
45
46
uint8_t wiper_default = 0;
47
if (!dev->read_registers(REG_MCP40D1x_NOP, &wiper_default, 1)) {
48
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "MCP40D1x not found at %u:%x", unsigned(params.bus), unsigned(params.bus_address));
49
delete dev;
50
return;
51
}
52
initialized = true;
53
}
54
55
void AP_DAC_MCP40D1x::update(void)
56
{
57
set_voltage(0, params.voltage);
58
}
59
60
// set voltage for a channel
61
bool AP_DAC_MCP40D1x::set_voltage(uint8_t chan, float v)
62
{
63
if (!initialized) {
64
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MCP40D1x not initialized");
65
return false;
66
}
67
68
// convert voltage to 7-bit value
69
uint8_t wiper = uint8_t(roundf(AP_DAC_MCP40D1X_CONVERSION_EQ(v, params.voltage_reference)));
70
if (wiper > 127) {
71
wiper = 127;
72
}
73
74
// Currently only suitable for AP_Periph as called from the main thread
75
WITH_SEMAPHORE(dev->get_semaphore());
76
77
// write to data register first
78
if (!dev->write_register(REG_MCP40D1x_NOP, wiper, true)) {
79
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MCP40D1x wiper write fail: %x", unsigned(wiper));
80
return false;
81
}
82
83
return true;
84
}
85
86
#endif // AP_DAC_MCP40D1X_ENABLED
87
88