Skip to content

Commit 8a78b20

Browse files
authored
Merge branch 'ArduPilot:master' into loadFactorFix
2 parents a3f97d1 + d76bf32 commit 8a78b20

File tree

286 files changed

+5366
-1703
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

286 files changed

+5366
-1703
lines changed

.github/workflows/test_ccache.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -140,5 +140,5 @@ jobs:
140140
run: |
141141
PATH="/usr/lib/ccache:/opt/gcc-arm-none-eabi-${{matrix.gcc}}/bin:$PATH"
142142
Tools/scripts/build_tests/test_ccache.py --boards MatekF405,MatekF405-bdshot --min-cache-pct=75
143-
Tools/scripts/build_tests/test_ccache.py --boards CubeOrange,Durandal --min-cache-pct=75
143+
Tools/scripts/build_tests/test_ccache.py --boards Durandal,Pixhawk6X --min-cache-pct=73
144144

AntennaTracker/GCS_Mavlink.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -425,7 +425,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_component_arm_disarm(const mavlin
425425
return MAV_RESULT_UNSUPPORTED;
426426
}
427427

428-
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet)
428+
MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
429429
{
430430
switch(packet.command) {
431431

@@ -444,7 +444,7 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_long_packet(const mavlink_command
444444
return MAV_RESULT_ACCEPTED;
445445

446446
default:
447-
return GCS_MAVLINK::handle_command_long_packet(packet);
447+
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
448448
}
449449
}
450450

AntennaTracker/GCS_Mavlink.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
2121

2222
MAV_RESULT handle_command_component_arm_disarm(const mavlink_command_int_t &packet) override;
2323
MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;
24-
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
24+
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
2525

2626
int32_t global_position_int_relative_alt() const override {
2727
return 0; // what if we have been picked up and carried somewhere?
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
/*
2+
external control library for copter
3+
*/
4+
5+
6+
#include "AP_ExternalControl_Copter.h"
7+
#if AP_EXTERNAL_CONTROL_ENABLED
8+
9+
#include "Copter.h"
10+
11+
/*
12+
set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw
13+
velocity is in earth frame, NED, m/s
14+
*/
15+
bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)
16+
{
17+
if (!ready_for_external_control()) {
18+
return false;
19+
}
20+
const float yaw_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100;
21+
22+
// Copter velocity is positive if aicraft is moving up which is opposite the incoming NED frame.
23+
Vector3f velocity_NEU_ms {
24+
linear_velocity.x,
25+
linear_velocity.y,
26+
-linear_velocity.z };
27+
Vector3f velocity_up_cms = velocity_NEU_ms * 100;
28+
copter.mode_guided.set_velocity(velocity_up_cms, false, 0, !isnan(yaw_rate_rads), yaw_rate_cds);
29+
return true;
30+
}
31+
32+
bool AP_ExternalControl_Copter::ready_for_external_control()
33+
{
34+
return copter.flightmode->in_guided_mode() && copter.motors->armed();
35+
}
36+
37+
#endif // AP_EXTERNAL_CONTROL_ENABLED
Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
/*
2+
external control library for copter
3+
*/
4+
#pragma once
5+
6+
#include <AP_ExternalControl/AP_ExternalControl.h>
7+
8+
#if AP_EXTERNAL_CONTROL_ENABLED
9+
10+
class AP_ExternalControl_Copter : public AP_ExternalControl {
11+
public:
12+
/*
13+
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
14+
Velocity is in earth frame, NED [m/s].
15+
Yaw is in earth frame, NED [rad/s].
16+
*/
17+
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override;
18+
private:
19+
/*
20+
Return true if Copter is ready to handle external control data.
21+
Currently checks mode and arm states.
22+
*/
23+
bool ready_for_external_control();
24+
};
25+
26+
#endif // AP_EXTERNAL_CONTROL_ENABLED

ArduCopter/Copter.h

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,11 @@
100100
#include "AP_Rally.h" // Rally point library
101101
#include "AP_Arming.h"
102102

103+
#include <AP_ExternalControl/AP_ExternalControl_config.h>
104+
#if AP_EXTERNAL_CONTROL_ENABLED
105+
#include "AP_ExternalControl_Copter.h"
106+
#endif
107+
103108
#include <AP_Beacon/AP_Beacon_config.h>
104109
#if AP_BEACON_ENABLED
105110
#include <AP_Beacon/AP_Beacon.h>
@@ -193,6 +198,9 @@ class Copter : public AP_Vehicle {
193198
friend class AP_AdvancedFailsafe_Copter;
194199
#endif
195200
friend class AP_Arming_Copter;
201+
#if AP_EXTERNAL_CONTROL_ENABLED
202+
friend class AP_ExternalControl_Copter;
203+
#endif
196204
friend class ToyMode;
197205
friend class RC_Channel_Copter;
198206
friend class RC_Channels_Copter;
@@ -319,6 +327,12 @@ class Copter : public AP_Vehicle {
319327
AP_OpticalFlow optflow;
320328
#endif
321329

330+
// external control library
331+
#if AP_EXTERNAL_CONTROL_ENABLED
332+
AP_ExternalControl_Copter external_control;
333+
#endif
334+
335+
322336
// system time in milliseconds of last recorded yaw reset from ekf
323337
uint32_t ekfYawReset_ms;
324338
int8_t ekf_primary_core;

ArduCopter/GCS_Mavlink.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -736,7 +736,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_co
736736
#endif
737737
}
738738

739-
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet)
739+
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
740740
{
741741
switch(packet.command) {
742742
#if MODE_FOLLOW_ENABLED == ENABLED
@@ -757,7 +757,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
757757
return handle_command_pause_continue(packet);
758758

759759
default:
760-
return GCS_MAVLINK::handle_command_int_packet(packet);
760+
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
761761
}
762762
}
763763

@@ -779,7 +779,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
779779
}
780780
#endif
781781

