Skip to content

Commit

Permalink
Merge branch 'master' into enforce-pre-commit
Browse files Browse the repository at this point in the history
  • Loading branch information
Ryanf55 authored Nov 29, 2023
2 parents d3b4d7d + 0a4eb25 commit 982299b
Show file tree
Hide file tree
Showing 91 changed files with 3,615 additions and 458 deletions.
1 change: 1 addition & 0 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const AP_Param::Info Tracker::var_info[] = {
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ const AP_Param::Info Copter::var_info[] = {
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/autoyaw.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,9 +114,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di
} else {
// absolute angle
_fixed_yaw_offset_cd = wrap_180_cd(angle_deg * 100.0 - _yaw_angle_cd);
if ( direction < 0 && is_positive(_fixed_yaw_offset_cd) ) {
if (direction < 0 && is_positive(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd -= 36000.0;
} else if ( direction > 0 && is_negative(_fixed_yaw_offset_cd) ) {
} else if (direction > 0 && is_negative(_fixed_yaw_offset_cd)) {
_fixed_yaw_offset_cd += 36000.0;
}
}
Expand Down
2 changes: 0 additions & 2 deletions ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1850,8 +1850,6 @@ void ModeAuto::do_yaw(const AP_Mission::Mission_Command& cmd)
// Do (Now) commands
/********************************************************************************/



void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.speed.target_ms > 0) {
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ const AP_Param::Info Plane::var_info[] = {
// @DisplayName: Ground station MAVLink system ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
3 changes: 3 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,9 @@ bool Mode::enter()
plane.adsb.set_is_auto_mode(does_auto_navigation());
#endif

// set the nav controller stale AFTER _enter() so that we can check if we're currently in a loiter during the mode change
plane.nav_controller->set_data_is_stale();

// reset steering integrator on mode change
plane.steerController.reset_I();

Expand Down
14 changes: 5 additions & 9 deletions ArduPlane/mode_LoiterAltQLand.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,17 +10,13 @@ bool ModeLoiterAltQLand::_enter()
return true;
}

// If we were already in a loiter then use that waypoint. Else, use the current point
const bool already_in_a_loiter = plane.nav_controller->reached_loiter_target() && !plane.nav_controller->data_is_stale();
const Location loiter_wp = already_in_a_loiter ? plane.next_WP_loc : plane.current_loc;

ModeLoiter::_enter();

#if AP_TERRAIN_AVAILABLE
if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) {
plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN);
} else {
plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
}
#else
plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME);
#endif
handle_guided_request(loiter_wp);

switch_qland();

