Skip to content

Commit

Permalink
Add payload power ADC measurement
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexKlimaj committed Oct 21, 2024
1 parent 969c15b commit 6e05213
Show file tree
Hide file tree
Showing 5 changed files with 39 additions and 7 deletions.
2 changes: 2 additions & 0 deletions boards/ark/fpv/init/rc.board_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -24,3 +24,5 @@ if ver hwtypecmp ARKFPV000
then
param set-default SENS_TEMP_ID 3014666
fi

param set-default BAT1_V_DIV 21.0
21 changes: 14 additions & 7 deletions boards/ark/fpv/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -156,17 +156,22 @@
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PB0 */ ADC1_CH(9)
#define ADC_BATTERY_CURRENT_CHANNEL /* PC2 */ ADC3_CH(0)
#define ADC_SCALED_12V_CHANNEL /* PA4 */ ADC1_CH(18)
#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16)
#define ADC_SCALED_VDD_3V3_SENSORS_CHANNEL /* PA0 */ ADC1_CH(16)
#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5)
#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14)
#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15)

#define ADC_CHANNELS \
((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL)) | \
(1 << ADC_SCALED_12V_CHANNEL) | \
(1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL)
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
(1 << ADC_SCALED_VDD_3V3_SENSORS_CHANNEL) | \
(1 << ADC_SCALED_V5_CHANNEL) | \
(1 << ADC_SCALED_12V_CHANNEL))


#define BOARD_BATTERY1_V_DIV (21.0f) // (20k + 1k) / 1k = 21

#define ADC_SCALED_PAYLOAD_SENSE ADC_SCALED_12V_CHANNEL

/* HW has to large of R termination on ADC todo:change when HW value is chosen */

Expand Down Expand Up @@ -235,6 +240,8 @@
#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)


#define BOARD_NUMBER_BRICKS 1

/* Define True logic Power Control in arch agnostic form */

#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true))
Expand Down Expand Up @@ -287,7 +294,7 @@
#define BOARD_ADC_SERVO_VALID (1)

#define BOARD_ADC_BRICK_VALID (px4_arch_gpioread(GPIO_VDD_5V_PGOOD))
#define BOARD_ADC_12V_RAIL_VALID (px4_arch_gpioread(GPIO_VDD_12V_PGOOD))
#define BOARD_GPIO_PAYOLOAD_V_VALID (px4_arch_gpioread(GPIO_VDD_12V_PGOOD))

/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
Expand Down
2 changes: 2 additions & 0 deletions msg/SystemPower.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
uint64 timestamp # time since system start (microseconds)
float32 voltage5v_v # peripheral 5V rail voltage
float32 voltage_payload_v # payload rail voltage
float32[4] sensors3v3 # Sensors 3V3 rail voltage
uint8 sensors3v3_valid # Sensors 3V3 rail voltage was read (bitfield).
uint8 usb_connected # USB is connected when 1
Expand All @@ -10,6 +11,7 @@ uint8 periph_5v_oc # peripheral overcurrent when 1
uint8 hipower_5v_oc # high power peripheral overcurrent when 1
uint8 comp_5v_valid # 5V to companion valid
uint8 can1_gps1_5v_valid # 5V for CAN1/GPS1 valid
uint8 payload_v_valid # payload rail voltage is valid

uint8 BRICK1_VALID_SHIFTS=0
uint8 BRICK1_VALID_MASK=1
Expand Down
7 changes: 7 additions & 0 deletions platforms/common/include/px4_platform_common/board_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,13 @@
#define ADC_V5_SCALE (2.0f) // The scale factor defined by HW's resistive divider (Rt+Rb)/ Rb
#endif

#if !defined(ADC_PAYLOAD_V_FULL_SCALE)
#define ADC_PAYLOAD_V_FULL_SCALE (25.3f) // Payload volt Rail full scale voltage
#endif
#if !defined(ADC_PAYLOAD_SCALE)
#define ADC_PAYLOAD_SCALE (7.667f) // The scale factor defined by HW's resistive divider (Rt+Rb)/ Rb
#endif

#if !defined(ADC_3V3_V_FULL_SCALE)
#define ADC_3V3_V_FULL_SCALE (3.6f) // 3.3V volt Rail full scale voltage
#endif
Expand Down
14 changes: 14 additions & 0 deletions src/drivers/adc/board_adc/ADC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,9 @@ void ADC::update_system_power(hrt_abstime now)
# if defined(ADC_SCALED_V5_SENSE) && defined(ADC_SCALED_V3V3_SENSORS_SENSE)
cnt += ADC_SCALED_V3V3_SENSORS_COUNT;
# endif
# if defined(ADC_SCALED_PAYLOAD_SENSE)
cnt++;
# endif

for (unsigned i = 0; i < _channel_count; i++) {
# if defined(ADC_SCALED_V5_SENSE)
Expand Down Expand Up @@ -234,7 +237,15 @@ void ADC::update_system_power(hrt_abstime now)
}

# endif
# if defined(ADC_SCALED_PAYLOAD_SENSE)

if (_samples[i].am_channel == ADC_SCALED_PAYLOAD_SENSE) {
system_power.voltage_payload_v = _samples[i].am_data * ((ADC_PAYLOAD_V_FULL_SCALE / 3.3f) * (px4_arch_adc_reference_v() /
px4_arch_adc_dn_fullcount()));
cnt--;
}

# endif
if (cnt == 0) {
break;
}
Expand Down Expand Up @@ -285,6 +296,9 @@ void ADC::update_system_power(hrt_abstime now)
#ifdef BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID
system_power.can1_gps1_5v_valid = read_gpio_value(_5v_can1_gps1_valid_fd);
#endif
#ifdef BOARD_GPIO_PAYOLOAD_V_VALID
system_power.payload_v_valid = BOARD_GPIO_PAYOLOAD_V_VALID;
#endif

system_power.timestamp = hrt_absolute_time();
_to_system_power.publish(system_power);
Expand Down

0 comments on commit 6e05213

Please sign in to comment.