Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/master'
Browse files Browse the repository at this point in the history
upstream updates
  • Loading branch information
davidbitton committed Nov 15, 2023
2 parents 816ff37 + da6f31d commit c230b0c
Show file tree
Hide file tree
Showing 65 changed files with 1,379 additions and 343 deletions.
5 changes: 4 additions & 1 deletion ArduCopter/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
ArduPilot Copter Release Notes:
------------------------------------------------------------------
Copter 4.4.3 14-Nov-2023
Changes from 4.4.3-beta1
1) AP_GPS: correct uBlox M10 configuration on low flash boards
------------------------------------------------------------------
Copter 4.4.3-beta1 07-Nov-2023
Changes from 4.4.2
1) Autopilot related enhancements and fixes
Expand Down Expand Up @@ -232,7 +236,6 @@ Changes from 4.3.6
- Touchdown detection threshold is configurable (see PLDP_THRESH)
- Position controller angle max adjusted inflight with CH6 Tuning knob (set TUNE=59)
- Surface tracking time constant allows tuning response (see SURFTRAK_TC)
- Takeoff throttle max is configurable (see TKOFF_TH_MAX)
- Throttle-Gain boost increases attitude control gains when throttle high (see ATC_THR_G_BOOST)
- Waypoint navigation cornering acceleration is configurable (see WPNAV_ACCEL_C)
- WeatherVane into the wind in Auto and Guided modes (see WVANE_ENABLE)
Expand Down
1 change: 1 addition & 0 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -524,6 +524,7 @@ void Copter::allocate_motors(void)
convert_pid_parameters();
#if FRAME_CONFIG == HELI_FRAME
convert_tradheli_parameters();
motors->heli_motors_param_conversions();
#endif

#if HAL_PROXIMITY_ENABLED
Expand Down
5 changes: 3 additions & 2 deletions ArduPlane/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
Release 4.4.3-beta1 4th November 2023
-------------------------------------
Release 4.4.3 14th November 2023
--------------------------------

Changes from 4.4.2:

Expand All @@ -14,6 +14,7 @@ Changes from 4.4.2:
- protect against notch filtering with uninitialised RPM source in ESC telemetry
- allow lua scripts to populate full ESC telemetry data
- added YJUAV_A6SE_H743 support
- fixed uBlox M10 GPS support on boards with 1M flash

Release 4.4.2 23th October 2023
-------------------------------
Expand Down
6 changes: 5 additions & 1 deletion Rover/release-notes.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,11 @@
Rover Release Notes:
------------------------------------------------------------------
Rover 4.4.0-beta10 14-Nov-2023
Changes from 4.4.0-beta9
1) AP_GPS: correct uBlox M10 configuration on low flash boards
------------------------------------------------------------------
Rover 4.4.0-beta9 07-Nov-2023
Changes from 4.4.2
Changes from 4.4.0-beta8
1) Autopilot related enhancements and fixes
- BETAFTP-F405 board configuration fixes
- CubeOrangePlus-BG edition ICM45486 IMU setup fixed
Expand Down
3 changes: 3 additions & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -254,6 +254,9 @@ AP_HW_TMOTORH7 1138
AP_HW_MICOAIR405 1139
AP_HW_PixPilot-C3 1140
AP_HW_YJUAV_A6SE_H743 1141
AP_HW_FSO_POWER_STACK 1142
AP_HW_ATOMRCF405NAVI_DLX 1143


AP_HW_ESP32_PERIPH 1205
AP_HW_ESP32S3_PERIPH 1206
Expand Down
68 changes: 68 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3226,6 +3226,71 @@ def FlyMissionTwice(self):
self.wait_disarmed()
self.delay_sim_time(20)

def FlyMissionTwiceWithReset(self):
'''Fly a mission twice in a row without changing modes in between.
Allow the mission to complete, then reset the mission state machine and restart the mission.'''

self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
])

num_wp = self.get_mission_count()
self.set_parameter("AUTO_OPTIONS", 3)
self.change_mode('AUTO')
self.wait_ready_to_arm()

for i in 1, 2:
self.progress("run %u" % i)
# Use the "Reset Mission" param of DO_SET_MISSION_CURRENT to reset mission state machine
self.set_current_waypoint_using_mav_cmd_do_set_mission_current(seq=0, reset=1)
self.arm_vehicle()
self.wait_waypoint(num_wp-1, num_wp-1)
self.wait_disarmed()
self.delay_sim_time(20)

def MissionIndexValidity(self):
'''Confirm that attempting to select an invalid mission item is rejected.'''

self.upload_simple_relhome_mission([
(mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20),
(mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0),
])

num_wp = self.get_mission_count()
accepted_indices = [0, 1, num_wp-1]
denied_indices = [-1, num_wp]

for seq in accepted_indices:
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
p1=seq,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED)

for seq in denied_indices:
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
p1=seq,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED)

def InvalidJumpTags(self):
'''Verify the behaviour when selecting invalid jump tags.'''

MAX_TAG_NUM = 65535
# Jump tag is not present, so expect FAILED
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
p1=MAX_TAG_NUM,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)

