Path: blob/master/libraries/AP_DAC/AP_DAC_TIx3204.cpp
4182 views
/*1DAC backend for TIx3204 I2C DACs2*/3#include "AP_DAC_config.h"45#if AP_DAC_TIX3204_ENABLED67#include "AP_DAC.h"8#include "AP_DAC_TIx3204.h"910#include <AP_HAL/utility/sparse-endian.h>11#include <GCS_MAVLink/GCS.h>12#include <AP_HAL/I2CDevice.h>1314// common registers15#define REG_TIx3204_NOP 0x0016#define REG_TIx3204_COMMON_CONFIG 0x1F1718#define REG_TIx3204_CHAN_BASE 0x01 // offset to first channel19#define REG_TIx3204_CHAN_SKIP 6 // 6 registers per channel2021// per channel config registers22#define REG_TIx3204_OFS_MARGIN_HIGH 0x0023#define REG_TIx3204_OFS_MARGIN_LOW 0x0124#define REG_TIx3204_OFS_VOUT_CMP_CONFIG 0x0225#define REG_TIx3204_OFS_IOUT_MISC_CONFIG 0x0326#define REG_TIx3204_OFS_CMP_MODE_CONFIG 0x0427#define REG_TIx3204_OFS_FUNC_CONFIG 0x052829// data registers30#define REG_TIx3204_DAC_DATA(chan) ((chan)+0x19)3132extern const AP_HAL::HAL &hal;3334void AP_DAC_TIx3204::init(void)35{36if (params.bus_address <= 0) {37GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 address is 0");38return;39}40dev = std::move(hal.i2c_mgr->get_device(params.bus, params.bus_address));41if (!dev) {42GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 device is null at %u:%", unsigned(params.bus), unsigned(params.bus_address));43return;44}4546WITH_SEMAPHORE(dev->get_semaphore());4748dev->set_retries(10);4950uint16_t val = 17;51if (!register_read(REG_TIx3204_NOP, val) || val != 0) {52GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TIx3204 not found 0x%x at %u:%u", unsigned(val), unsigned(params.bus), unsigned(params.bus_address));53return;54}5556GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 found");5758dev->set_retries(1);59}6061// set voltage for a channel62bool AP_DAC_TIx3204::set_voltage(uint8_t chan, float v)63{64if (chan >= 4) {65return false;66}6768// convert voltage to 12-bit value69uint16_t val = uint16_t(v * 4095.0f / params.voltage_reference);70if (val > 4095) {71val = 4095;72}7374WITH_SEMAPHORE(dev->get_semaphore());7576// write to data register first77if (!register_write(REG_TIx3204_DAC_DATA(chan), val<<4)) {78GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 data write fail");79return false;80}8182if (!configured[chan]) {83uint16_t config;84if (!register_read(REG_TIx3204_COMMON_CONFIG, config)) {85GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 chan config read %u fail", unsigned(chan));86return false;87}88const uint8_t config_shift = chan*3;89const uint16_t config_mask = 0x7 << config_shift;90const uint16_t config_val = 0x1; // enable Vout91config = (config & ~config_mask) | (config_val << config_shift);92if (!register_write(REG_TIx3204_COMMON_CONFIG, config)) {93GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TIx3204 chan config %u fail", unsigned(chan));94return false;95}96configured[chan] = true;97}98return true;99}100101bool AP_DAC_TIx3204::register_read(uint8_t reg, uint16_t &val)102{103uint16_t v;104if (!dev->read_registers(reg, (uint8_t*)&v, sizeof(v))) {105return false;106}107val = be16toh(v);108return true;109}110111bool AP_DAC_TIx3204::register_write(uint8_t reg, uint16_t val)112{113uint8_t buf[3] { reg, uint8_t(val >> 8), uint8_t(val) };114return dev->transfer(buf, sizeof(buf), nullptr, 0);115}116117#endif // AP_DAC_TIX3204_ENABLED118119120