Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into hwdef_add_MicoAir405Mini
Browse files Browse the repository at this point in the history
  • Loading branch information
Minderring authored Apr 11, 2024
2 parents 63bafe1 + f605c0f commit 78b3bb5
Show file tree
Hide file tree
Showing 13 changed files with 172 additions and 69 deletions.
16 changes: 16 additions & 0 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::SIMPLE_HEADING_RESET:
case AUX_FUNC::ARMDISARM_AIRMODE:
case AUX_FUNC::TURBINE_START:
case AUX_FUNC::FLIGHTMODE_PAUSE:
break;
case AUX_FUNC::ACRO_TRAINER:
case AUX_FUNC::ATTCON_ACCEL_LIM:
Expand Down Expand Up @@ -566,6 +567,21 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
}
break;

case AUX_FUNC::FLIGHTMODE_PAUSE:
switch (ch_flag) {
case AuxSwitchPos::HIGH:
if (!copter.flightmode->pause()) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Flight Mode Pause failed");
}
break;
case AuxSwitchPos::MIDDLE:
break;
case AuxSwitchPos::LOW:
copter.flightmode->resume();
break;
}
break;

case AUX_FUNC::ZIGZAG_Auto:
#if MODE_ZIGZAG_ENABLED == ENABLED
if (copter.flightmode == &copter.mode_zigzag) {
Expand Down
7 changes: 4 additions & 3 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,14 @@ float Mode::AutoYaw::roi_yaw() const
return get_bearing_cd(copter.inertial_nav.get_position_xy_cm(), roi.xy());
}

// returns a yaw in degrees, direction of vehicle travel:
float Mode::AutoYaw::look_ahead_yaw()
{
const Vector3f& vel = copter.inertial_nav.get_velocity_neu_cms();
const float speed_sq = vel.xy().length_squared();
// Commanded Yaw to automatically look ahead.
if (copter.position_ok() && (speed_sq > (YAW_LOOK_AHEAD_MIN_SPEED * YAW_LOOK_AHEAD_MIN_SPEED))) {
_look_ahead_yaw = degrees(atan2f(vel.y,vel.x))*100.0f;
_look_ahead_yaw = degrees(atan2f(vel.y,vel.x));
}
return _look_ahead_yaw;
}
Expand Down Expand Up @@ -80,7 +81,7 @@ void Mode::AutoYaw::set_mode(Mode yaw_mode)

case Mode::LOOK_AHEAD:
// Commanded Yaw to automatically look ahead.
_look_ahead_yaw = copter.ahrs.yaw_sensor;
_look_ahead_yaw = copter.ahrs.yaw_sensor * 0.01; // cdeg -> deg
break;

case Mode::RESETTOARMEDYAW:
Expand Down Expand Up @@ -230,7 +231,7 @@ float Mode::AutoYaw::yaw_cd()

case Mode::LOOK_AHEAD:
// Commanded Yaw to automatically look ahead.
_yaw_angle_cd = look_ahead_yaw();
_yaw_angle_cd = look_ahead_yaw() * 100.0;
break;

