Skip to content

Commit

Permalink
DAC WIP
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Mar 15, 2024
1 parent 068e3b6 commit 632e099
Show file tree
Hide file tree
Showing 9 changed files with 163 additions and 0 deletions.
4 changes: 4 additions & 0 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -200,6 +200,10 @@ void AP_Periph_FW::init()
}
#endif

#if AP_DAC_DACx0501_ENABLED
dac.init();
#endif

#if AP_KDECAN_ENABLED
kdecan.init();
#endif
Expand Down
5 changes: 5 additions & 0 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include <AP_RangeFinder/AP_RangeFinder.h>
#include <AP_Proximity/AP_Proximity.h>
#include <AP_EFI/AP_EFI.h>
#include <AP_DAC/AP_DAC_DACx0501.h>
#include <AP_KDECAN/AP_KDECAN.h>
#include <AP_MSP/AP_MSP.h>
#include <AP_MSP/msp.h>
Expand Down Expand Up @@ -323,6 +324,10 @@ class AP_Periph_FW {
uint32_t efi_update_ms;
#endif

#if AP_DAC_DACx0501_ENABLED
AP_DAC_DACx0501 dac;
#endif

#if AP_KDECAN_ENABLED
AP_KDECAN kdecan;
#endif
Expand Down
6 changes: 6 additions & 0 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,6 +560,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(nmea, "NMEA_", AP_NMEA_Output),
#endif

#if AP_DAC_DACx0501_ENABLED
// @Group: DAC_
// @Path: ../libraries/AP_DAC/AP_DAC_DACx0501.cpp
GOBJECT(dac, "DAC_", AP_DAC_DACx0501),
#endif

#if AP_KDECAN_ENABLED
// @Group: KDE_
// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@ class Parameters {
k_param_relay,
k_param_temperature_msg_rate,
k_param_adc_send_rate,
k_param_dac,
};

AP_Int16 format_version;
Expand Down
1 change: 1 addition & 0 deletions Tools/AP_Periph/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ def build(bld):
'AC_PID',
'AP_BLHeli',
'AP_ADC',
'AP_DAC',
'AP_ESC_Telem',
'AP_Stats',
'AP_EFI',
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_ADC/AP_ADC_ADS1115.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,8 @@ bool AP_ADC_ADS1115::init()
_samples[i].data = -1.0f;
}

_dev->set_retries(3);

_dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_ADC_ADS1115::_update, void));

return true;
Expand Down
100 changes: 100 additions & 0 deletions libraries/AP_DAC/AP_DAC_DACx0501.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@

#include "AP_DAC_DACx0501.h"

#if AP_DAC_DACx0501_ENABLED
#include <SRV_Channel/SRV_Channel.h>

extern const AP_HAL::HAL &hal;

#define DACx0501_ADDRESS_ADDR_GND 0x48 // address pin low (GND)
#define DACx0501_ADDRESS_ADDR_VDD 0x49 // address pin high (VDD)
#define DACx0501_ADDRESS_ADDR_SDA 0x4A // address pin tied to SDA pin
#define DACx0501_ADDRESS_ADDR_SCL 0x4B // address pin tied to SCL pin

#ifndef DACx0501_I2C_ADDR
#define DACx0501_I2C_ADDR DACx0501_ADDRESS_ADDR_GND
#endif

#ifndef DACx0501_I2C_BUS
#define DACx0501_I2C_BUS 0
#endif

// Registers
#define DACx0501_REG_NOOP 0x00 // no operation, this should never be used intentionally
#define DACx0501_REG_DEVID 0x01 // same as WHO_AM_I
#define DACx0501_REG_SYNC 0x02
#define DACx0501_REG_CONFIG 0x03
#define DACx0501_REG_GAIN 0x04
#define DACx0501_REG_TRIGGER 0x05
//#define DACx0501_REG_UNKNOWN 0x06
#define DACx0501_REG_STATUS 0x07
#define DACx0501_REG_DAC_DATA 0x08

#define DACx0501_DEVID 0x0015 // base ID. More bit sget set for other flavors of the chip

