Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rockblock4 #2

Open
wants to merge 85 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
85 commits
Select commit Hold shift + click to select a range
c721752
AP_HAL_ChibiOS: fix incorrect definition of AP_PERIPH_MAG_ENABLED for…
shiv-tyagi Jan 30, 2025
c4654c9
AP_HAL_ChibiOS: use AP_PERIPH_BARO_ENABLED in place of HAL_PERIPH_ENA…
shiv-tyagi Jan 30, 2025
4fca0cc
AP_Scripting: use AP_PERIPH_BARO_ENABLED in place of HAL_PERIPH_ENABL…
shiv-tyagi Jan 30, 2025
dba4136
Tools: create and use AP_PERIPH_BARO_ENABLED
shiv-tyagi Jan 30, 2025
061f382
AP_Logger: use GCS_SEND_TEXT for error message rather than stdout
peterbarker Jan 29, 2025
97e87df
AP_HAL_ChibiOS: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
45db7d2
AP_HAL_Empty: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
0a617b5
AP_HAL: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
07d5938
AP_HAL_Linux: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
049ad39
AP_HAL_QURT: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
51d1cee
AP_HAL_SITL: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
d5922b2
AP_Notify: avoid use of OwnPtr for ToshibaLED
peterbarker Jan 28, 2025
4697365
AP_HAL_ESP32: add get_device_ptr to HAL I2CDevice API
peterbarker Jan 29, 2025
2ef98e1
Tools: size_compare_branches.py: mark navigator64 as a Linux board
peterbarker Jan 30, 2025
c3f2b40
Copter: free allocations in case of allocation failure
peterbarker Jan 29, 2025
6bf29ec
AP_AIS: remove incorrect use of strncat
peterbarker Jan 29, 2025
63afcae
AP_Filesystem: ROMFS: fix open race conditions
tpwrules Jan 31, 2025
4e35eb3
SITL: fix array-bounds warning in tsys01 sim
peterbarker Jan 29, 2025
46d99a4
HAL_ChibiOS: support LSE for clock on STM32L4xx
tridge Jan 30, 2025
0679282
AP_Bootloader: support CAN termination switch and LED
tridge Jan 30, 2025
30e3533
AP_Periph: support CAN switch and LED defines
tridge Jan 29, 2025
05dd0f8
Tools: define board type for TBS_L431_Periph
tridge Jan 17, 2025
70305ba
hwdef: added TBS-L431-Airspeed
tridge Jan 17, 2025
0cacc90
Tools: added TBS periph bootloader
tridge Jan 17, 2025
e5f719b
Copter: SystemID: Fix unutilized variables
lthall Jan 30, 2025
2cd3970
GCS_MAVLink: add capability to send autopilot to config error loop
peterbarker Feb 1, 2025
5790e0e
AP_HAL_ChibiOS: use AP_PERIPH_RANGEFINDER_ENABLED in place of HAL_PER…
shiv-tyagi Jan 31, 2025
c324143
Tools: create and use AP_PERIPH_RANGEFINDER_ENABLED
shiv-tyagi Jan 31, 2025
8c94c6e
Reserving IDs for Lumenier.
djmorvay Jan 24, 2025
f6a6e35
AP_AIS: fix multi part message decoding
IamPete1 Jan 30, 2025
4ddd78e
Plane: plane.h: remove unused definitions
IamPete1 Feb 2, 2025
3e37b01
Plane: remove unused method `set_target_altitude_current_adjusted`
IamPete1 Feb 2, 2025
e5efe49
Plane: takeoff: use `tkoff_option_is_set` helper
IamPete1 Feb 2, 2025
7667a04
Sub: remove dead variable
clydemcqueen Sep 23, 2024
025df25
Sub: poshold requires GPS
clydemcqueen Sep 23, 2024
2a28b77
Sub: limit poshold xy velocity to PILOT_SPEED to avoid bounceback
clydemcqueen Dec 7, 2024
1df6744
autotest: test poshold bounceback
clydemcqueen Dec 7, 2024
ab46ca2
Sub: support MASK_LOG_IMU_FAST (loop rate logging)
clydemcqueen Nov 25, 2024
a1421e7
AP_Baro: update MS5837_BA30 temperature compensation
ES-Alexander Jan 24, 2025
e5e3e9a
autotest: do not assert COMPASS_LEARN value after we set it
peterbarker Feb 3, 2025
9a1dc96
board_types.txt: add SULILGH7-P1-P2
SULILG Feb 1, 2025
4db73d3
APM_Control: add test for roll and pitch controllers
IamPete1 Jan 16, 2025
f8dd0b2
APM_Control: add AP_FW_Controller as common base class to roll and pi…
IamPete1 Aug 3, 2024
790290d
APM_Control: AP_AutoTune: add static `axis_string` method
IamPete1 Nov 8, 2024
44d2fc1
AMP_Control: move pitch and roll `autotune_start` into base `AP_FW_Co…
IamPete1 Nov 8, 2024
63fecc7
APM_Control: examples: AP_FW_Controller_test: update to use HAL SITL
IamPete1 Feb 1, 2025
022c43c
AP_HAL_SITL: Add getter for `SITL_State`
IamPete1 Feb 1, 2025
f59f28b
Tools: autotest: arduplane: check param values after autotune
IamPete1 Feb 2, 2025
31fe3d3
Tools: autotest: suite: add `check_parameter_value` to to check parma…
IamPete1 Feb 2, 2025
0b7a56e
AP_ESC_Telem: fix RPM timeout race
robertlong13 Jan 3, 2025
4eab74f
AP_Vehicle: add comment for ESC Telem update rate
robertlong13 Jan 3, 2025
fe0a0db
AP_Arming: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming
peterbarker Jan 15, 2025
569386c
ArduCopter: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming
peterbarker Jan 15, 2025
5dc7751
Tools: move REQUIRE_POSITION_FROM_ARMING bit to AP_arming
peterbarker Jan 15, 2025
505b373
gitignore: ignore .python-version file used by pyenv
shiv-tyagi Jan 26, 2025
a2ca9be
Plane:adjust CTUN.Pitch to remove PITCH_TRIM
Hwurzburg Jan 27, 2025
cdfe939
Plane: remove dead store of cruise_speed
peterbarker Jan 29, 2025
8fdfed5
AP_Notify: use only AP_NOTIFY_TONEALARM_ENABLED to guard tonealarm ba…
peterbarker Jan 31, 2025
8a9a182
AP_HAL: move enabling of AP_NOTIFY_TONEALARM_ENABLED out of AP_Notify…
peterbarker Jan 31, 2025
6f40c80
AP_Notify: move enabling of AP_NOTIFY_TONEALARM_ENABLED out of AP_Not…
peterbarker Jan 31, 2025
613aa60
waf: move setting of -cl-single-precision-constant into cxx-flags block
peterbarker Jan 31, 2025
eed3e14
AP_BattMonitor: remove use of ownptr
peterbarker Feb 1, 2025
9c12476
AP_Airspeed: AUAV airspeed support
Tdogb Jan 30, 2025
bac78b5
Tools: allow selection of AUAV airspeed in custom build server
Tdogb Jan 30, 2025
131c0f8
SITL: Clarification for timestamp in JSON interface
Tuxliri Jan 28, 2025
4bad4f8
AP_HAL: change IsMavCAN to IsForwardedFrame
bugobliterator Jan 30, 2025
f9a8d9b
AP_CANManager: use updated frame callback types
bugobliterator Jan 30, 2025
51471a0
AP_Networking: make can multicast an endpoint by default
bugobliterator Jan 30, 2025
402936a
bootloaders: update bootloaders using networking
bugobliterator Jan 30, 2025
f8726ee
AP_HAL_ChibiOS: disable mcast bridging in bootloader
bugobliterator Feb 4, 2025
3acb03b
autotest: add test for Rover's require-location-for-arming flag
peterbarker Jan 14, 2025
0fb5a21
AP_Arming: add option to require position for Rover before arming
peterbarker Feb 3, 2025
4959cee
Rover: add option to require position for Rover before arming
peterbarker Feb 3, 2025
a1cf1cf
Tools: add option to require position for Rover before arming
peterbarker Feb 3, 2025
f6922db
.github: exclude QURT changes when running various workflows
peterbarker Jan 29, 2025
54a71ce
AP_Airspeed: Calibration: remove unused DT
IamPete1 Feb 4, 2025
400699f
waf: stop clang complaining about variable-length stack arrays
peterbarker Feb 4, 2025
dd54f02
AP_ESC_Telem: fix timeout race
robertlong13 Jan 9, 2025
5370165
SIM_XPlane: avoid leaking memory upon json load failure
peterbarker Jan 29, 2025
26c61f5
SIM_XPlane: remove use-after-free issue
peterbarker Feb 4, 2025
e9e419d
autotest: add test for fetching invalid fence point
peterbarker Feb 4, 2025
4161c42
GCS_MAVLink: simplify MissionItemProtocol get_item interface
peterbarker Feb 4, 2025
db8931f
Tools:reserve bd id for BrahamF4
Hwurzburg Feb 5, 2025
8c7afb3
waf: correct clang++ extension name
peterbarker Feb 5, 2025
1b0c89c
AP_Scripting: Update rockblock and MAVLinkHL with additional commands…
stephendade Jan 29, 2025
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
2 changes: 2 additions & 0 deletions .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -74,6 +75,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/qurt_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -74,6 +75,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_replay.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -81,6 +82,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_blimp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -88,6 +89,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_copter.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -87,6 +88,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/bootloaders/**'
- 'Tools/CHDK-Script/**'
Expand Down Expand Up @@ -86,6 +87,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/bootloaders/**'
- 'Tools/CHDK-Script/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_plane.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -87,6 +88,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_rover.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -87,6 +88,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_sub.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -88,6 +89,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_sitl_tracker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down Expand Up @@ -88,6 +89,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# remove non SITL directories
- 'Tools/AP_Bootloader/**'
- 'Tools/AP_Periph/**'
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_unit_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# Remove change on other workflows
- '.github/workflows/test_environment.yml'
pull_request:
Expand Down Expand Up @@ -88,6 +89,7 @@ on:
# remove non SITL HAL
- 'libraries/AP_HAL_ChibiOS/**'
- 'libraries/AP_HAL_ESP32/**'
- 'libraries/AP_HAL_QURT/**'
# Remove change on other workflows
- '.github/workflows/test_environment.yml'
workflow_dispatch:
Expand Down
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -172,3 +172,4 @@ ENV/
env.bak/
venv.bak/
autotest_result_*_junit.xml
.python-version
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -460,7 +460,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif

if (mode_requires_gps || copter.option_is_enabled(Copter::FlightOption::REQUIRE_POSITION_FOR_ARMING)) {
if (mode_requires_gps || require_location == RequireLocation::YES) {
if (!copter.position_ok()) {
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");
Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -451,6 +451,8 @@ AP_Vehicle::custom_mode_state* Copter::register_custom_mode(const uint8_t num, c
}
if (mode_guided_custom[i] == nullptr) {
// Allocation failure
free((void*)full_name_copy);
free((void*)short_name_copy);
return nullptr;
}

Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -632,7 +632,6 @@ class Copter : public AP_Vehicle {
DISABLE_THRUST_LOSS_CHECK = (1<<0), // 1
DISABLE_YAW_IMBALANCE_WARNING = (1<<1), // 2
RELEASE_GRIPPER_ON_THRUST_LOSS = (1<<2), // 4
REQUIRE_POSITION_FOR_ARMING = (1<<3), // 8
};

// type of fast rate attitude controller in operation
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1003,7 +1003,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Param: FLIGHT_OPTIONS
// @DisplayName: Flight mode options
// @Description: Flight mode specific options
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss, 3:Require position for arming
// @Bitmask: 0:Disable thrust loss check, 1:Disable yaw imbalance warning, 2:Release gripper on thrust loss
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 44, ParametersG2, flight_options, 0),

Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/mode_systemid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,8 @@ void ModeSystemId::exit()
// should be called at 100hz or more
void ModeSystemId::run()
{
float target_roll, target_pitch;
float target_roll = 0.0f;
float target_pitch = 0.0f;
float target_yaw_rate = 0.0f;
float pilot_throttle_scaled = 0.0f;
float target_climb_rate = 0.0f;
Expand Down
12 changes: 9 additions & 3 deletions ArduPlane/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,13 +102,19 @@ void Plane::Log_Write_Control_Tuning()
synthetic_airspeed = logger.quiet_nan();
}

int16_t pitch = ahrs.pitch_sensor - g.pitch_trim * 100;
#if HAL_QUADPLANE_ENABLED
if (quadplane.show_vtol_view()) {
pitch = quadplane.ahrs_view->pitch_sensor;
}
#endif
struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
time_us : AP_HAL::micros64(),
nav_roll_cd : (int16_t)nav_roll_cd,
roll : (int16_t)ahrs.roll_sensor,
nav_pitch_cd : (int16_t)nav_pitch_cd,
pitch : (int16_t)ahrs.pitch_sensor,
pitch : pitch,
throttle_out : SRV_Channels::get_output_scaled(SRV_Channel::k_throttle),
rudder_out : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder),
throttle_dem : TECS_controller.get_throttle_demand(),
Expand Down Expand Up @@ -312,8 +318,8 @@ const struct LogStructure Plane::log_structure[] = {
// @Field: TimeUS: Time since system startup
// @Field: NavRoll: desired roll
// @Field: Roll: achieved roll
// @Field: NavPitch: desired pitch
// @Field: Pitch: achieved pitch
// @Field: NavPitch: desired pitch assuming pitch trims are already applied
// @Field: Pitch: achieved pitch assuming pitch trims are already applied,ie "0deg" is level flight trimmed pitch attitude as shown on artifical horizon level line.
// @Field: ThO: scaled output throttle
// @Field: RdO: scaled output rudder
// @Field: ThD: demanded speed-height-controller throttle
Expand Down
16 changes: 0 additions & 16 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -347,10 +347,6 @@ class Plane : public AP_Vehicle {
// time of last mode change
uint32_t last_mode_change_ms;

// Used to maintain the state of the previous control switch position
// This is set to 254 when we need to re-read the switch
uint8_t oldSwitchPosition = 254;

// This is used to enable the inverted flight feature
bool inverted_flight;

Expand Down Expand Up @@ -758,8 +754,6 @@ class Plane : public AP_Vehicle {
// A starting value used to check the status of a conditional command.
// For example in a delay command the condition_start records that start time for the delay
uint32_t condition_start;
// A value used in condition commands. For example the rate at which to change altitude.
int16_t condition_rate;

// 3D Location vectors
// Location structure defined in AP_Common
Expand Down Expand Up @@ -808,8 +802,6 @@ class Plane : public AP_Vehicle {

float relative_altitude;

// loop performance monitoring:
AP::PerfInfo perf_info;
struct {
uint32_t last_trim_check;
uint32_t last_trim_save;
Expand Down Expand Up @@ -904,7 +896,6 @@ class Plane : public AP_Vehicle {
float relative_ground_altitude(bool use_rangefinder_if_available);
float relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available);
void set_target_altitude_current(void);
void set_target_altitude_current_adjusted(void);
void set_target_altitude_location(const Location &loc);
int32_t relative_target_altitude_cm(void);
void change_target_altitude(int32_t change_cm);
Expand Down Expand Up @@ -1042,13 +1033,10 @@ class Plane : public AP_Vehicle {
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;

// control_modes.cpp
void read_control_switch();
uint8_t readSwitch(void) const;
void autotune_start(void);
void autotune_restore(void);
void autotune_enable(bool enable);
bool fly_inverted(void);
bool mode_allows_autotuning(void);
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
Mode *mode_from_mode_num(const enum Mode::Number num);
bool current_mode_requires_mission() const override {
Expand Down Expand Up @@ -1077,7 +1065,6 @@ class Plane : public AP_Vehicle {
bool trigger_land_abort(const float climb_to_alt_m);
void get_osd_roll_pitch_rad(float &roll, float &pitch) const override;
float tecs_hgt_afe(void);
void efi_update(void);
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
Expand Down Expand Up @@ -1113,7 +1100,6 @@ class Plane : public AP_Vehicle {
void calc_gndspeed_undershoot();
void update_loiter(uint16_t radius);
void update_loiter_update_nav(uint16_t radius);
void update_cruise();
void update_fbwb_speed_height(void);
void setup_turn_angle(void);
bool reached_loiter_target(void);
Expand Down Expand Up @@ -1168,7 +1154,6 @@ class Plane : public AP_Vehicle {
float apply_throttle_limits(float throttle_in);
void set_throttle(void);
void set_takeoff_expected(void);
void set_servos_old_elevons(void);
void set_servos_flaps(void);
void set_landing_gear(void);
void dspoiler_update(void);
Expand Down Expand Up @@ -1196,7 +1181,6 @@ class Plane : public AP_Vehicle {
// parachute.cpp
void parachute_check();
#if HAL_PARACHUTE_ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);
void parachute_release();
bool parachute_manual_release();
#endif
Expand Down
11 changes: 0 additions & 11 deletions ArduPlane/altitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,17 +208,6 @@ void Plane::set_target_altitude_current(void)
#endif
}

/*
set the target altitude to the current altitude, with ALT_OFFSET adjustment
*/
void Plane::set_target_altitude_current_adjusted(void)
{
set_target_altitude_current();

// use adjusted_altitude_cm() to take account of ALTITUDE_OFFSET
target_altitude.amsl_cm = adjusted_altitude_cm();
}

/*
set target altitude based on a location structure
*/
Expand Down
14 changes: 5 additions & 9 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4257,19 +4257,15 @@ float QuadPlane::get_land_airspeed(void)
if (qstate == QPOS_APPROACH ||
plane.control_mode == &plane.mode_rtl) {
const float cruise_speed = plane.aparm.airspeed_cruise;
// assume cruise speed, but try to do better:
float approach_speed = cruise_speed;
float tecs_land_airspeed = plane.TECS_controller.get_land_airspeed();
if (is_positive(tecs_land_airspeed)) {
approach_speed = tecs_land_airspeed;
} else {
if (qstate == QPOS_APPROACH) {
// default to half way between min airspeed and cruise
// airspeed when on the approach
approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min);
} else {
// otherwise cruise
approach_speed = cruise_speed;
}
} else if (qstate == QPOS_APPROACH) {
// default to half way between min airspeed and cruise
// airspeed when on the approach
approach_speed = 0.5*(cruise_speed+plane.aparm.airspeed_min);
}
const float time_to_pos1 = (plane.auto_state.wp_distance - stopping_distance(sq(approach_speed))) / MAX(approach_speed, 5);
/*
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ void Plane::takeoff_calc_throttle() {
const float current_baro_alt = barometer.get_altitude();
const bool below_lvl_alt = current_baro_alt < auto_state.baro_takeoff_alt + mode_takeoff.level_alt;
// Set the minimum throttle limit.
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
const bool use_throttle_range = tkoff_option_is_set(AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
if (!use_throttle_range // We don't want to employ a throttle range.
|| !ahrs.using_airspeed_sensor() // We don't have an airspeed sensor.
|| below_lvl_alt // We are below TKOFF_LVL_ALT.
Expand Down
Loading
Loading