Skip to content

Commit

Permalink
Add drivers DAC_DACx050 and ADC_ADS1115
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Mar 19, 2024
1 parent e8aa517 commit 96e7727
Show file tree
Hide file tree
Showing 11 changed files with 357 additions and 2 deletions.
12 changes: 12 additions & 0 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,10 @@ void AP_Periph_FW::init()
rcout_init();
#endif

#ifdef HAL_PERIPH_ENABLE_ADC
adc.init();
#endif

#ifdef HAL_PERIPH_ENABLE_ADSB
adsb_init();
#endif
Expand All @@ -195,6 +199,10 @@ void AP_Periph_FW::init()
}
#endif

#if AP_DAC_DACx0501_ENABLED
dac.init();
#endif

#if AP_KDECAN_ENABLED
kdecan.init();
#endif
Expand Down Expand Up @@ -493,6 +501,10 @@ void AP_Periph_FW::update()
temperature_sensor.update();
#endif

#ifdef HAL_PERIPH_ENABLE_ADC
adc.update();
#endif

#ifdef HAL_PERIPH_ENABLE_RPM
if (now - rpm_last_update_ms >= 100) {
rpm_last_update_ms = now;
Expand Down
13 changes: 13 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 @@ -65,6 +66,10 @@
#error "AP_NMEA_Output requires Serial/GCS and either AHRS or GPS. Needs HAL_GCS_ENABLED and HAL_PERIPH_ENABLE_GPS"
#endif

#ifdef HAL_PERIPH_ENABLE_ADC
#include "adc.h"
#endif

#if HAL_GCS_ENABLED
#include "GCS_MAVLink.h"
#endif
Expand Down Expand Up @@ -228,6 +233,10 @@ class AP_Periph_FW {
uint32_t rpm_last_update_ms;
#endif

#ifdef HAL_PERIPH_ENABLE_ADC
Periph_ADC adc;
#endif

#ifdef HAL_PERIPH_ENABLE_BATTERY
void handle_battery_failsafe(const char* type_str, const int8_t action) { }
AP_BattMonitor battery_lib{0, FUNCTOR_BIND_MEMBER(&AP_Periph_FW::handle_battery_failsafe, void, const char*, const int8_t), nullptr};
Expand Down Expand Up @@ -309,6 +318,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
12 changes: 12 additions & 0 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -550,6 +550,18 @@ 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

#ifdef HAL_PERIPH_ENABLE_ADC
// @Group: ADC
// @Path: adc.cpp
GOBJECT(adc, "ADC_", Periph_ADC),
#endif

#if AP_KDECAN_ENABLED
// @Group: KDE_
// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp
Expand Down
2 changes: 2 additions & 0 deletions Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ class Parameters {
k_param_serial_options,
k_param_relay,
k_param_temperature_msg_rate,
k_param_adc,
k_param_dac,
};

AP_Int16 format_version;
Expand Down
108 changes: 108 additions & 0 deletions Tools/AP_Periph/adc.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/


#include "AP_Periph.h"

#ifdef HAL_PERIPH_ENABLE_ADC

#include <dronecan_msgs.h>

extern const AP_HAL::HAL &hal;

const AP_Param::GroupInfo Periph_ADC::var_info[] {

// @Param: ADC_RATE
// @DisplayName: ADC Send Rate Interval
// @Description: ADC Send Rate Interval
// @Range: -1 2000
// @Increment: 1
// @Units: ms
AP_GROUPINFO("ADC_RATE", 1, Periph_ADC, params.send_rate, 1000),

AP_GROUPEND
};

void Periph_ADC::init()
{
lib.init();
}

void Periph_ADC::update()
{
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - _last_update_ms >= 10) {
_last_update_ms = now_ms;
IGNORE_RETURN(lib.read(_samples, ARRAY_SIZE(_samples)));
}

if (params.send_rate >= 1 || params.send_rate == -1) {
const uint32_t last_sample_timestamp_ms = lib.get_last_sample_timestamp_ms();
const bool new_sample_available = (last_sample_timestamp_ms != 0) && (last_sample_timestamp_ms != _last_sample_timestamp_ms);

if (params.send_rate == -1) {
if (now_ms - _last_debug_ms >= 1000) {
_last_debug_ms = now_ms;
_last_sample_timestamp_ms = last_sample_timestamp_ms;

can_printf("ADC%s %.2f, %.2f, %.2f, %.2f, %.2f, %.2f",
new_sample_available ? "" : " STALE",
_samples[0].data,
_samples[1].data,
_samples[2].data,
_samples[3].data,
_samples[4].data,
_samples[5].data);
}

} else if (new_sample_available && now_ms - _last_send_ms >= params.send_rate) {
_last_sample_timestamp_ms = last_sample_timestamp_ms;
_last_send_ms = now_ms;

ardupilot_equipment_power_BatteryCells pkt1 {};
pkt1.voltages.len = MIN(ARRAY_SIZE(_samples),ARRAY_SIZE(pkt1.voltages.data));
for (uint8_t i=0; i<pkt1.voltages.len; i++) {
pkt1.voltages.data[i] = _samples[i].data;
}

uint8_t buffer1[ARDUPILOT_EQUIPMENT_POWER_BATTERYCELLS_MAX_SIZE] {};
uint16_t total_size1 = ardupilot_equipment_power_BatteryCells_encode(&pkt1, buffer1, !periph.canfdout());
periph.canard_broadcast(ARDUPILOT_EQUIPMENT_POWER_BATTERYCELLS_SIGNATURE,
ARDUPILOT_EQUIPMENT_POWER_BATTERYCELLS_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer1[0],
total_size1);



rb_ADC pkt2 {};
pkt2.voltages.len = MIN(ARRAY_SIZE(_samples),ARRAY_SIZE(pkt2.voltages.data));
for (uint8_t i=0; i<pkt2.voltages.len; i++) {
pkt2.voltages.data[i] = _samples[i].data;
}

uint8_t buffer2[RB_ADC_MAX_SIZE] {};
uint16_t total_size2 = rb_ADC_encode(&pkt2, buffer2, !periph.canfdout());
periph.canard_broadcast(RB_ADC_SIGNATURE,
RB_ADC_ID,
CANARD_TRANSFER_PRIORITY_LOW,
&buffer2[0],
total_size2);
}
}
}

#endif // HAL_PERIPH_ENABLE_ADC

36 changes: 36 additions & 0 deletions Tools/AP_Periph/adc.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
#pragma once

#ifdef HAL_PERIPH_ENABLE_ADC

#include <AP_ADC/AP_ADC_ADS1115.h>

class Periph_ADC {
public:
friend class AP_Periph_FW;

Periph_ADC() {
AP_Param::setup_object_defaults(this, var_info);
}

void init();
void update();

static const struct AP_Param::GroupInfo var_info[];

private:

struct {
AP_Int32 send_rate;
} params;

AP_ADC_ADS1115 lib;
adc_report_s _samples[ADS1115_CHANNELS_COUNT];
uint32_t _last_update_ms;
uint32_t _last_send_ms;
uint32_t _last_sample_timestamp_ms;
uint32_t _last_debug_ms;

};

#endif // HAL_PERIPH_ENABLE_ADC

2 changes: 2 additions & 0 deletions Tools/AP_Periph/wscript
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ def build(bld):
'AP_Logger',
'AC_PID',
'AP_BLHeli',
'AP_ADC',
'AP_DAC',
'AP_ESC_Telem',
'AP_Stats',
'AP_EFI',
Expand Down
14 changes: 12 additions & 2 deletions libraries/AP_ADC/AP_ADC_ADS1115.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,20 @@
#include <AP_HAL/utility/sparse-endian.h>

#include "AP_ADC_ADS1115.h"
#if AP_ADC_ADS1115_ENABLED

#define ADS1115_ADDRESS_ADDR_GND 0x48 // address pin low (GND)
#define ADS1115_ADDRESS_ADDR_VDD 0x49 // address pin high (VCC)
#define ADS1115_ADDRESS_ADDR_SDA 0x4A // address pin tied to SDA pin
#define ADS1115_ADDRESS_ADDR_SCL 0x4B // address pin tied to SCL pin

#ifndef ADS1115_I2C_ADDR
#define ADS1115_I2C_ADDR ADS1115_ADDRESS_ADDR_GND
#endif

#ifndef ADS1115_I2C_BUS
#define ADS1115_I2C_BUS 1
#endif

#define ADS1115_RA_CONVERSION 0x00
#define ADS1115_RA_CONFIG 0x01
Expand Down Expand Up @@ -93,7 +99,6 @@

extern const AP_HAL::HAL &hal;

#define ADS1115_CHANNELS_COUNT 6

const uint8_t AP_ADC_ADS1115::_channels_number = ADS1115_CHANNELS_COUNT;

Expand Down Expand Up @@ -130,6 +135,8 @@ bool AP_ADC_ADS1115::init()

_gain = ADS1115_PGA_4P096;

_dev->set_retries(3);

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

return true;
Expand Down Expand Up @@ -205,7 +212,7 @@ void AP_ADC_ADS1115::_update()
uint8_t config[2];
be16_t val;

if (!_dev->read_registers(ADS1115_RA_CONFIG, config, sizeof(config))) {
if (!_dev->read_registers(ADS1115_RA_CONFIG, config, ARRAY_SIZE(config))) {
error("_dev->read_registers failed in ADS1115");
return;
}
Expand All @@ -227,4 +234,7 @@ void AP_ADC_ADS1115::_update()
/* select next channel */
_channel_to_read = (_channel_to_read + 1) % _channels_number;
_start_conversion(_channel_to_read);

_last_sample_timestamp_ms = AP_HAL::millis();
}
#endif // AP_ADC_ADS1115_ENABLED
10 changes: 10 additions & 0 deletions libraries/AP_ADC/AP_ADC_ADS1115.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,13 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>

#ifndef AP_ADC_ADS1115_ENABLED
#define AP_ADC_ADS1115_ENABLED 0
#endif

#define ADS1115_CHANNELS_COUNT 6

#if AP_ADC_ADS1115_ENABLED
struct adc_report_s
{
uint8_t id;
Expand All @@ -18,6 +25,7 @@ class AP_ADC_ADS1115

bool init();
size_t read(adc_report_s *report, size_t length) const;
uint32_t get_last_sample_timestamp_ms() const { return _last_sample_timestamp_ms;}

uint8_t get_channels_number() const
{
Expand All @@ -32,9 +40,11 @@ class AP_ADC_ADS1115
uint16_t _gain;
int _channel_to_read;
adc_report_s *_samples;
uint32_t _last_sample_timestamp_ms;

void _update();
bool _start_conversion(uint8_t channel);

float _convert_register_data_to_mv(int16_t word) const;
};
#endif // AP_ADC_ADS1115_ENABLED
Loading

0 comments on commit 96e7727

Please sign in to comment.