# Jump tag is too big, so expect DENIED
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG,
p1=MAX_TAG_NUM+1,
timeout=1,
want_result=mavutil.mavlink.MAV_RESULT_DENIED)

def GPSViconSwitching(self):
"""Fly GPS and Vicon switching test"""
self.customise_SITL_commandline(["--uartF=sim:vicon:"])
Expand Down Expand Up @@ -10544,6 +10609,9 @@ def tests2b(self): # this block currently around 9.5mins here
self.ThrottleGainBoost,
self.ScriptMountPOI,
self.FlyMissionTwice,
self.FlyMissionTwiceWithReset,
self.MissionIndexValidity,
self.InvalidJumpTags,
self.IMUConsistency,
self.AHRSTrimLand,
self.GuidedYawRate,
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/rover.py
Original file line number Diff line number Diff line change
Expand Up @@ -6055,7 +6055,7 @@ def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1):
timeout=1,
target_sysid=target_sysid,
target_compid=target_compid,
want_result=mavutil.mavlink.MAV_RESULT_FAILED,
want_result=mavutil.mavlink.MAV_RESULT_DENIED,
)

def FlashStorage(self):
Expand Down
4 changes: 3 additions & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -5911,10 +5911,12 @@ def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None,
def set_current_waypoint_using_mav_cmd_do_set_mission_current(
self,
seq,
reset=0,
target_sysid=1,
target_compid=1):
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
p1=seq,
p2=reset,
timeout=1,
target_sysid=target_sysid,
target_compid=target_compid)
Expand Down Expand Up @@ -13179,7 +13181,7 @@ def GPSTypes(self):
(6, "SBP", None, "SBP", 5, 'detected'),
# (7, "SBP2", 9, "SBP2", 5), # broken, "waiting for config data"
(8, "NOVA", 15, "NOVA", 5, 'detected'), # no attempt to auto-detect this in AP_GPS
(11, "GSOF", 11, "GSOF", 5, 'detected'),
(11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS
(19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS
# (9, "FILE"),
]
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,7 @@ def __init__(self,
Feature('Rangefinder', 'RANGEFINDER_BLPING', 'AP_RANGEFINDER_BLPING_ENABLED', "Enable Rangefinder - BLPing", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_GYUS42V2', 'AP_RANGEFINDER_GYUS42V2_ENABLED', "Enable Rangefinder - GYUS42V2", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_HC_SR04', 'AP_RANGEFINDER_HC_SR04_ENABLED', "Enable Rangefinder - HC_SR04", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_JRE_SERIAL', 'AP_RANGEFINDER_JRE_SERIAL_ENABLED', "Enable Rangefinder - JRE_SERIAL", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_LANBAO', 'AP_RANGEFINDER_LANBAO_ENABLED', "Enable Rangefinder - Lanbao", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_LEDDARONE', 'AP_RANGEFINDER_LEDDARONE_ENABLED', "Enable Rangefinder - LeddarOne", 0, "RANGEFINDER"), # NOQA: E501
Feature('Rangefinder', 'RANGEFINDER_LEDDARVU8', 'AP_RANGEFINDER_LEDDARVU8_ENABLED', "Enable Rangefinder - LeddarVU8", 0, "RANGEFINDER"), # NOQA: E501
Expand Down
2 changes: 2 additions & 0 deletions Tools/scripts/decode_devid.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@ def num(s):
0x12 : "DEVTYPE_RM3100",
0x13 : "DEVTYPE_MMC5883",
0x14 : "DEVTYPE_AK09918",
0x15 : "DEVTYPE_AK09915",
0x16 : "DEVTYPE_QMC5883P",
}

imu_types = {
Expand Down
1 change: 1 addition & 0 deletions Tools/scripts/extract_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):
('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',),
('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',),
('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',),
('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',),

('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P<type>.*)::read\b',),

Expand Down
56 changes: 51 additions & 5 deletions libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,42 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = {
// @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,103:Pixhawk SBUS
AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1),

// @Param: FL_VLT_MAX
// @DisplayName: Full fuel level voltage
// @Description: The voltage seen on the analog pin when the fuel tank is full.
// @Range: 0 10
// @Units: V
// @User: Advanced
AP_GROUPINFO("FL_VLT_MAX", 44, AP_BattMonitor_FuelLevel_Analog, _fuel_level_max_voltage, -1),

// @Param: FL_FF
// @DisplayName: First order term
// @Description: First order polynomial fit term
// @Range: 0 10
// @User: Advanced
AP_GROUPINFO("FL_FF", 45, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_first_order_coeff, 1),

// @Param: FL_FS
// @DisplayName: Second order term
// @Description: Second order polynomial fit term
// @Range: 0 10
// @User: Advanced
AP_GROUPINFO("FL_FS", 46, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_second_order_coeff, 0),

// @Param: FL_FT
// @DisplayName: Third order term
// @Description: Third order polynomial fit term
// @Range: 0 10
// @User: Advanced
AP_GROUPINFO("FL_FT", 47, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_third_order_coeff, 0),

// @Param: FL_OFF
// @DisplayName: Offset term
// @Description: Offset polynomial fit term
// @Range: 0 10
// @User: Advanced
AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0),

// Param indexes must be between 40 and 49 to avoid conflict with other battery monitor param tables loaded by pointer

AP_GROUPEND
Expand Down Expand Up @@ -96,16 +132,24 @@ void AP_BattMonitor_FuelLevel_Analog::read()
const uint32_t tnow = AP_HAL::micros();
const uint32_t dt_us = tnow - _state.last_time_micros;

// get voltage from an ADC pin and filter it
const float voltage = _analog_source->voltage_average();
// get voltage from an ADC pin
const float raw_voltage = _analog_source->voltage_average();

// Converting sensor reading to actual volume in tank in Litres (quadratic fit)
const float voltage =
(_fuel_fit_third_order_coeff * raw_voltage * raw_voltage * raw_voltage) +
(_fuel_fit_second_order_coeff * raw_voltage * raw_voltage) +
(_fuel_fit_first_order_coeff * raw_voltage) +
_fuel_fit_offset;

const float filtered_voltage = _voltage_filter.apply(voltage, float(dt_us) * 1.0e-6f);
const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage;

// output the ADC voltage to the voltage field for easier calibration of sensors
// also output filtered voltage as a measure of tank slosh filtering
// this could be useful for tuning the LPF
_state.voltage = voltage;
_state.current_amps = filtered_voltage;
const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage;

_state.voltage = filtered_voltage;

// this driver assumes that CAPACITY is set to tank volume in millilitres.
// _fuel_level_voltage_mult is calculated by the user as 1 / (full_voltage - empty_voltage)
Expand All @@ -115,6 +159,8 @@ void AP_BattMonitor_FuelLevel_Analog::read()
// map consumed_mah to consumed millilitres
_state.consumed_mah = fuel_level_used_ratio * _params._pack_capacity;

_state.current_amps = 0;

// map consumed_wh using fixed voltage of 1
_state.consumed_wh = _state.consumed_mah;

Expand Down
10 changes: 8 additions & 2 deletions libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

#include <Filter/LowPassFilter.h>
#include "AP_BattMonitor.h"
#include <Filter/Filter.h> // Filter library

class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend
{
Expand All @@ -40,20 +41,25 @@ class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend
bool has_consumed_energy() const override { return true; }

// returns true if battery monitor provides current info
bool has_current() const override { return true; }
bool has_current() const override { return false; }

void init(void) override {}

private:

AP_Float _fuel_level_empty_voltage;
AP_Float _fuel_level_max_voltage;
AP_Float _fuel_level_voltage_mult;
AP_Float _fuel_level_filter_frequency;
AP_Int8 _pin;

AP_Float _fuel_fit_first_order_coeff;
AP_Float _fuel_fit_second_order_coeff;
AP_Float _fuel_fit_third_order_coeff;
AP_Float _fuel_fit_offset;
AP_HAL::AnalogSource *_analog_source;

LowPassFilterFloat _voltage_filter;

};

#endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED
21 changes: 21 additions & 0 deletions libraries/AP_Compass/AP_Compass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#if AP_COMPASS_DRONECAN_ENABLED
#include "AP_Compass_DroneCAN.h"
#endif
#include "AP_Compass_QMC5883P.h"
#include "AP_Compass_MMC3416.h"
#include "AP_Compass_MMC5xx3.h"
#include "AP_Compass_MAG3110.h"
Expand Down Expand Up @@ -1132,6 +1133,26 @@ void Compass::_probe_external_i2c_compasses(void)
#endif
#endif // AP_COMPASS_QMC5883L_ENABLED

#if AP_COMPASS_QMC5883P_ENABLED
//external i2c bus
FOREACH_I2C_EXTERNAL(i) {
ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),
true, HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL));
}

