Skip to content

Commit

Permalink
Add support for ADS1115 ADC in Periph
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Mar 14, 2024
1 parent b9bc4a5 commit f6b9800
Show file tree
Hide file tree
Showing 8 changed files with 86 additions and 1 deletion.
45 changes: 45 additions & 0 deletions Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include "AP_Periph.h"
#include <stdio.h>
#include <dronecan_msgs.h>

#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
Expand Down Expand Up @@ -180,6 +181,10 @@ void AP_Periph_FW::init()
rcout_init();
#endif

#if AP_ADC_ADS1115_ENABLED
adc.lib.init();
#endif

#ifdef HAL_PERIPH_ENABLE_ADSB
adsb_init();
#endif
Expand Down Expand Up @@ -493,6 +498,46 @@ void AP_Periph_FW::update()
temperature_sensor.update();
#endif

#if AP_ADC_ADS1115_ENABLED
if (now - adc.last_update_ms >= 10) {
adc.last_update_ms = now;
IGNORE_RETURN(adc.lib.read(adc.samples, ARRAY_SIZE(adc.samples)));
}
if (g.adc_send_rate > 0 && now - adc.last_send_ms >= g.adc_send_rate) {
adc.last_send_ms = now;

ardupilot_equipment_power_BatteryCells pkt1 {};
pkt1.voltages.len = MIN(ARRAY_SIZE(adc.samples),ARRAY_SIZE(pkt1.voltages.data));
for (uint8_t i=0; i<pkt1.voltages.len; i++) {
pkt1.voltages.data[i] = adc.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());
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(adc.samples),ARRAY_SIZE(pkt2.voltages.data));
for (uint8_t i=0; i<pkt2.voltages.len; i++) {
pkt2.voltages.data[i] = adc.samples[i].data;
}

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

#ifdef HAL_PERIPH_ENABLE_RPM
if (now - rpm_last_update_ms >= 100) {
rpm_last_update_ms = now;
Expand Down
11 changes: 11 additions & 0 deletions Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@
#endif
#endif

#include <AP_ADC/AP_ADC_ADS1115.h>

#if defined(HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE) && !AP_TEMPERATURE_SENSOR_ENABLED
#error "HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE requires AP_TEMPERATURE_SENSOR_ENABLED"
#endif
Expand Down Expand Up @@ -229,6 +231,15 @@ class AP_Periph_FW {
uint32_t rpm_last_update_ms;
#endif

#if AP_ADC_ADS1115_ENABLED
struct {
AP_ADC_ADS1115 lib;
adc_report_s samples[ADS1115_CHANNELS_COUNT];
uint32_t last_update_ms;
uint32_t last_send_ms;
} 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
10 changes: 10 additions & 0 deletions Tools/AP_Periph/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -510,6 +510,16 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
GOBJECT(efi, "EFI", AP_EFI),
#endif

#if AP_ADC_ADS1115_ENABLED
// @Param: ADC_RATE
// @DisplayName: ADC Send Rate Interval
// @Description: ADC Send Rate Interval
// @Range: 0 2000
// @Increment: 1
// @Units: ms
GSCALAR(adc_send_rate, "ADC_RATE", 1),
#endif

#ifdef HAL_PERIPH_ENABLE_PROXIMITY
// @Param: PRX_BAUDRATE
// @DisplayName: Proximity Sensor serial baudrate
Expand Down
5 changes: 5 additions & 0 deletions Tools/AP_Periph/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,7 @@ class Parameters {
k_param_serial_options,
k_param_relay,
k_param_temperature_msg_rate,
k_param_adc_send_rate,
};

AP_Int16 format_version;
Expand Down Expand Up @@ -201,6 +202,10 @@ class Parameters {
AP_Int8 efi_port;
#endif

#if AP_ADC_ADS1115_ENABLED
AP_Int32 adc_send_rate;
#endif

#if HAL_PERIPH_CAN_MIRROR
AP_Int8 can_mirror_ports;
#endif // HAL_PERIPH_CAN_MIRROR
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 @@ -2,6 +2,7 @@
#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)
Expand Down Expand Up @@ -227,3 +228,4 @@ void AP_ADC_ADS1115::_update()
_channel_to_read = (_channel_to_read + 1) % _channels_number;
_start_conversion(_channel_to_read);
}
#endif // AP_ADC_ADS1115_ENABLED
6 changes: 6 additions & 0 deletions libraries/AP_ADC/AP_ADC_ADS1115.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +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 Down Expand Up @@ -40,3 +45,4 @@ class AP_ADC_ADS1115

float _convert_register_data_to_mv(int16_t word) const;
};
#endif // AP_ADC_ADS1115_ENABLED
6 changes: 6 additions & 0 deletions libraries/AP_DroneCAN/dsdl/rb/31000.uavcan
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#
# ADC voltages
#

float32[<=10] voltages # [Volt]

2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -61,4 +61,4 @@ define HAL_CAN_DRIVER_DEFAULT 1
# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0


define AP_ADC_ADS1115_ENABLED 1

0 comments on commit f6b9800

Please sign in to comment.