Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file added Tools/bootloaders/CubeNode-vehicle_bl.bin
Binary file not shown.
1,269 changes: 1,269 additions & 0 deletions Tools/bootloaders/CubeNode-vehicle_bl.hex

Large diffs are not rendered by default.

43 changes: 26 additions & 17 deletions libraries/AP_HAL_ChibiOS/AnalogIn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,32 +70,21 @@ using namespace ChibiOS;
scaling table between ADC count and actual input voltage, to account
for voltage dividers on the board.
*/
const AnalogIn::pin_info AnalogIn::pin_config[] = { HAL_ANALOG_PINS };
#ifdef HAL_ANALOG_PINS
const AnalogIn::pin_info AnalogIn::pin_config[] = { HAL_ANALOG_PINS };
#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config)
#endif

#ifdef HAL_ANALOG2_PINS
const AnalogIn::pin_info AnalogIn::pin_config_2[] = { HAL_ANALOG2_PINS };
#define ADC2_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config_2)
#endif

#if defined(HAL_ANALOG3_PINS) || HAL_WITH_MCU_MONITORING
#if HAL_WITH_MCU_MONITORING
// internal ADC channels (from H7 reference manual)
#define ADC3_VSENSE_CHAN 18
#define ADC3_VREFINT_CHAN 19
#define ADC3_VBAT4_CHAN 17
#define HAL_MCU_MONITORING_PINS {ADC3_VBAT4_CHAN, 252, 3.30/4096}, {ADC3_VSENSE_CHAN, 253, 3.30/4096}, {ADC3_VREFINT_CHAN, 254, 3.30/4096}
#else
#define HAL_MCU_MONITORING_PINS
#endif
#ifndef HAL_ANALOG3_PINS
#define HAL_ANALOG3_PINS
#endif
const AnalogIn::pin_info AnalogIn::pin_config_3[] = { HAL_ANALOG3_PINS HAL_MCU_MONITORING_PINS};
#ifdef HAL_ANALOG3_PINS
const AnalogIn::pin_info AnalogIn::pin_config_3[] = { HAL_ANALOG3_PINS };
#define ADC3_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config_3)
#endif

#define ADC_GRP1_NUM_CHANNELS ARRAY_SIZE(AnalogIn::pin_config)

