Skip to content

Commit

Permalink
Revert "Merge branch 'ArduPilot:master' into hwdef_add_MicoAir405Mini"
Browse files Browse the repository at this point in the history
This reverts commit 78b3bb5, reversing
changes made to 63bafe1.
  • Loading branch information
Minderring committed Apr 11, 2024
1 parent 237dc70 commit b4265cc
Show file tree
Hide file tree
Showing 13 changed files with 69 additions and 172 deletions.
16 changes: 0 additions & 16 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,6 @@ 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 @@ -567,21 +566,6 @@ 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: 3 additions & 4 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,13 @@ 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));
_look_ahead_yaw = degrees(atan2f(vel.y,vel.x))*100.0f;
}
return _look_ahead_yaw;
}
Expand Down Expand Up @@ -81,7 +80,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 * 0.01; // cdeg -> deg
_look_ahead_yaw = copter.ahrs.yaw_sensor;
break;

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

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

case Mode::RESETTOARMEDYAW:
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -341,9 +341,7 @@ 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: 500 30000
// @Range: 2000 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,500,30000);
const float trans_time_ms = constrain_float(quadplane.transition_time_ms,2000,30000);
if (transition_timer_ms > unsigned(trans_time_ms)) {
transition_state = TRANSITION_DONE;
in_forced_transition = false;
Expand Down
16 changes: 16 additions & 0 deletions Tools/autotest/fakepos.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,22 @@ 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: 0 additions & 2 deletions Tools/autotest/locations.txt
Original file line number Diff line number Diff line change
Expand Up @@ -99,5 +99,3 @@ 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: 15 additions & 0 deletions Tools/autotest/pysim/fg_display.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,21 @@ 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: 27 additions & 16 deletions Tools/autotest/pysim/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,24 @@
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 @@ -421,7 +439,7 @@ def start_SITL(binary,
model=None,
speedup=1,
sim_rate_hz=None,
defaults_filepath=[],
defaults_filepath=None,
unhide_parameters=False,
gdbserver=False,
breakpoints=[],
Expand Down Expand Up @@ -506,13 +524,6 @@ 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 @@ -522,12 +533,7 @@ def start_SITL(binary,
cmd.extend(['--home', home])
cmd.extend(['--model', model])
if speedup is not None and speedup != 1:
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
cmd.extend(['--speedup', str(speedup)])
if sim_rate_hz is not None:
cmd.extend(['--rate', str(sim_rate_hz)])
if unhide_parameters:
Expand All @@ -537,8 +543,13 @@ def start_SITL(binary,
if enable_fgview_output:
cmd.append("--enable-fgview")

if len(defaults):
cmd.extend(['--defaults', ",".join(defaults)])
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)])

cmd.extend(customisations)

Expand Down
Binary file not shown.
118 changes: 0 additions & 118 deletions libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/Readme.md

This file was deleted.

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) 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
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)
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
PB4 TIM3_CH1 TIM3 PWM(7) GPIO(56)
PB5 TIM3_CH2 TIM3 PWM(8) GPIO(57) BIDIR
PB5 TIM3_CH2 TIM3 PWM(8) GPIO(57)
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: 0 additions & 5 deletions libraries/RC_Channel/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,6 @@ 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 @@ -674,9 +673,7 @@ 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 @@ -1341,11 +1338,9 @@ 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: 0 additions & 1 deletion libraries/RC_Channel/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,6 @@ 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 b4265cc

Please sign in to comment.