782-
MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet)
782+
MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
783783
{
784784
switch(packet.command) {
785785

@@ -1004,7 +1004,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
10041004
}
10051005

10061006
default:
1007-
return GCS_MAVLINK::handle_command_long_packet(packet);
1007+
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
10081008
}
10091009
}
10101010

ArduCopter/GCS_Mavlink.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -32,8 +32,8 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK
3232
#if HAL_MOUNT_ENABLED
3333
MAV_RESULT handle_command_mount(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
3434
#endif
35-
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
36-
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
35+
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
36+
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
3737
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
3838
MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet);
3939

ArduCopter/ReleaseNotes.txt

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
ArduPilot Copter Release Notes:
22
------------------------------------------------------------------
3-
Copter 4.4.0-beta5 12-Aug-2023
3+
Copter 4.4.0 18-Aug-2023 / 4.4.0-beta5 12-Aug-2023
44
Changes from 4.4.0-beta4
55
1) Autopilots specific changes
66
- SIYI N7 support
@@ -288,7 +288,14 @@ Changes from 4.3.6
288288
- Webots 2023a simulator support
289289
- XPlane support for wider range of aircraft
290290
------------------------------------------------------------------
291-
Copter 4.3.7-beta1 24-May-2023
291+
Copter 4.3.8-beta1 12-Aug-2023
292+
Changes from 4.3.7
293+
1) Bug fixes
294+
- DroneCAN GPS RTK injection fix
295+
- INAxxx battery monitors allow for battery reset remaining
296+
- Notch filter gyro glitch caused by race condition fixed
297+
- Scripting restart memory corruption bug fixed
298+
------------------------------------------------------------------
292299
Copter 4.3.7 31-May-2023 / 4.3.7-beta1 24-May-2023
293300
Changes from 4.3.6
294301
1) Bug fixes

ArduCopter/config.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
/// change in your local copy of APM_Config.h.
2828
///
2929
#include "APM_Config.h"
30+
#include <AP_Follow/AP_Follow_config.h>
3031

3132

3233
//////////////////////////////////////////////////////////////////////////////
@@ -189,7 +190,7 @@
189190
//////////////////////////////////////////////////////////////////////////////
190191
// Follow - follow another vehicle or GCS
191192
#ifndef MODE_FOLLOW_ENABLED
192-
# define MODE_FOLLOW_ENABLED ENABLED
193+
# define MODE_FOLLOW_ENABLED AP_FOLLOW_ENABLED
193194
#endif
194195

195196
//////////////////////////////////////////////////////////////////////////////
@@ -255,7 +256,7 @@
255256
//////////////////////////////////////////////////////////////////////////////
256257
// Turtle - allow vehicle to be flipped over after a crash
257258
#ifndef MODE_TURTLE_ENABLED
258-
# define MODE_TURTLE_ENABLED !defined(DISABLE_DSHOT) && FRAME_CONFIG != HELI_FRAME
259+
# define MODE_TURTLE_ENABLED HAL_DSHOT_ENABLED && FRAME_CONFIG != HELI_FRAME
259260
#endif
260261

261262
//////////////////////////////////////////////////////////////////////////////

ArduCopter/mode.h

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
#include "Copter.h"
44
#include <AP_Math/chirp.h>
5+
#include <AP_ExternalControl/AP_ExternalControl_config.h> // TODO why is this needed if Copter.h includes this
56
class Parameters;
67
class ParametersG2;
78