#if defined(ADC_CFGR_RES_16BITS)
// on H7 we use 16 bit ADC transfers, giving us more resolution. We
// need to scale by 1/16 to match the 12 bit scale factors in hwdef.dat
Expand Down Expand Up @@ -141,11 +130,13 @@ bool AnalogIn::valid_analog_pin(uint16_t pin) const
if (pin == ANALOG_INPUT_NONE) {
return false;
}
#ifdef HAL_ANALOG_PINS
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config[i].analog_pin == pin) {
return true;
}
}
#endif
#ifdef HAL_ANALOG2_PINS
for (uint8_t i=0; i<ADC2_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config_2[i].analog_pin == pin) {
Expand All @@ -169,12 +160,14 @@ bool AnalogIn::valid_analog_pin(uint16_t pin) const
float AnalogSource::_pin_scaler(void)
{
float scaling = VOLTAGE_SCALING;
#ifdef HAL_ANALOG_PINS
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config[i].analog_pin == _pin && (_pin != ANALOG_INPUT_NONE)) {
scaling = AnalogIn::pin_config[i].scaling;
break;
}
}
#endif
#ifdef HAL_ANALOG2_PINS
for (uint8_t i=0; i<ADC2_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config_2[i].analog_pin == _pin && (_pin != ANALOG_INPUT_NONE)) {
Expand Down Expand Up @@ -232,12 +225,14 @@ bool AnalogSource::set_pin(uint8_t pin)
if (pin == ANALOG_SERVO_VRSSI_PIN) {
found_pin = true;
} else {
#ifdef HAL_ANALOG_PINS
for (uint8_t i=0; i<ADC_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config[i].analog_pin == pin) {
found_pin = true;
break;
}
}
#endif
#ifdef HAL_ANALOG2_PINS
for (uint8_t i=0; i<ADC2_GRP1_NUM_CHANNELS; i++) {
if (AnalogIn::pin_config_2[i].analog_pin == pin) {
Expand Down Expand Up @@ -301,9 +296,11 @@ void AnalogSource::_add_value(float v, float vcc5V)
uint8_t AnalogIn::get_pin_channel(uint8_t adc_index, uint8_t pin_index)
{
switch(adc_index) {
#if defined(HAL_ANALOG_PINS)
case 0:
osalDbgAssert(pin_index < ADC_GRP1_NUM_CHANNELS, "invalid pin_index");
return pin_config[pin_index].channel;
#endif
#if defined(HAL_ANALOG2_PINS)
case 1:
osalDbgAssert(pin_index < ADC2_GRP1_NUM_CHANNELS, "invalid pin_index");
Expand All @@ -322,8 +319,10 @@ uint8_t AnalogIn::get_pin_channel(uint8_t adc_index, uint8_t pin_index)
uint8_t AnalogIn::get_analog_pin(uint8_t adc_index, uint8_t pin_index)
{
switch(adc_index) {
#if defined(HAL_ANALOG_PINS)
case 0:
return pin_config[pin_index].analog_pin;
#endif
#if defined(HAL_ANALOG2_PINS)
case 1:
return pin_config_2[pin_index].analog_pin;
Expand All @@ -342,8 +341,10 @@ uint8_t AnalogIn::get_analog_pin(uint8_t adc_index, uint8_t pin_index)
float AnalogIn::get_pin_scaling(uint8_t adc_index, uint8_t pin_index)
{
switch(adc_index) {
#if defined(HAL_ANALOG_PINS)
case 0:
return pin_config[pin_index].scaling;
#endif
#if defined(HAL_ANALOG2_PINS)
case 1:
return pin_config_2[pin_index].scaling;
Expand Down Expand Up @@ -417,9 +418,11 @@ void AnalogIn::adccallback(ADCDriver *adcp)

uint8_t AnalogIn::get_adc_index(ADCDriver* adcp)
{
#if defined(HAL_ANALOG_PINS)
if (adcp == &ADCD1) {
return 0;
}
#endif
#if defined(HAL_ANALOG2_PINS) && !STM32_ADC_DUAL_MODE
if (adcp == &ADCD2) {
return 1;
Expand All @@ -437,8 +440,10 @@ uint8_t AnalogIn::get_adc_index(ADCDriver* adcp)
uint8_t AnalogIn::get_num_grp_channels(uint8_t index)
{
switch (index) {
#if defined(HAL_ANALOG_PINS)
case 0:
return ADC_GRP1_NUM_CHANNELS;
#endif
#if defined(HAL_ANALOG2_PINS)
case 1:
return ADC2_GRP1_NUM_CHANNELS;
Expand All @@ -462,7 +467,9 @@ void AnalogIn::init()
#else
static_assert(sizeof(uint16_t) == sizeof(adcsample_t), "adcsample_t must be uint16_t");
#endif
#if defined(HAL_ANALOG_PINS)
setup_adc(0);
#endif
#if defined(HAL_ANALOG2_PINS)
setup_adc(1);
#endif
Expand All @@ -480,9 +487,11 @@ void AnalogIn::setup_adc(uint8_t index)

ADCDriver *adcp;
switch (index) {
#if defined(HAL_ANALOG_PINS)
case 0:
adcp = &ADCD1;
break;
#endif
// if we are in dual mode then ADC2 is setup along with ADC1
// so we don't need to setup ADC2 separately
#if defined(HAL_ANALOG2_PINS) && !STM32_ADC_DUAL_MODE
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeNode-vehicle/hwdef-bl.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
include ../CubeNode/hwdef-bl.inc

# Add activity LEDs
PB1 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # Blue
PB0 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # Green
define HAL_LED_ON 0
71 changes: 71 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeNode-vehicle/hwdef.dat
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
# hw definition file for processing by chibios_hwdef.py for H757
# CubeNode pin descriptions can be found at https://docs.cubepilot.org/user-guides/cubenode/pin-descriptions

include ../CubeNode/hwdef.inc

# CAN2
PB5 CAN2_RX CAN2
PB6 CAN2_TX CAN2

# SERIAL

# UART 1
PE1 UART8_TX UART8
PE0 UART8_RX UART8

# UART 2
PC6 USART6_TX USART6
PC7 USART6_RX USART6

# UART 3
undef PE7
undef PE8
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE10 UART7_CTS UART7
PE9 UART7_RTS UART7

undef SERIAL_ORDER
SERIAL_ORDER OTG1 UART8 USART6 UART7 OTG2

# I2C
PB8 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1

I2C_ORDER I2C1

# No Baro on the board, allow boot without
define HAL_BARO_ALLOW_INIT_NO_BARO

# LEDs
PB1 LED_BLUE OUTPUT LOW GPIO(0)
PB0 LED_GREEN OUTPUT LOW GPIO(1)
PE6 LED_RED OUTPUT LOW GPIO(2)

define AP_NOTIFY_GPIO_LED_3_ENABLED 1
define HAL_GPIO_A_LED_PIN 0
define HAL_GPIO_B_LED_PIN 1
define HAL_GPIO_C_LED_PIN 2

# PWM output for buzzer
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM

# pins for SD card:
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
PD6 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2

# Enable FAT filesystem support (needs a microSD defined via SDMMC).
define HAL_OS_FATFS_IO 1
define FATFS_HAL_DEVICE SDCD2

# Defining some PWM pins. We also map these pins to GPIO
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PD13 TIM4_CH2 TIM4 PWM(4) GPIO(53)
PD14 TIM4_CH3 TIM4 PWM(5) GPIO(54)
PD15 TIM4_CH4 TIM4 PWM(6) GPIO(55)
115 changes: 115 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/CubeNode-vehicle/readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
# CubeNode-vehicle

This build can be used to flash a vehicle code on a CubeNode. This will have to be loaded using dfu as the CubeNode ships with a Periph bootloader which cannot load a vehicle binary.

This can be used as a starting point for other configurations, pin functions can be add, removed, or changed as needed.

## Serial
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is a better summary, I think
UART Port Mapping:
Port UART Protocol TX DMA RX DMA


0 USB MAVLink2 ✘ ✘
1 UART8 MAVLink2 ✔ ✔
2 USART6 MAVLink2 ✔ ✔
3 UART7 GPS ✔ ✔
4 USB SLCAN ✘ ✘


Three serial physical ports are available along with two USB endpoints. The ordering is:

#### SERIAL0

First USB endpoint

#### SERIAL1

| Pin name | Pin number | function |
| -------- | ---------- | -------- |
| PE1 | 3 | UART8_TX |
| PE0 | 4 | UART8_RX |

#### SERIAL2

| Pin name | Pin number | function |
| -------- | ---------- | --------- |
| PC6 | 44 | USART6_TX |
| PC7 | 43 | USART6_RX |

#### SERIAL3

UART 3 has flow control.

| Pin name | Pin number | function |
| -------- | ---------- | --------- |
| PE7 | 23 | UART7_RX |
| PE8 | 22 | UART7_TX |
| PE10 | 21 | UART7_CTS |
| PE9 | 72 | UART7_RTS |

##### SERIAL4

Second USB endpoint

# CAN

Two CAN busses are available, transceivers are within the Node itself but termination resistors are not.

#### CAN 1

| Pin name | Pin number | function |
| -------- | ---------- | --------- |
| CAN1_H | 2 | CAN1 high |
| CAN1_L | 1 | CAN1 low |

#### CAN 2

| Pin name | Pin number | function |
| -------- | ---------- | --------- |
| CAN2_H | 15 | CAN2 high |
| CAN2_L | 14 | CAN2 low |

# I2C

A single I2C bus is provided, software pullup resistors can be enabled but hardware pullup are recommended.

##### I2C

| Pin name | Pin number | function |
| -------- | ---------- | -------- |
| PB8 | 5 | I2C1_SCL |
| PB7 | 6 | I2C1_SDA |

# LEDs

Three board LEDs are defined for use with notify to provide status feedback, these are active low.

| Pin name | Pin number | function |
| -------- | ---------- | --------- |
| PB1 | 45 | Blue LED |
| PB0 | 46 | Green LED |
| PE6 | 47 | Red LED |

# Buzzer

A Alarm output is provided for a buzzer, some external drive circuit is required.

| Pin name | Pin number | function |
| -------- | ---------- | -------- |
| PA15 | 60 | ALARM |

# SD Card

A SD can be connected via SDMMC

| Pin name | Pin number | function |
| -------- | ---------- | ---------- |
| PB14 | 102 | SDMMC2_D0 |
| PB15 | 101 | SDMMC2_D1 |
| PB3 | 106 | SDMMC2_D2 |
| PB4 | 107 | SDMMC2_D3 |
| PD6 | 110 | SDMMC2_CK |
| PD7 | 111 | SDMMC2_CMD |

## PWM outputs

PWM output pins can also be used as GPIOs. They are in two groups.

| Pin name | Pin number | function | SERVO num | GPIO num | Group |
| -------- | ---------- | ---------- | --------- | -------- | ------|
| PE14 | 69 | TIM1_CH4 | 1 | 50 | A |
| PE13 | 70 | TIM1_CH3 | 2 | 51 | A |
| PE11 | 71 | TIM1_CH2 | 3 | 52 | A |
| PD13 | 34 | TIM4_CH2 | 4 | 53 | B |
| PD14 | 33 | TIM4_CH3 | 5 | 54 | B |
| PD15 | 32 | TIM4_CH4 | 6 | 55 | B |
Loading
Loading