Skip to content

Commit

Permalink
Merge branch 'ArduPilot:master' into raw_IMU_hz
Browse files Browse the repository at this point in the history
  • Loading branch information
Astik-2002 authored Feb 26, 2024
2 parents ad82db6 + e9d065c commit 3c8148d
Show file tree
Hide file tree
Showing 30 changed files with 271 additions and 227 deletions.
1 change: 1 addition & 0 deletions .github/workflows/esp32_build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,7 @@ jobs:
- name: Install Prerequisites
shell: bash
run: |
sudo apt-get update
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
Expand Down
6 changes: 3 additions & 3 deletions AntennaTracker/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,13 @@

#include "ap_version.h"

#define THISFIRMWARE "AntennaTracker V4.5.0-dev"
#define THISFIRMWARE "AntennaTracker V4.6.0-dev"

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 4,5,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 4,6,0,FIRMWARE_VERSION_TYPE_DEV

#define FW_MAJOR 4
#define FW_MINOR 5
#define FW_MINOR 6
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

Expand Down
80 changes: 62 additions & 18 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @User: Standard
AP_GROUPINFO("FWD_THR_USE", 37, QuadPlane, q_fwd_thr_use, uint8_t(FwdThrUse::OFF)),

// @Param: BCK_PIT_LIM
// @DisplayName: Q mode rearward pitch limit
// @Description: This sets the maximum number of degrees of back or pitch up in Q modes when the airspeed is at AIRSPEED_MIN, and is used to prevent excessive sutructural loads when pitching up decelerate. If airspeed is above or below AIRSPEED_MIN, the pitch up/back will be adjusted according to the formula pitch_limit = Q_BCK_PIT_LIM * (AIRSPEED_MIN / IAS)^2. The backwards/up pitch limit controlled by this parameter is in addition to limiting applied by PTCH_LIM_MAX_DEG and Q_ANGLE_MAX. The BCK_PIT_LIM limit is only applied when Q_FWD_THR_USE is set to 1 or 2 and the vehicle is flying in a mode that uses forward throttle instead of forward tilt to generate forward speed. Set to a non positive value 0 to deactivate this limit.
// @Units: deg
// @Range: 0.0 15.0
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO("BCK_PIT_LIM", 38, QuadPlane, q_bck_pitch_lim, 10.0f),

AP_GROUPEND
};

Expand Down Expand Up @@ -3016,21 +3025,55 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f);