// table of user settable CAN bus parameters
const AP_Param::GroupInfo AP_DAC_DACx0501::var_info[] = {

// @Param: ADDR
// @DisplayName: I2C address
// @Description: I2C address
AP_GROUPINFO("ADDR", 1, AP_DAC_DACx0501, params.i2c_address, DACx0501_I2C_ADDR),

// @Param: BUS
// @DisplayName: I2C bus
// @Description: I2C bus
AP_GROUPINFO("BUS", 2, AP_DAC_DACx0501, params.i2c_bus, DACx0501_I2C_BUS),

// @Param: SRV_INDEX
// @DisplayName: SRV_INDEX
// @Description: SRV_INDEX
AP_GROUPINFO("SRV_INDEX", 3, AP_DAC_DACx0501, params.servo_index, -1),

// @Param: BIT_RES
// @DisplayName: BIT_RES
// @Description: BIT_RESolution of the DAC.
// @Values: 12:12-bit, 14:14-bit, 16:16-bit
AP_GROUPINFO("BIT_RES", 4, AP_DAC_DACx0501, params.bit_resolution, 12),

// @Param: GAIN
// @DisplayName: GAIN
// @Description: GAIN
// @Range: 0.01 100
// @Incremenet: 0.01
AP_GROUPINFO("GAIN", 5, AP_DAC_DACx0501, params.gain, 1),

AP_GROUPEND
};

void AP_DAC_DACx0501::init()
{
_dev = hal.i2c_mgr->get_device(params.i2c_bus, params.i2c_address);
if (!_dev) {
return;
}

_dev->set_retries(3);
_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_DAC_DACx0501::thread, void));
}

void AP_DAC_DACx0501::thread()
{
const SRV_Channel *c = SRV_Channels::srv_channel(params.servo_index);
if (c == nullptr || !c->valid_function()) {
return;
}

const uint16_t bit_resolution = constrain_int16(params.bit_resolution.get(), 12, 16);
const uint16_t max_output = (1U << bit_resolution) - 1;

uint16_t value = linear_interpolate(0, max_output, c->get_output_pwm(), c->get_output_min(), c->get_output_max());
value *= MAX(0.01f, params.gain.get());

uint8_t buf[3];
buf[0] = DACx0501_REG_DAC_DATA;
buf[1] = HIGHBYTE(value);
buf[2] = LOWBYTE(value);

UNUSED_RESULT(_dev->transfer(buf, sizeof(buf), nullptr, 0));
}
#endif // AP_DAC_DACx0501_ENABLED
41 changes: 41 additions & 0 deletions libraries/AP_DAC/AP_DAC_DACx0501.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
#pragma once

#include <AP_HAL/AP_HAL.h>

#ifndef AP_DAC_DACx0501_ENABLED
#define AP_DAC_DACx0501_ENABLED 0
#endif

#if AP_DAC_DACx0501_ENABLED
#include <AP_HAL/I2CDevice.h>
#include <AP_Param/AP_Param.h>

class AP_DAC_DACx0501
{
public:
AP_DAC_DACx0501() {
AP_Param::setup_object_defaults(this, var_info);
}

/* Do not allow copies */
CLASS_NO_COPY(AP_DAC_DACx0501);

static const struct AP_Param::GroupInfo var_info[];

void init();

private:
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;

struct {
AP_Int8 i2c_address;
AP_Int8 i2c_bus;
AP_Int16 servo_index;
AP_Int16 bit_resolution;
AP_Float gain;
} params;

void thread();
};

#endif // AP_DAC_DACx0501_ENABLED
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -65,3 +65,6 @@ define AP_ADC_ADS1115_ENABLED 1
define ADS1115_I2C_BUS 0
define HAL_I2C_MAX_CLOCK 400000

define AP_DAC_DACx0501_ENABLED 1
define DACx0501_I2C_ADDR 0x49 # address pin high (VDD)
define DACx0501_I2C_BUS 0

0 comments on commit 632e099

Please sign in to comment.