Expand Down
2 changes: 2 additions & 0 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ const AP_Param::Info Sub::var_info[] = {
// @Param: SYSID_MYGCS
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ const AP_Param::Info Blimp::var_info[] = {
// @DisplayName: My ground station number
// @Description: Allows restricting radio overrides to only come from my ground station
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
1 change: 1 addition & 0 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ const AP_Param::Info Rover::var_info[] = {
// @DisplayName: MAVLink ground station ID
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
// @Range: 1 255
// @Increment: 1
// @User: Advanced
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),

Expand Down
5 changes: 5 additions & 0 deletions Rover/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw
// the following functions do not need initialising:
case AUX_FUNC::ACRO:
case AUX_FUNC::AUTO:
case AUX_FUNC::CIRCLE:
case AUX_FUNC::FOLLOW:
case AUX_FUNC::GUIDED:
case AUX_FUNC::HOLD:
Expand Down Expand Up @@ -226,6 +227,10 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
do_aux_function_change_mode(rover.mode_simple, ch_flag);
break;

case AUX_FUNC::CIRCLE:
do_aux_function_change_mode(rover.g2.mode_circle, ch_flag);
break;

// trigger sailboat tack
case AUX_FUNC::SAILBOAT_TACK:
// any switch movement interpreted as request to tack
Expand Down
22 changes: 8 additions & 14 deletions Rover/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,21 +82,15 @@ void ModeAuto::update()
switch (_submode) {
case SubMode::WP:
{
// check if we've reached the destination
if (!g2.wp_nav.reached_destination() || g2.wp_nav.is_fast_waypoint()) {
// update navigation controller
// boats loiter once the waypoint is reached
bool keep_navigating = true;
if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) {
keep_navigating = !start_loiter();
}

// update navigation controller
if (keep_navigating) {
navigate_to_waypoint();
} else {
// we have reached the destination so stay here
if (rover.is_boat()) {
if (!start_loiter()) {
start_stop();
}
} else {
start_stop();
}
// update distance to destination
_distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination());
}
break;
}
Expand Down
10 changes: 9 additions & 1 deletion Tools/AP_Periph/AP_Periph.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@
#include <AP_Scripting/AP_Scripting.h>
#include <AP_HAL/CANIface.h>
#include <AP_Stats/AP_Stats.h>
#include <AP_Networking/AP_Networking.h>
#include <AP_RPM/AP_RPM.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_ESC_Telem/AP_ESC_Telem_config.h>
Expand Down Expand Up @@ -77,6 +76,15 @@
#define HAL_PERIPH_CAN_MIRROR 0
#endif

#if defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT) && !defined(HAL_DEBUG_BUILD) && !defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG)
/* this checking for reboot can lose bytes on GPS modules and other
* serial devices. It is really only relevent on a debug build if you
* really want it for non-debug build then define
* HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG in hwdef.dat
*/
#undef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
#endif

#include "Parameters.h"

#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
Expand Down
4 changes: 3 additions & 1 deletion Tools/AP_Periph/networking.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
#pragma once

#include "AP_Periph.h"
#include <AP_HAL/AP_HAL_Boards.h>

#ifdef HAL_PERIPH_ENABLE_NETWORKING

#include <AP_Networking/AP_Networking.h>

#ifndef HAL_PERIPH_NETWORK_NUM_PASSTHRU
#define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2
#endif
Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/networking_passthru.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include "networking.h"
#include "AP_Periph.h"

#if defined(HAL_PERIPH_ENABLE_NETWORKING) && HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0

Expand Down
21 changes: 17 additions & 4 deletions Tools/ardupilotwaf/boards.py
Original file line number Diff line number Diff line change
Expand Up @@ -462,8 +462,8 @@ def configure_env(self, cfg, env):
# We always want to use PRI format macros
cfg.define('__STDC_FORMAT_MACROS', 1)

if cfg.options.disable_ekf2:
env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0']
if cfg.options.enable_ekf2:
env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=1']

if cfg.options.disable_ekf3:
env.CXXFLAGS += ['-DHAL_NAVEKF3_AVAILABLE=0']
Expand Down Expand Up @@ -654,6 +654,12 @@ def configure_env(self, cfg, env):
cfg.define('AP_NOTIFY_LP5562_BUS', 2)
cfg.define('AP_NOTIFY_LP5562_ADDR', 0x30)

try:
env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=0')
except ValueError:
pass
env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=1']

if self.with_can:
cfg.define('HAL_NUM_CAN_IFACES', 2)
env.DEFINES.update(CANARD_MULTI_IFACE=1,
Expand Down Expand Up @@ -793,6 +799,7 @@ def configure_env(self, cfg, env):
# whitelist of compilers which we should build with -Werror
gcc_whitelist = frozenset([
('11','3','0'),
('11','4','0'),
('12','1','0'),
])

Expand Down Expand Up @@ -871,13 +878,17 @@ def configure_env(self, cfg, env):
AP_CAN_SLCAN_ENABLED = 0,
HAL_PROXIMITY_ENABLED = 0,
AP_SCRIPTING_ENABLED = 0,
HAL_NAVEKF2_AVAILABLE = 0,
HAL_NAVEKF3_AVAILABLE = 0,
HAL_PWM_COUNT = 32,
HAL_WITH_ESC_TELEM = 1,
AP_RTC_ENABLED = 0,
)

try:
env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1')
except ValueError:
pass
env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0']

class esp32(Board):
abstract = True
Expand Down Expand Up @@ -1138,7 +1149,8 @@ def configure_env(self, cfg, env):
]

env.INCLUDES += [
cfg.srcnode.find_dir('libraries/AP_GyroFFT/CMSIS_5/include').abspath()
cfg.srcnode.find_dir('libraries/AP_GyroFFT/CMSIS_5/include').abspath(),
cfg.srcnode.find_dir('modules/ChibiOS/ext/lwip/src/include/compat/posix').abspath()
]

# whitelist of compilers which we should build with -Werror
Expand All @@ -1149,6 +1161,7 @@ def configure_env(self, cfg, env):
('9','3','1'),
('10','2','1'),
('11','3','0'),
('11','4','0'),
])

if cfg.env.HAL_CANFD_SUPPORTED:
Expand Down
22 changes: 14 additions & 8 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -7678,6 +7678,12 @@ def RichenPower(self):
raise NotAchievedException("Did not find expected GEN message")

def IE24(self):
'''Test IntelligentEnergy 2.4kWh generator with V1 and V2 telemetry protocols'''
protocol_ver = (1, 2)
for ver in protocol_ver:
self.run_IE24(ver)

def run_IE24(self, proto_ver):
'''Test IntelligentEnergy 2.4kWh generator'''
elec_battery_instance = 2
fuel_battery_instance = 1
Expand All @@ -7687,14 +7693,14 @@ def IE24(self):
"GEN_TYPE": 2,
"BATT%u_MONITOR" % (fuel_battery_instance + 1): 18, # fuel-based generator
"BATT%u_MONITOR" % (elec_battery_instance + 1): 17,
"SIM_IE24_ENABLE": 1,
"SIM_IE24_ENABLE": proto_ver,
"LOG_DISARMED": 1,
})