@@ -957,6 +958,10 @@ class ModeFlowHold : public Mode {
957958
class ModeGuided : public Mode {
958959

959960
public:
961+
#if AP_EXTERNAL_CONTROL_ENABLED
962+
friend class AP_ExternalControl_Copter;
963+
#endif
964+
960965
// inherit constructor
961966
using Mode::Mode;
962967
Number mode_number() const override { return Number::GUIDED; }
@@ -1718,6 +1723,7 @@ class ModeAvoidADSB : public ModeGuided {
17181723

17191724
};
17201725

1726+
#if AP_FOLLOW_ENABLED
17211727
class ModeFollow : public ModeGuided {
17221728

17231729
public:
@@ -1747,6 +1753,7 @@ class ModeFollow : public ModeGuided {
17471753

17481754
uint32_t last_log_ms; // system time of last time desired velocity was logging
17491755
};
1756+
#endif
17501757

17511758
class ModeZigZag : public Mode {
17521759

ArduPlane/GCS_Mavlink.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -711,7 +711,7 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
711711
#if HAL_ADSB_ENABLED
712712
plane.avoidance_adsb.handle_msg(msg);
713713
#endif
714-
#if AP_SCRIPTING_ENABLED
714+
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
715715
// pass message to follow library
716716
plane.g2.follow.handle_msg(msg);
717717
#endif
@@ -950,7 +950,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_guided_slew_commands(const mavl
950950

951951
}
952952

953-
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet)
953+
MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
954954
{
955955
switch(packet.command) {
956956

@@ -963,7 +963,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
963963
case MAV_CMD_GUIDED_CHANGE_HEADING:
964964
return handle_command_int_guided_slew_commands(packet);
965965

966-
#if AP_SCRIPTING_ENABLED
966+
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
967967
case MAV_CMD_DO_FOLLOW:
968968
// param1: sysid of target to follow
969969
if ((packet.param1 > 0) && (packet.param1 <= 255)) {
@@ -974,11 +974,11 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
974974
#endif
975975

976976
default:
977-
return GCS_MAVLINK::handle_command_int_packet(packet);
977+
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
978978
}
979979
}
980980

981-
MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet)
981+
MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
982982
{
983983
switch(packet.command) {
984984

@@ -1103,7 +1103,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
11031103
#endif
11041104

11051105
default:
1106-
return GCS_MAVLINK::handle_command_long_packet(packet);
1106+
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
11071107
}
11081108
}
11091109

ArduPlane/GCS_Mavlink.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,8 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK
2424
bool sysid_enforce() const override;
2525

2626
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
27-
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
28-
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
27+
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
28+
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
2929
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override;
3030

3131
void send_position_target_global_int() override;

ArduPlane/Parameters.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1235,7 +1235,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
12351235
// @Bitmask: 0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
12361236
AP_GROUPINFO("ONESHOT_MASK", 32, ParametersG2, oneshot_mask, 0),
12371237

1238-
#if AP_SCRIPTING_ENABLED
1238+
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
12391239
// @Group: FOLL
12401240
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
12411241
AP_SUBGROUPINFO(follow, "FOLL", 33, ParametersG2, AP_Follow),

ArduPlane/Parameters.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -550,7 +550,7 @@ class ParametersG2 {
550550
AC_PID guidedHeading{5000.0, 0.0, 0.0, 0 , 10.0, 5.0, 5.0 , 5.0 , 0.2};
551551
#endif
552552

553-
#if AP_SCRIPTING_ENABLED
553+
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
554554
AP_Follow follow;
555555
#endif
556556

ArduPlane/Plane.h

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,6 +83,10 @@
8383
#include <AP_Landing/AP_Landing.h>
8484
#include <AP_LandingGear/AP_LandingGear.h> // Landing Gear library
8585
#include <AP_Follow/AP_Follow.h>
86+
#include <AP_ExternalControl/AP_ExternalControl_config.h>
87+
#if AP_EXTERNAL_CONTROL_ENABLED
88+
#include <AP_ExternalControl/AP_ExternalControl.h>
89+
#endif
8690

8791
#include "GCS_Mavlink.h"
8892
#include "GCS_Plane.h"
@@ -770,6 +774,11 @@ class Plane : public AP_Vehicle {
770774

771775
AP_Param param_loader {var_info};
772776

777+
// dummy implementation of external control
778+
#if AP_EXTERNAL_CONTROL_ENABLED
779+
AP_ExternalControl external_control;
780+
#endif
781+
773782
static const AP_Scheduler::Task scheduler_tasks[];
774783
static const AP_Param::Info var_info[];
775784

ArduPlane/ReleaseNotes.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
Release 4.4.0 18th August 2023
2+
------------------------------
3+
4+
No changes from beta5
5+
16
Release 4.4.0-beta5 11th August 2023
27
------------------------------------
38

ArduSub/GCS_Mavlink.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -460,7 +460,7 @@ bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) {
460460
}
461461

462462

463-
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet)
463+
MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg)
464464
{
465465
switch (packet.command) {
466466
case MAV_CMD_NAV_LOITER_UNLIM:
@@ -516,7 +516,7 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_long_packet(const mavlink_command_lon
516516
return MAV_RESULT_ACCEPTED;
517517

518518
default:
519-
return GCS_MAVLINK::handle_command_long_packet(packet);
519+
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
520520
}
521521
}
522522

0 commit comments

Comments
 (0)