// internal i2c bus
#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE)
if (all_external) {
// only probe QMC5883P on internal if we are treating internals as externals
FOREACH_I2C_INTERNAL(i) {
ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR),
all_external,
all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL));
}
}
#endif
#endif // AP_COMPASS_QMC5883P_ENABLED

#ifndef HAL_BUILD_AP_PERIPH
// AK09916 on ICM20948
#if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED
Expand Down
5 changes: 4 additions & 1 deletion libraries/AP_Compass/AP_Compass.h
Original file line number Diff line number Diff line change
Expand Up @@ -481,7 +481,10 @@ friend class AP_Compass_Backend;
#if AP_COMPASS_MMC5XX3_ENABLED
DRIVER_MMC5XX3 =19,
#endif
};
#if AP_COMPASS_QMC5883P_ENABLED
DRIVER_QMC5883P =20,
#endif
};

bool _driver_enabled(enum DriverType driver_type);

Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Compass/AP_Compass_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ class AP_Compass_Backend
DEVTYPE_MMC5983 = 0x13,
DEVTYPE_AK09918 = 0x14,
DEVTYPE_AK09915 = 0x15,
DEVTYPE_QMC5883P = 0x16,
};

#if AP_COMPASS_MSP_ENABLED
Expand Down
Loading

0 comments on commit c230b0c

Please sign in to comment.