Skip to content

Commit

Permalink
Merge resolving
Browse files Browse the repository at this point in the history
  • Loading branch information
graheeth committed Nov 29, 2023
2 parents c4619a2 + 927c9f7 commit ee0da68
Show file tree
Hide file tree
Showing 615 changed files with 19,495 additions and 5,905 deletions.
6 changes: 3 additions & 3 deletions .github/workflows/test_environment.yml
Original file line number Diff line number Diff line change
Expand Up @@ -28,14 +28,14 @@ jobs:
fail-fast: false # don't cancel if a job from the matrix fails
matrix:
include:
- os: ubuntu
name: bionic
- os: ubuntu
name: focal
- os: ubuntu
name: jammy
- os: ubuntu
name: lunar
- os: ubuntu
name: mantic
- os: archlinux
name: latest
- os: debian
Expand Down Expand Up @@ -77,7 +77,7 @@ jobs:
with:
submodules: 'recursive'
- name: test install environment ${{matrix.os}}.${{matrix.name}}
timeout-minutes: 30
timeout-minutes: 45
env:
DISABLE_MAVNATIVE: True
DEBIAN_FRONTEND: noninteractive
Expand Down
2 changes: 2 additions & 0 deletions .github/workflows/test_size.yml
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,8 @@ jobs:
config: [
Durandal,
MatekF405,
KakuteF7,
MatekH743-bdshot,
Pixhawk1-1M,
MatekF405-CAN, # see special "build bootloader" code below
DrotekP3Pro, # see special "build bootloader" code below
Expand Down
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@ logs/
mav.log
mav.log.raw
mav.parm
mission.stg
/defaults.parm
/ArduCopter/defaults.parm
/ArduPlane/defaults.parm
Expand Down
4 changes: 2 additions & 2 deletions AntennaTracker/AntennaTracker.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ around. It might even damage itself.
AntennaTracker (like other ardupilot software such as ArduPlane, ArduRover
etc) has configuration values that control and tailor its operation, and which
are stored in EEPROM on the processor. The configuration is restored from
EEPROM every time the processsor starts.
EEPROM every time the processor starts.

You can use MissionPlanner, mavproxy or apm_planner or other mavlink compatible
software to check and change the configuration of your AntennaTracker.
Expand Down Expand Up @@ -219,7 +219,7 @@ the vehicle, cd to the ArduPlane directory and run this:

../Tools/autotest/sim_arduplane.sh -T --aircraft test

The -T flag tells sim_arduplane.sh to start an entenna tracker
The -T flag tells sim_arduplane.sh to start an antenna tracker
simulator and also start a virtual antenna tracker in a window.

To start the antenna tracker running run "tracker start" in the
Expand Down
2 changes: 2 additions & 0 deletions AntennaTracker/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -302,8 +302,10 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
MSG_SIMSTATE,
MSG_SYSTEM_TIME,
MSG_AHRS2,
#if COMPASS_CAL_ENABLED
MSG_MAG_CAL_REPORT,
MSG_MAG_CAL_PROGRESS,
#endif
MSG_EKF_STATUS_REPORT,
};
static const ap_message STREAM_PARAMS_msgs[] = {
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/GCS_Mavlink.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class GCS_MAVLINK_Tracker : public GCS_MAVLINK
protected:

// telem_delay is not used by Tracker but is pure virtual, thus
// this implementaiton. it probably *should* be used by Tracker,
// this implementation. it probably *should* be used by Tracker,
// as currently Tracker may brick XBees
uint32_t telem_delay() const override { return 0; }

Expand Down
30 changes: 29 additions & 1 deletion AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ const AP_Param::Info Tracker::var_info[] = {

// @Param: ONOFF_PITCH_MINT
// @DisplayName: Pitch minimum movement time
// @Description: Minimim amount of time in seconds to move in pitch
// @Description: Minimum amount of time in seconds to move in pitch
// @Units: s
// @Increment: 0.01
// @Range: 0 2
Expand Down Expand Up @@ -379,6 +379,14 @@ const AP_Param::Info Tracker::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: PITCH2SRV_PDMX
// @DisplayName: Pitch axis controller PD sum maximum
// @Description: Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Advanced

GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),

// @Param: YAW2SRV_P
Expand Down Expand Up @@ -448,6 +456,14 @@ const AP_Param::Info Tracker::var_info[] = {
// @Increment: 0.5
// @User: Advanced

// @Param: YAW2SRV_PDMX
// @DisplayName: Yaw axis controller PD sum maximum
// @Description: Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output
// @Range: 0 4000
// @Increment: 10
// @Units: d%
// @User: Advanced

GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),

#if AP_SCRIPTING_ENABLED
Expand Down Expand Up @@ -525,6 +541,18 @@ const AP_Param::Info Tracker::var_info[] = {
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
GOBJECT(logger, "LOG", AP_Logger),

#if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
#endif

#if HAL_NAVEKF3_AVAILABLE
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
#endif

AP_VAREND
};

Expand Down
2 changes: 2 additions & 0 deletions AntennaTracker/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,8 @@ class Parameters {
k_param_disarm_pwm,

k_param_auto_opts,
k_param_NavEKF2,
k_param_NavEKF3,

k_param_logger = 253, // 253 - Logging Group

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_ExternalControl_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f
}
const float yaw_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100;

// Copter velocity is positive if aicraft is moving up which is opposite the incoming NED frame.
// Copter velocity is positive if aircraft is moving up which is opposite the incoming NED frame.
Vector3f velocity_NEU_ms {
linear_velocity.x,
linear_velocity.y,
Expand Down
3 changes: 2 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,8 @@ class Copter : public AP_Vehicle {
friend class ModeZigZag;
friend class ModeAutorotate;
friend class ModeTurtle;
friend class AP_ExternalControl_Copter;

friend class _AutoTakeoff;

Copter(void);

Expand Down
Loading

0 comments on commit ee0da68

Please sign in to comment.