self.customise_SITL_commandline(["--uartF=sim:ie24"])

self.start_subtest("ensure that BATTERY_STATUS for electrical generator message looks right")
self.start_subsubtest("Checking original voltage (electrical)")
self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for electrical generator message looks right" % proto_ver)
self.start_subsubtest("Protocol %i: Checking original voltage (electrical)" % proto_ver)
# ArduPilot spits out essentially uninitialised battery
# messages until we read things fromthe battery:
self.delay_sim_time(30)
Expand All @@ -7712,13 +7718,13 @@ def IE24(self):
"battery_remaining": original_elec_m.battery_remaining - 1,
}, instance=elec_battery_instance)

self.start_subtest("ensure that BATTERY_STATUS for fuel generator message looks right")
self.start_subsubtest("Checking original voltage (fuel)")
self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for fuel generator message looks right" % proto_ver)
self.start_subsubtest("Protocol %i: Checking original voltage (fuel)" % proto_ver)
# ArduPilot spits out essentially uninitialised battery
# messages until we read things fromthe battery:
if original_fuel_m.battery_remaining <= 90:
raise NotAchievedException("Bad original percentage (want=>%f got %f" % (90, original_fuel_m.battery_remaining))
self.start_subsubtest("Ensure percentage is counting down")
self.start_subsubtest("Protocol %i: Ensure percentage is counting down" % proto_ver)
self.wait_message_field_values('BATTERY_STATUS', {
"battery_remaining": original_fuel_m.battery_remaining - 1,
}, instance=fuel_battery_instance)
Expand All @@ -7728,15 +7734,15 @@ def IE24(self):
self.disarm_vehicle()

# Test for pre-arm check fail when state is not running
self.start_subtest("If you haven't taken off generator error should cause instant failsafe and disarm")
self.start_subtest("Protocol %i: Without takeoff generator error should cause failsafe and disarm" % proto_ver)
self.set_parameter("SIM_IE24_STATE", 8)
self.wait_statustext("Status not running", timeout=40)
self.try_arm(result=False,
expect_msg="Status not running")
self.set_parameter("SIM_IE24_STATE", 2) # Explicitly set state to running

# Test that error code does result in failsafe
self.start_subtest("If you haven't taken off generator error should cause instant failsafe and disarm")
self.start_subtest("Protocol %i: Without taken off generator error should cause failsafe and disarm" % proto_ver)
self.change_mode("STABILIZE")
self.set_parameter("DISARM_DELAY", 0)
self.arm_vehicle()
Expand Down
11 changes: 6 additions & 5 deletions Tools/autotest/param_metadata/param_parse.py
Original file line number Diff line number Diff line change
Expand Up @@ -109,11 +109,12 @@ def lua_applets():

libraries = []

# AP_Vehicle also has parameters rooted at "", but isn't referenced
# from the vehicle in any way:
ap_vehicle_lib = Library("", reference="VEHICLE") # the "" is tacked onto the front of param name
setattr(ap_vehicle_lib, "Path", os.path.join('..', 'libraries', 'AP_Vehicle', 'AP_Vehicle.cpp'))
libraries.append(ap_vehicle_lib)
if args.vehicle != "AP_Periph":
# AP_Vehicle also has parameters rooted at "", but isn't referenced
# from the vehicle in any way:
ap_vehicle_lib = Library("", reference="VEHICLE") # the "" is tacked onto the front of param name
setattr(ap_vehicle_lib, "Path", os.path.join('..', 'libraries', 'AP_Vehicle', 'AP_Vehicle.cpp'))
libraries.append(ap_vehicle_lib)

libraries.append(lua_applets())

Expand Down
6 changes: 3 additions & 3 deletions Tools/autotest/sim_vehicle.py
Original file line number Diff line number Diff line change
Expand Up @@ -378,8 +378,8 @@ def do_build(opts, frame_options):
if opts.math_check_indexes:
cmd_configure.append("--enable-math-check-indexes")

if opts.disable_ekf2:
cmd_configure.append("--disable-ekf2")
if opts.enable_ekf2:
cmd_configure.append("--enable-ekf2")

if opts.disable_ekf3:
cmd_configure.append("--disable-ekf3")
Expand Down Expand Up @@ -1295,7 +1295,7 @@ def generate_frame_help():
group_sim.add_option("--fram-storage",
action='store_true',
help="use fram storage emulation")
group_sim.add_option("--disable-ekf2",
group_sim.add_option("--enable-ekf2",
action='store_true',
help="disable EKF2 in build")
group_sim.add_option("--disable-ekf3",
Expand Down
Loading

0 comments on commit 982299b

Please sign in to comment.