// Relax forward tilt limit if the position controller is saturating in the forward direction because
// the forward thrust motor could be failed
const float fwd_tilt_range_cd = (float)aparm.angle_max - 100.0f * q_fwd_pitch_lim;
if (is_positive(fwd_tilt_range_cd)) {
// rate limit the forward tilt change to slew between the motor good and motor failed
// value over 10 seconds
const bool fwd_limited = plane.quadplane.pos_control->is_active_xy() and plane.quadplane.pos_control->get_fwd_pitch_is_limited();
const float fwd_pitch_lim_cd_tgt = fwd_limited ? (float)aparm.angle_max : 100.0f * q_fwd_pitch_lim;
const float delta_max = 0.1f * fwd_tilt_range_cd * plane.G_Dt;
q_fwd_pitch_lim_cd += constrain_float((fwd_pitch_lim_cd_tgt - q_fwd_pitch_lim_cd), -delta_max, delta_max);
// Don't let the forward pitch limit be more than the forward pitch demand before limiting to
// avoid opening up the limit more than necessary
q_fwd_pitch_lim_cd = MIN(q_fwd_pitch_lim_cd, MAX(-(float)plane.nav_pitch_cd, 100.0f * q_fwd_pitch_lim));
} else {
// take the lesser of the two limits
q_fwd_pitch_lim_cd = (float)aparm.angle_max;
// the forward thrust motor could be failed. Do not do this with tilt rotors because they do not rely on
// forward throttle during VTOL flight
if (!tiltrotor.enabled()) {
const float fwd_tilt_range_cd = (float)aparm.angle_max - 100.0f * q_fwd_pitch_lim;
if (is_positive(fwd_tilt_range_cd)) {
// rate limit the forward tilt change to slew between the motor good and motor failed
// value over 10 seconds
const bool fwd_limited = plane.quadplane.pos_control->is_active_xy() and plane.quadplane.pos_control->get_fwd_pitch_is_limited();
const float fwd_pitch_lim_cd_tgt = fwd_limited ? (float)aparm.angle_max : 100.0f * q_fwd_pitch_lim;
const float delta_max = 0.1f * fwd_tilt_range_cd * plane.G_Dt;
q_fwd_pitch_lim_cd += constrain_float((fwd_pitch_lim_cd_tgt - q_fwd_pitch_lim_cd), -delta_max, delta_max);
// Don't let the forward pitch limit be more than the forward pitch demand before limiting to
// avoid opening up the limit more than necessary
q_fwd_pitch_lim_cd = MIN(q_fwd_pitch_lim_cd, MAX(-(float)plane.nav_pitch_cd, 100.0f * q_fwd_pitch_lim));
} else {
// take the lesser of the two limits
q_fwd_pitch_lim_cd = (float)aparm.angle_max;
}
}

// Prevent the wing from being overloaded when braking from high speed in a VTOL mode
float nav_pitch_upper_limit_cd = 100.0f * q_bck_pitch_lim;
float aspeed;
if (is_positive(q_bck_pitch_lim) && ahrs.airspeed_estimate(aspeed)) {
const float reference_speed = MAX(plane.aparm.airspeed_min, MIN_AIRSPEED_MIN);
float speed_scaler = sq(reference_speed / MAX(aspeed, 0.1f));
nav_pitch_upper_limit_cd *= speed_scaler;
nav_pitch_upper_limit_cd = MIN(nav_pitch_upper_limit_cd, (float)aparm.angle_max);

const float tconst = 0.5f;
const float dt = AP_HAL::millis() - q_pitch_limit_update_ms;
q_pitch_limit_update_ms = AP_HAL::millis();
if (is_positive(dt)) {
const float coef = dt / (dt + tconst);
q_bck_pitch_lim_cd = (1.0f - coef) * q_bck_pitch_lim_cd + coef * nav_pitch_upper_limit_cd;
}

plane.nav_pitch_cd = MIN(plane.nav_pitch_cd, (int32_t)q_bck_pitch_lim_cd);

#if HAL_LOGGING_ENABLED
AP::logger().WriteStreaming("QBRK",
"TimeUS,SpdScaler,NPULCD,QBPLCD,NPCD", // labels
"Qffii", // fmt
AP_HAL::micros64(),
(double)speed_scaler,
(double)nav_pitch_upper_limit_cd,
(int32_t)q_bck_pitch_lim_cd,
(int32_t)plane.nav_pitch_cd);
#endif
}

float fwd_thr_scaler;
Expand All @@ -3054,14 +3097,15 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
#if HAL_LOGGING_ENABLED
// Diagnostics logging - remove when feature is fully flight tested.
AP::logger().WriteStreaming("FWDT",
"TimeUS,fts,qfplcd,npllcd,npcd,qft", // labels
"Qfffff", // fmt
"TimeUS,fts,qfplcd,npllcd,npcd,qft,npulcd", // labels
"Qffffff", // fmt
AP_HAL::micros64(),
(double)fwd_thr_scaler,
(double)q_fwd_pitch_lim_cd,
(double)nav_pitch_lower_limit_cd,
(double)plane.nav_pitch_cd,
(double)q_fwd_throttle);
(double)q_fwd_throttle,
(float)nav_pitch_upper_limit_cd);
#endif

plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd);
Expand Down
5 changes: 5 additions & 0 deletions ArduPlane/quadplane.h
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,9 @@ class QuadPlane
// limit applied to forward pitch to prevent wing producing negative lift
AP_Float q_fwd_pitch_lim;

// limit applied to back pitch to prevent wing producing excessive lift
AP_Float q_bck_pitch_lim;

