Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
ZeroOne-Aero authored Dec 30, 2024
2 parents 331b58d + 8875479 commit 21e4d13
Show file tree
Hide file tree
Showing 264 changed files with 66,022 additions and 65,240 deletions.
32 changes: 32 additions & 0 deletions .github/problem-matchers/Lua.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
{
"problemMatcher": [
{
"owner": "Luacheck-problem-matcher",
"fileLocation": [ "relative", "${GITHUB_WORKSPACE}" ],
"pattern": [
{
"regexp": "^( *)(.+.lua):(\\d+):(\\d+): (.*)$",
"file": 2,
"line": 3,
"column": 4,
"message": 5
}
]
},
{
"owner": "Lua-language-server-problem-matcher",
"pattern": [
{
"regexp": "^(.+.lua):(\\d+):(\\d+)",
"file": 1,
"line": 2,
"column": 3
},
{
"regexp": "^(.*)",
"message": 1
}
]
}
]
}
3 changes: 3 additions & 0 deletions .github/workflows/test_scripting.yml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,9 @@ jobs:
with:
submodules: 'recursive'

- name: Register lua problem matcher
run: echo "::add-matcher::.github/problem-matchers/Lua.json"

- name: Lua Linter
shell: bash
run: |
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Tracker.h"
#include "Tracker.h"

MAV_TYPE GCS_Tracker::frame_type() const
Expand Down
File renamed without changes.
2 changes: 1 addition & 1 deletion AntennaTracker/GCS_Tracker.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include <GCS_MAVLink/GCS.h>
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Tracker.h"

class GCS_Tracker : public GCS
{
Expand Down
14 changes: 7 additions & 7 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -222,42 +222,42 @@ const AP_Param::Info Tracker::var_info[] = {
GOBJECT(scheduler, "SCHED_", AP_Scheduler),

// @Group: SR0_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),

#if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Tracker.cpp
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
#endif

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "Tracker.h"

#include "RC_Channel.h"
#include "RC_Channel_Tracker.h"

// defining these two macros and including the RC_Channels_VarInfo
// header defines the parameter information common to all vehicle
Expand Down
File renamed without changes.
4 changes: 2 additions & 2 deletions AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,9 @@
#include "config.h"
#include "defines.h"

#include "RC_Channel.h"
#include "RC_Channel_Tracker.h"
#include "Parameters.h"
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Tracker.h"
#include "GCS_Tracker.h"

#include "AP_Arming.h"
Expand Down
1 change: 1 addition & 0 deletions AntennaTracker/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ class Mode {
GUIDED=4,
AUTO=10,
INITIALISING=16
// Mode number 30 reserved for "offboard" for external/lua control.
};

Mode() {}
Expand Down
4 changes: 2 additions & 2 deletions ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,9 @@
#include <AC_Autorotation/AC_Autorotation.h> // Autorotation controllers
#endif

#include "RC_Channel.h" // RC Channel Library
#include "RC_Channel_Copter.h" // RC Channel Library

#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"
#include "GCS_Copter.h"
#include "AP_Rally.h" // Rally point library
#include "AP_Arming.h"
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/GCS_Copter.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include <GCS_MAVLink/GCS.h>
#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"

class GCS_Copter : public GCS
{
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "Copter.h"

#include "GCS_Mavlink.h"
#include "GCS_MAVLink_Copter.h"
#include <AP_RPM/AP_RPM_config.h>
#include <AP_EFI/AP_EFI_config.h>

Expand Down
File renamed without changes.
14 changes: 7 additions & 7 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -503,42 +503,42 @@ const AP_Param::Info Copter::var_info[] = {
GOBJECTPTR(pos_control, "PSC", AC_PosControl),

// @Group: SR0_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),

#if MAVLINK_COMM_NUM_BUFFERS >= 2
// @Group: SR1_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 3
// @Group: SR2_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 4
// @Group: SR3_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 5
// @Group: SR4_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 6
// @Group: SR5_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 7
// @Group: SR6_
// @Path: GCS_Mavlink.cpp
// @Path: GCS_MAVLink_Copter.cpp
GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),
#endif

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#define AP_PARAM_VEHICLE_NAME copter

#include <AP_Common/AP_Common.h>
#include "RC_Channel.h"
#include "RC_Channel_Copter.h"
#include <AP_Proximity/AP_Proximity.h>

#if MODE_FOLLOW_ENABLED
Expand Down
11 changes: 7 additions & 4 deletions ArduCopter/RC_Channel.cpp → ArduCopter/RC_Channel_Copter.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "Copter.h"

#include "RC_Channel.h"
#include "RC_Channel_Copter.h"


// defining these two macros and including the RC_Channels_VarInfo header defines the parameter information common to all vehicle types
Expand Down Expand Up @@ -140,7 +140,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::CUSTOM_CONTROLLER:
case AUX_FUNC::WEATHER_VANE_ENABLE:
case AUX_FUNC::TRANSMITTER_TUNING:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT, ch_in);
break;
default:
RC_Channel::init_aux_function(ch_option, ch_flag);
Expand Down Expand Up @@ -169,8 +169,11 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Copter::do_aux_function(const AuxFuncTrigger &trigger)
{
const AUX_FUNC &ch_option = trigger.func;
const AuxSwitchPos &ch_flag = trigger.pos;

switch(ch_option) {
case AUX_FUNC::FLIP:
// flip if switch is on, positive throttle and we're actually flying
Expand Down Expand Up @@ -668,7 +671,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
return RC_Channel::do_aux_function(trigger);
}
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/RC_Channel.h → ArduCopter/RC_Channel_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class RC_Channel_Copter : public RC_Channel
protected:

void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(const AuxFuncTrigger &trigger) override;

private:

Expand Down
2 changes: 2 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,8 @@ class Mode {
AUTO_RTL = 27, // Auto RTL, this is not a true mode, AUTO will report as this mode if entered to perform a DO_LAND_START Landing sequence
TURTLE = 28, // Flip over after crash

// Mode number 30 reserved for "offboard" for external/lua control.

// Mode number 127 reserved for the "drone show mode" in the Skybrush
// fork at https://github.com/skybrush-io/ardupilot
};
Expand Down
Loading

0 comments on commit 21e4d13

Please sign in to comment.