mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: remove TRIM_AUTO param
This commit is contained in:
parent
6ebef3fe6b
commit
8e693e5cd1
@ -569,13 +569,6 @@ const AP_Param::Info Plane::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90),
|
GSCALAR(ground_steer_dps, "GROUND_STEER_DPS", 90),
|
||||||
|
|
||||||
// @Param: TRIM_AUTO
|
|
||||||
// @DisplayName: Automatic trim adjustment
|
|
||||||
// @Description: Enables the setting SERVOn_TRIM values to current levels when switching out of MANUAL mode. Should not be left on as mode switches while the plane is rolling or pitching can cause invalid trim values and subsequent unstable behavior. See newer and safer SERVO_AUTO_TRIM parameter for automated results.
|
|
||||||
// @Values: 0:Disabled,1:Enabled
|
|
||||||
// @User: Standard
|
|
||||||
GSCALAR(auto_trim, "TRIM_AUTO", AUTO_TRIM),
|
|
||||||
|
|
||||||
// @Param: MIXING_GAIN
|
// @Param: MIXING_GAIN
|
||||||
// @DisplayName: Mixing Gain
|
// @DisplayName: Mixing Gain
|
||||||
// @Description: The gain for the Vtail and elevon output mixers. The default is 0.5, which ensures that the mixer doesn't saturate, allowing both input channels to go to extremes while retaining control over the output. Hardware mixers often have a 1.0 gain, which gives more servo throw, but can saturate. If you don't have enough throw on your servos with VTAIL_OUTPUT or ELEVON_OUTPUT enabled then you can raise the gain using MIXING_GAIN. The mixer allows outputs in the range 900 to 2100 microseconds.
|
// @Description: The gain for the Vtail and elevon output mixers. The default is 0.5, which ensures that the mixer doesn't saturate, allowing both input channels to go to extremes while retaining control over the output. Hardware mixers often have a 1.0 gain, which gives more servo throw, but can saturate. If you don't have enough throw on your servos with VTAIL_OUTPUT or ELEVON_OUTPUT enabled then you can raise the gain using MIXING_GAIN. The mixer allows outputs in the range 900 to 2100 microseconds.
|
||||||
|
@ -51,7 +51,7 @@ public:
|
|||||||
|
|
||||||
// Misc
|
// Misc
|
||||||
//
|
//
|
||||||
k_param_auto_trim = 10,
|
k_param_auto_trim = 10, // unused
|
||||||
k_param_log_bitmask_old, // unused
|
k_param_log_bitmask_old, // unused
|
||||||
k_param_pitch_trim_cd,
|
k_param_pitch_trim_cd,
|
||||||
k_param_mix_mode,
|
k_param_mix_mode,
|
||||||
@ -424,7 +424,6 @@ public:
|
|||||||
|
|
||||||
// Misc
|
// Misc
|
||||||
//
|
//
|
||||||
AP_Int8 auto_trim;
|
|
||||||
AP_Int8 rudder_only;
|
AP_Int8 rudder_only;
|
||||||
AP_Float mixing_gain;
|
AP_Float mixing_gain;
|
||||||
AP_Int16 mixing_offset;
|
AP_Int16 mixing_offset;
|
||||||
|
@ -60,15 +60,11 @@ void Plane::fence_check()
|
|||||||
case AC_FENCE_ACTION_GUIDED:
|
case AC_FENCE_ACTION_GUIDED:
|
||||||
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
|
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
|
||||||
case AC_FENCE_ACTION_RTL_AND_LAND:
|
case AC_FENCE_ACTION_RTL_AND_LAND:
|
||||||
// make sure we don't auto trim the surfaces on this mode change
|
|
||||||
int8_t saved_auto_trim = g.auto_trim;
|
|
||||||
g.auto_trim.set(0);
|
|
||||||
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
||||||
set_mode(mode_rtl, ModeReason::FENCE_BREACHED);
|
set_mode(mode_rtl, ModeReason::FENCE_BREACHED);
|
||||||
} else {
|
} else {
|
||||||
set_mode(mode_guided, ModeReason::FENCE_BREACHED);
|
set_mode(mode_guided, ModeReason::FENCE_BREACHED);
|
||||||
}
|
}
|
||||||
g.auto_trim.set(saved_auto_trim);
|
|
||||||
|
|
||||||
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
|
||||||
guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
|
guided_WP_loc = rally.calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
|
||||||
|
@ -279,10 +279,6 @@ public:
|
|||||||
|
|
||||||
// methods that affect movement of the vehicle in this mode
|
// methods that affect movement of the vehicle in this mode
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
void _exit() override;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,13 +1,6 @@
|
|||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
void ModeManual::_exit()
|
|
||||||
{
|
|
||||||
if (plane.g.auto_trim > 0) {
|
|
||||||
plane.trim_radio();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeManual::update()
|
void ModeManual::update()
|
||||||
{
|
{
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.roll_in_expo(false));
|
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.roll_in_expo(false));
|
||||||
|
Loading…
Reference in New Issue
Block a user