// which fwd throttle handling method is active
enum class ActiveFwdThr : uint8_t {
NONE = 0,
Expand Down Expand Up @@ -441,6 +444,8 @@ class QuadPlane

float q_fwd_throttle; // forward throttle used in q modes
float q_fwd_pitch_lim_cd; // forward pitch limit applied when using q_fwd_throttle
float q_bck_pitch_lim_cd; // backward pitch limit applied when using Q_BCK_PIT_LIM
uint32_t q_pitch_limit_update_ms; // last time the backward pitch limit was updated

// when did we last run the attitude controller?
uint32_t last_att_control_ms;
Expand Down
15 changes: 15 additions & 0 deletions Tools/AP_Periph/ReleaseNotes.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,18 @@
Release 1.7.0 26th February 2023
--------------------------------

This is a major AP_Periph release with the following key changes:

- fixed DroneCAN packet parsing bug when dealing with corrupt packets
- added BATT_HIDE_MASK parameter
- support IPv4 networking in AP_Periph and PPP gateway
- support per-cell battery monitoring
- rate limit EFI updates
- support serial tunnelling over DroneCAN
- support relays over DroneCAN via hardpoint messages
- support mapping MAVLink SEND_TEXT to DroneCAN debug levels
- fixed CANFD timings

Release 1.6.0 8th September 2023
--------------------------------

Expand Down
6 changes: 3 additions & 3 deletions Tools/AP_Periph/version.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
#include "ap_version.h"
#include <AP_HAL/AP_HAL.h>

#define THISFIRMWARE "AP_Periph V1.7.0-dev"
#define THISFIRMWARE "AP_Periph V1.8.0-dev"

// defines needed due to lack of GCS includes
#ifndef HAVE_ENUM_FIRMWARE_VERSION_TYPE
Expand All @@ -17,10 +17,10 @@
#endif

// the following line is parsed by the autotest scripts
#define FIRMWARE_VERSION 1,7,0,FIRMWARE_VERSION_TYPE_DEV
#define FIRMWARE_VERSION 1,8,0,FIRMWARE_VERSION_TYPE_DEV

#define FW_MAJOR 1
#define FW_MINOR 7
#define FW_MINOR 8
#define FW_PATCH 0
#define FW_TYPE FIRMWARE_VERSION_TYPE_DEV

Expand Down
2 changes: 1 addition & 1 deletion Tools/ardupilotwaf/ap_library.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def _vehicle_index(vehicle):
return _vehicle_indexes[vehicle]

# note that AP_NavEKF3_core.h is needed for AP_NavEKF3_feature.h
_vehicle_macros = ['SKETCHNAME', 'SKETCH', 'APM_BUILD_DIRECTORY',
_vehicle_macros = ['APM_BUILD_DIRECTORY', 'AP_BUILD_TARGET_NAME',
'APM_BUILD_TYPE', 'APM_BUILD_COPTER_OR_HELI',
'AP_NavEKF3_core.h', 'lua_generated_bindings.h']
_macros_re = re.compile(r'\b(%s)\b' % '|'.join(_vehicle_macros))
Expand Down
6 changes: 2 additions & 4 deletions Tools/ardupilotwaf/ardupilotwaf.py
Original file line number Diff line number Diff line change
Expand Up @@ -125,14 +125,12 @@ def get_legacy_defines(sketch_name, bld):
if bld.cmd == 'heli' or 'heli' in bld.targets:
return [
'APM_BUILD_DIRECTORY=APM_BUILD_Heli',
'SKETCH="' + sketch_name + '"',
'SKETCHNAME="' + sketch_name + '"',
'AP_BUILD_TARGET_NAME="' + sketch_name + '"',
]

return [
'APM_BUILD_DIRECTORY=APM_BUILD_' + sketch_name,
'SKETCH="' + sketch_name + '"',
'SKETCHNAME="' + sketch_name + '"',
'AP_BUILD_TARGET_NAME="' + sketch_name + '"',
]

IGNORED_AP_LIBRARIES = [
Expand Down
2 changes: 1 addition & 1 deletion Tools/autotest/vehicle_test_suite.py
Original file line number Diff line number Diff line change
Expand Up @@ -7966,7 +7966,7 @@ def statustext_in_collections(self, text, regex=False):
if "STATUSTEXT" not in c.collections:
raise NotAchievedException("Asked to check context but it isn't collecting!")
for x in c.collections["STATUSTEXT"]:
self.progress(" statustext=%s vs text=%s" % (x.text, text))
self.progress(" statustext want=(%s) got=(%s)" % (x.text, text))
if regex:
if re.match(text, x.text):
return x
Expand Down
16 changes: 8 additions & 8 deletions libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
#ifndef AC_ATC_MULTI_RATE_RP_IMAX
# define AC_ATC_MULTI_RATE_RP_IMAX 0.5f
#endif
#ifndef AC_ATC_MULTI_RATE_RP_FILT_HZ
# define AC_ATC_MULTI_RATE_RP_FILT_HZ 20.0f
#ifndef AC_ATC_MULTI_RATE_RPY_FILT_HZ
# define AC_ATC_MULTI_RATE_RPY_FILT_HZ 20.0f
#endif
#ifndef AC_ATC_MULTI_RATE_YAW_P
# define AC_ATC_MULTI_RATE_YAW_P 0.180f
Expand Down Expand Up @@ -106,9 +106,9 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl {
.d = AC_ATC_MULTI_RATE_RP_D,
.ff = 0.0f,
.imax = AC_ATC_MULTI_RATE_RP_IMAX,
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_T_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.filt_E_hz = 0.0f,
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_D_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.srmax = 0,
.srtau = 1.0
}
Expand All @@ -120,9 +120,9 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl {
.d = AC_ATC_MULTI_RATE_RP_D,
.ff = 0.0f,
.imax = AC_ATC_MULTI_RATE_RP_IMAX,
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_T_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.filt_E_hz = 0.0f,
.filt_D_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_D_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.srmax = 0,
.srtau = 1.0
}
Expand All @@ -135,9 +135,9 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl {
.d = AC_ATC_MULTI_RATE_YAW_D,
.ff = 0.0f,
.imax = AC_ATC_MULTI_RATE_YAW_IMAX,
.filt_T_hz = AC_ATC_MULTI_RATE_RP_FILT_HZ,
.filt_T_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.filt_E_hz = AC_ATC_MULTI_RATE_YAW_FILT_HZ,
.filt_D_hz = 0.0f,
.filt_D_hz = AC_ATC_MULTI_RATE_RPY_FILT_HZ,
.srmax = 0,
.srtau = 1.0
}
Expand Down
6 changes: 3 additions & 3 deletions libraries/AC_CustomControl/AC_CustomControl_PID.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,9 +323,9 @@ AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_V
_p_angle_roll2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_p_angle_pitch2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_p_angle_yaw2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f),
_pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f),
_pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f)
_pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f),
_pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f),
_pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f)
{
_dt = dt;
AP_Param::setup_object_defaults(this, var_info);
Expand Down
6 changes: 3 additions & 3 deletions libraries/AC_CustomControl/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -243,9 +243,9 @@ AC_CustomControl_PID::AC_CustomControl_PID(AC_CustomControl &frontend, AP_AHRS_V
_p_angle_roll2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_p_angle_pitch2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_p_angle_yaw2(AC_ATTITUDE_CONTROL_ANGLE_P * 0.90f),
_pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt),
_pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, dt),
_pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RP_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f, dt)
_pid_atti_rate_roll(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, dt),
_pid_atti_rate_pitch(AC_ATC_MULTI_RATE_RP_P * 0.90f, AC_ATC_MULTI_RATE_RP_I * 0.90f, AC_ATC_MULTI_RATE_RP_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RP_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, 0.0f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, dt),
_pid_atti_rate_yaw(AC_ATC_MULTI_RATE_YAW_P * 0.90f, AC_ATC_MULTI_RATE_YAW_I * 0.90f, AC_ATC_MULTI_RATE_YAW_D * 0.90f, 0.0f, AC_ATC_MULTI_RATE_YAW_IMAX * 0.90f, AC_ATC_MULTI_RATE_RPY_FILT_HZ * 0.90f, AC_ATC_MULTI_RATE_YAW_FILT_HZ * 0.90f, 0.0f, dt)
{
AP_Param::setup_object_defaults(this, var_info);
}
Expand Down
14 changes: 7 additions & 7 deletions libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,11 +70,11 @@ void setup()
void loop()
{
// setup (unfortunately must be done here as we cannot create a global AC_PID object)
AC_PID pid(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER);
AC_HELI_PID heli_pid(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER);
AC_PID *pid = new AC_PID(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER);
// AC_HELI_PID *heli_pid= new AC_HELI_PID(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER);

// display PID gains
hal.console->printf("P %f I %f D %f imax %f\n", (double)pid.kP(), (double)pid.kI(), (double)pid.kD(), (double)pid.imax());
hal.console->printf("P %f I %f D %f imax %f\n", (double)pid->kP(), (double)pid->kI(), (double)pid->kD(), (double)pid->imax());

RC_Channel *c = rc().channel(0);
if (c == nullptr) {
Expand All @@ -91,10 +91,10 @@ void loop()
rc().read_input(); // poll the radio for new values
const uint16_t radio_in = c->get_radio_in();
const int16_t error = radio_in - radio_trim;
pid.update_error(error, TEST_DT);
const float control_P = pid.get_p();
const float control_I = pid.get_i();
const float control_D = pid.get_d();
pid->update_error(error, TEST_DT);
const float control_P = pid->get_p();
const float control_I = pid->get_i();
const float control_D = pid->get_d();

// display pid results
hal.console->printf("radio: %d\t err: %d\t pid:%4.2f (p:%4.2f i:%4.2f d:%4.2f)\n",
Expand Down
Loading

0 comments on commit 3c8148d

Please sign in to comment.