case Mode::RESETTOARMEDYAW:
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -341,7 +341,9 @@ class Mode {
// rate_cds(): desired yaw rate in centidegrees/second:
float rate_cds();

// returns a yaw in degrees, direction of vehicle travel:
float look_ahead_yaw();

float roi_yaw() const;

// auto flight mode's yaw mode
Expand Down
4 changes: 2 additions & 2 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @DisplayName: Transition time
// @Description: Transition time in milliseconds after minimum airspeed is reached
// @Units: ms
// @Range: 2000 30000
// @Range: 500 30000
// @User: Advanced
AP_GROUPINFO("TRANSITION_MS", 11, QuadPlane, transition_time_ms, 5000),

Expand Down Expand Up @@ -1714,7 +1714,7 @@ void SLT_Transition::update()
// after airspeed is reached we degrade throttle over the
// transition time, but continue to stabilize
const uint32_t transition_timer_ms = now - transition_low_airspeed_ms;
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,2000,30000);
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,500,30000);
if (transition_timer_ms > unsigned(trans_time_ms)) {
transition_state = TRANSITION_DONE;
in_forced_transition = false;
Expand Down
16 changes: 0 additions & 16 deletions Tools/autotest/fakepos.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,22 +36,6 @@ def write(self, buf):
pass


def ft2m(x):
return x * 0.3048


def m2ft(x):
return x / 0.3048


def kt2mps(x):
return x * 0.514444444


def mps2kt(x):
return x / 0.514444444


udp = udp_out("127.0.0.1:5501")

latitude = -35
Expand Down
2 changes: 2 additions & 0 deletions Tools/autotest/locations.txt
Original file line number Diff line number Diff line change
Expand Up @@ -99,3 +99,5 @@ RF_Garage=37.621798,-2.646596,788,0
SFO_Bay=37.62561973,-122.33235387,0.0,0
Egge=60.215720,10.324071,198,303
Gundaroo=-35.02349196,149.26496411,576.8,0
Kaga=36.3268982,136.3316638,44,0

15 changes: 0 additions & 15 deletions Tools/autotest/pysim/fg_display.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,21 +44,6 @@ def write(self, buf):
pass


def ft2m(x):
return x * 0.3048


def m2ft(x):
return x / 0.3048


def kt2mps(x):
return x * 0.514444444


def mps2kt(x):
return x / 0.514444444

udp = udp_socket("127.0.0.1:5123")
fgout = udp_socket("127.0.0.1:5124", is_input=False)

Expand Down
43 changes: 16 additions & 27 deletions Tools/autotest/pysim/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,24 +29,6 @@
windowID = []


def m2ft(x):
"""Meters to feet."""
return float(x) / 0.3048


def ft2m(x):
"""Feet to meters."""
return float(x) * 0.3048


def kt2mps(x):
return x * 0.514444444


def mps2kt(x):
return x / 0.514444444


def topdir():
"""Return top of git tree where autotest is running from."""
d = os.path.dirname(os.path.realpath(__file__))
Expand Down Expand Up @@ -439,7 +421,7 @@ def start_SITL(binary,
model=None,
speedup=1,
sim_rate_hz=None,
defaults_filepath=None,
defaults_filepath=[],
unhide_parameters=False,
gdbserver=False,
breakpoints=[],
Expand Down Expand Up @@ -524,6 +506,13 @@ def start_SITL(binary,
raise RuntimeError("DISPLAY was not set")

cmd.append(binary)

if defaults_filepath is None:
defaults_filepath = []
if not isinstance(defaults_filepath, list):
defaults_filepath = [defaults_filepath]
defaults = [reltopdir(path) for path in defaults_filepath]

if not supplementary:
if wipe:
cmd.append('-w')
Expand All @@ -533,7 +522,12 @@ def start_SITL(binary,
cmd.extend(['--home', home])
cmd.extend(['--model', model])
if speedup is not None and speedup != 1:
cmd.extend(['--speedup', str(speedup)])
ntf = tempfile.NamedTemporaryFile(mode="w", delete=False)
print(f"SIM_SPEEDUP {speedup}", file=ntf)
ntf.close()
# prepend it so that a caller can override the speedup in
# passed-in defaults:
defaults = [ntf.name] + defaults
if sim_rate_hz is not None:
cmd.extend(['--rate', str(sim_rate_hz)])
if unhide_parameters:
Expand All @@ -543,13 +537,8 @@ def start_SITL(binary,
if enable_fgview_output:
cmd.append("--enable-fgview")

if defaults_filepath is not None:
if isinstance(defaults_filepath, list):
defaults = [reltopdir(path) for path in defaults_filepath]
if len(defaults):
cmd.extend(['--defaults', ",".join(defaults)])
else:
cmd.extend(['--defaults', reltopdir(defaults_filepath)])
if len(defaults):
cmd.extend(['--defaults', ",".join(defaults)])

cmd.extend(customisations)

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
118 changes: 118 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/Readme.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,118 @@
# Matek H7A3-slim Flight Controller

https://www.mateksys.com/?portfolio=h7a3-slim.


## Features
Processor
STM32H7A3RIT6 Cortex-M7 280 MHz, 2MB flash
Sensors
ICM-42688p Acc/Gyro
SPL06-001 barometer
AT7456E OSD
W25N01GV dataflash
Power
2S - 6S Lipo input voltage with voltage monitoring
9V, 2A BEC for powering Video Transmitter and camera controlled by GPIO
5V, 2A BEC for internal and peripherals
Interfaces
11x PWM outputs DShot capable
6x UARTs
1x CAN
1x I2C
4x ADC
128MB NAND for logging
USB-C port
LED
Red, 3.3V power indicator
Blue and Green, FC status
Size
36 x 36mm PCB with 30.5mm M3 mounting


## Overview

![MATEKH7A3-SLIM](H7A3-SLIM.jpg)

## Wiring Diagram


## UART Mapping

The UARTs are marked Rx* and Tx* in the above pinouts. The Rx* pin is the
receive pin for UART*. The Tx* pin is the transmit pin for UART*.

- SERIAL0 -> USB
- SERIAL1 -> USART1 (MAVLink2 telem) (DMA capable)
- SERIAL2 -> USART2 (Serial RC input) (DMA capable)
- SERIAL3 -> USART3 (GPS) (DMA capable)
- SERIAL4 -> UART4 (User) (NO DMA)
- SERIAL5 -> UART5 (User) (NO DMA)
- SERIAL6 -> USART6 (User) (NO DMA)

## CAN and I2C

H7A3-SLIM supports 1x CAN bus and 1x I2C bus
multiple CAN peripherals can be connected to one CAN bus in parallel. similarly for I2C bus.

## RC Input

RC input is configured on the USART2(SERIAL2). It supports all serial RC protocols. SERIAL2_PROTOCOL=23 by default.
- PPM is not supported.
- CRSF requires Tx2 & Rx2 connection, and set SERIAL2_OPTIONS to “0” (default).
- SBUS/DSM/SRXL connects to the Rx2 pin, but SBUS requires that the SERIAL2_OPTIONS be set to “3”.
- FPort requires connection to Tx2, and set SERIAL2_OPTIONS to “7”.
- SRXL2 requires a connection to Tx2, and automatically provides telemetry. Set SERIAL2_OPTIONS to “4”.


## OSD Support

H7A3-SLIM supports using its internal OSD using OSD_TYPE 1 (MAX7456 driver). External OSD support such as DJI or DisplayPort is supported using any spare UART. See :ref:`common-msp-osd-overview-4.2` for more info.

## PWM Output

H7A3-SLIM supports up to 11 PWM outputs. All outputs support DShot.
The PWM is in 5 groups:

- PWM 1,2 TIM1
- PWM 3,4 TIM2
- PWM 5,6,7,8 TIM3
- PWM 9,10 TIM4
- PWM 11 TIM16

## Battery Monitoring

The board has 2x built-in voltage dividers and 2x current ADC. support external 3.3V based current sensor

The correct battery setting parameters are set by default and are:

- BATT_MONITOR 4

- BATT_VOLT_PIN 10
- BATT_CURR_PIN 11
- BATT_VOLT_MULT 21.0 ("Vbat" pad support 5.5~30V input, limited by onboard regulator chips)
- BATT_AMP_PERVLT X ("Curr" pad, set it according to external current sensor spec)

- BATT2_VOLT_PIN 18
- BATT2_CURR_PIN 8
- BATT2_VOLT_MULT 21.0 ("VB2" pad support Max.69V voltage sense)
- BATT_AMP_PERVLT X ("CU2" pad, set it according to external current sensor spec)


## Compass

H7A3-SLIM does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads.

## VTX power control

GPIO 81 controls the 9V BEC output to pins marked "9V". Setting this GPIO high removes voltage supply to pins. Default GPIO 81 is low(9V output enable)

## Loading Firmware
Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled MatekH7A3.

Initial firmware load can be done with DFU by plugging in USB with the
boot button pressed. Then you should load the "ardu*_with_bl.hex" firmware, using your favourite DFU loading tool. eg STM32CubeProgrammer

Subsequently, you can update firmware with Mission Planner.


12 changes: 6 additions & 6 deletions libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat
Original file line number Diff line number Diff line change
Expand Up @@ -115,14 +115,14 @@ PB12 CAN2_RX CAN2
PB13 CAN2_TX CAN2

# PWM
PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50)
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52)
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53)
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)
PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) BIDIR
PA10 TIM1_CH3 TIM1 PWM(2) GPIO(51) BIDIR
PA15 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR
PB3 TIM2_CH2 TIM2 PWM(4) GPIO(53)
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54) BIDIR
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
PB4 TIM3_CH1 TIM3 PWM(7) GPIO(56)
PB5 TIM3_CH2 TIM3 PWM(8) GPIO(57)
PB5 TIM3_CH2 TIM3 PWM(8) GPIO(57) BIDIR
PB6 TIM4_CH1 TIM4 PWM(9) GPIO(58)
PB7 TIM4_CH2 TIM4 PWM(10) GPIO(59)
PB8 TIM16_CH1 TIM16 PWM(11) GPIO(60)
Expand Down
5 changes: 5 additions & 0 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,6 +237,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = {
// @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens
// @Values{Plane}: 176:Quadplane Fwd Throttle Override enable
// @Values{Copter, Rover, Plane, Blimp}: 177:Mount LRF enable
// @Values{Copter}: 178:FlightMode Pause/Resume
// @Values{Rover}: 201:Roll
// @Values{Rover}: 202:Pitch
// @Values{Rover}: 207:MainSail
Expand Down Expand Up @@ -673,7 +674,9 @@ void RC_Channel::init_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos
// not really aux functions:
case AUX_FUNC::LOWEHEISER_THROTTLE:
break;
#if HAL_ADSB_ENABLED
case AUX_FUNC::AVOID_ADSB:
#endif
case AUX_FUNC::AVOID_PROXIMITY:
case AUX_FUNC::FENCE:
case AUX_FUNC::GPS_DISABLE:
Expand Down Expand Up @@ -1338,9 +1341,11 @@ bool RC_Channel::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch
do_aux_function_mission_reset(ch_flag);
break;

#if HAL_ADSB_ENABLED
case AUX_FUNC::AVOID_ADSB:
do_aux_function_avoid_adsb(ch_flag);
break;
#endif

case AUX_FUNC::FFT_NOTCH_TUNE:
do_aux_function_fft_notch_tune(ch_flag);
Expand Down
1 change: 1 addition & 0 deletions libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,7 @@ class RC_Channel {
CAMERA_LENS = 175, // camera lens selection
VFWD_THR_OVERRIDE = 176, // force enabled VTOL forward throttle method
MOUNT_LRF_ENABLE = 177, // mount LRF enable/disable
FLIGHTMODE_PAUSE = 178, // e.g. pause movement towards waypoint


// inputs from 200 will eventually used to replace RCMAP
Expand Down

0 comments on commit 78b3bb5

Please sign in to comment.