Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
BryonOI authored Nov 14, 2024
2 parents 145e4d0 + f07df39 commit e9b52bf
Show file tree
Hide file tree
Showing 425 changed files with 21,735 additions and 5,112 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/colcon.yml
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
6 changes: 3 additions & 3 deletions .github/workflows/cygwin_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,7 @@ jobs:
source ~/ccache.conf &&
ccache -s
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: D:/a/ardupilot/ardupilot/ccache
key: ${{ steps.ccache_cache_timestamp.outputs.cache-key }}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand All @@ -188,8 +188,8 @@ jobs:
shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}'
run: >-
ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip &&
python -m pip install --progress-bar off empy==3.3.4 pexpect &&
python -m pip install --progress-bar off dronecan --upgrade &&
python3 -m pip install --progress-bar off empy==3.3.4 pexpect &&
python3 -m pip install --progress-bar off dronecan --upgrade &&
cp /usr/bin/ccache /usr/local/bin/ &&
cd /usr/local/bin && ln -s ccache /usr/local/bin/gcc &&
ln -s ccache /usr/local/bin/g++ &&
Expand Down
6 changes: 3 additions & 3 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ jobs:
sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10
update-alternatives --query python
python --version
python3 --version
pip3 install gevent
# we actualy want 3.11 .. but the above only gave us 3.10, not ok with esp32 builds.
Expand All @@ -188,7 +188,7 @@ jobs:
sudo apt-get install python3 python3-pip python3-venv python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools
update-alternatives --query python
pip3 install gevent
python --version
python3 --version
python3.11 --version
which python3.11
sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.11 11
Expand Down Expand Up @@ -229,7 +229,7 @@ jobs:
./install.sh
source ./export.sh
cd ../..
python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan
python3 -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan
which cmake
./waf configure --board ${{matrix.config}}
echo './waf configure --board ${{matrix.config}}' >> $GITHUB_STEP_SUMMARY
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/macos_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -169,7 +169,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
4 changes: 4 additions & 0 deletions .github/workflows/qurt_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,9 @@ jobs:
cp -a build/QURT/bin/arducopter build/QURT/ArduPilot_Copter.so
cp -a build/QURT/bin/arduplane build/QURT/ArduPilot_Plane.so
cp -a build/QURT/bin/ardurover build/QURT/ArduPilot_Rover.so
libraries/AP_HAL_QURT/packaging/make_package.sh ArduCopter arducopter
libraries/AP_HAL_QURT/packaging/make_package.sh ArduPlane arduplane
libraries/AP_HAL_QURT/packaging/make_package.sh Rover ardurover
- name: Archive build
uses: actions/upload-artifact@v4
Expand All @@ -168,4 +171,5 @@ jobs:
build/QURT/ArduPilot_Plane.so
build/QURT/ArduPilot_Rover.so
build/QURT/ArduPilot.so
libraries/AP_HAL_QURT/packaging/*.deb
retention-days: 7
2 changes: 1 addition & 1 deletion .github/workflows/test_chibios.yml
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{ matrix.gcc }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_coverage.yml
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_dds.yml
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.config }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_linux_sbc.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{matrix.config}}-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_replay.yml
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
1 change: 1 addition & 0 deletions .github/workflows/test_scripts.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ jobs:
python-cleanliness,
astyle-cleanliness,
validate_board_list,
logger_metadata,
]
steps:
# git checkout the PR
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_blimp.yml
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/test_sitl_copter.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down Expand Up @@ -302,7 +302,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-base-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/test_sitl_periph.yml
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down Expand Up @@ -222,7 +222,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_plane.yml
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_rover.yml
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_sub.yml
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_sitl_tracker.yml
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_size.yml
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/test_unit_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ jobs:
NOW=$(date -u +"%F-%T")
echo "timestamp=${NOW}" >> $GITHUB_OUTPUT
- name: ccache cache files
uses: actions/cache@v3
uses: actions/cache@v4
with:
path: ~/.ccache
key: ${{github.workflow}}-ccache-${{ matrix.toolchain }}-${{steps.ccache_cache_timestamp.outputs.timestamp}}
Expand Down
51 changes: 49 additions & 2 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,10 +276,16 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
#endif
MSG_MEMINFO,
MSG_NAV_CONTROLLER_OUTPUT,
#if AP_GPS_GPS_RAW_INT_SENDING_ENABLED
MSG_GPS_RAW,
#endif
#if AP_GPS_GPS_RTK_SENDING_ENABLED
MSG_GPS_RTK,
#if GPS_MAX_RECEIVERS > 1
#endif
#if AP_GPS_GPS2_RAW_SENDING_ENABLED
MSG_GPS2_RAW,
#endif
#if AP_GPS_GPS2_RTK_SENDING_ENABLED
MSG_GPS2_RTK,
#endif
};
Expand Down Expand Up @@ -315,7 +321,8 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_BATTERY_STATUS,
};
static const ap_message STREAM_PARAMS_msgs[] = {
MSG_NEXT_PARAM
MSG_NEXT_PARAM,
MSG_AVAILABLE_MODES
};

const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
Expand Down Expand Up @@ -643,3 +650,43 @@ void GCS_MAVLINK_Tracker::send_global_position_int()
0, // Z speed cm/s (+ve Down)
tracker.ahrs.yaw_sensor); // compass heading in 1/100 degree
}

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t GCS_MAVLINK_Tracker::send_available_mode(uint8_t index) const
{
const Mode* modes[] {
&tracker.mode_manual,
&tracker.mode_stop,
&tracker.mode_scan,
&tracker.mode_guided,
&tracker.mode_servotest,
&tracker.mode_auto,
&tracker.mode_initialising,
};

const uint8_t mode_count = ARRAY_SIZE(modes);

// Convert to zero indexed
const uint8_t index_zero = index - 1;
if (index_zero >= mode_count) {
// Mode does not exist!?
return mode_count;
}

// Ask the mode for its name and number
const char* name = modes[index_zero]->name();
const uint8_t mode_number = (uint8_t)modes[index_zero]->number();

mavlink_msg_available_modes_send(
chan,
mode_count,
index,
MAV_STANDARD_MODE::MAV_STANDARD_MODE_NON_STANDARD,
mode_number,
0, // MAV_MODE_PROPERTY bitmask
name
);

return mode_count;
}
4 changes: 4 additions & 0 deletions AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
void send_nav_controller_output() const override;
void send_pid_tuning() override;

// Send the mode with the given index (not mode number!) return the total number of modes
// Index starts at 1
uint8_t send_available_mode(uint8_t index) const override;

private:

void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
Expand Down
Loading

0 comments on commit e9b52bf

Please sign in to comment.