Copter: Add parameter LAND_REPOSITION to enable/disable user input during auto-mode landings and descents
This commit is contained in:
parent
2dfef17caf
commit
5b36e65cb9
@ -111,10 +111,11 @@ public:
|
||||
k_param_rally,
|
||||
k_param_hybrid_brake_rate,
|
||||
k_param_hybrid_brake_angle_max,
|
||||
k_param_pilot_accel_z, // 48
|
||||
k_param_pilot_accel_z,
|
||||
k_param_serial0_baud,
|
||||
k_param_serial1_baud,
|
||||
k_param_serial2_baud,
|
||||
k_param_land_repositioning, // 52
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
@ -384,6 +385,8 @@ public:
|
||||
AP_Int8 ch8_option;
|
||||
AP_Int8 arming_check;
|
||||
|
||||
AP_Int8 land_repositioning;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Heli
|
||||
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
|
||||
|
@ -442,6 +442,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(hybrid_brake_angle_max, "HYBR_BRAKE_ANGLE", HYBRID_BRAKE_ANGLE_DEFAULT),
|
||||
#endif
|
||||
|
||||
// @Param: LAND_REPOSITION
|
||||
// @DisplayName: Land repositioning
|
||||
// @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
|
||||
// @Values: 0:No repositiong, 1:Repositioning
|
||||
// @User: Advanced
|
||||
GSCALAR(land_repositioning, "LAND_REPOSITION", LAND_REPOSITION_DEFAULT),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// @Group: HS1_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
|
@ -461,6 +461,9 @@
|
||||
#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM // require pilot to reduce throttle to minimum before vehicle will disarm
|
||||
# define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED
|
||||
#endif
|
||||
#ifndef LAND_REPOSITION_DEFAULT
|
||||
# define LAND_REPOSITION_DEFAULT 0 // by default the pilot cannot override roll/pitch during landing
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// CAMERA TRIGGER AND CONTROL
|
||||
|
@ -274,6 +274,9 @@ static void auto_land_start(const Vector3f& destination)
|
||||
// called by auto_run at 100hz or more
|
||||
static void auto_land_run()
|
||||
{
|
||||
int16_t roll_control = 0, pitch_control = 0;
|
||||
float target_yaw_rate = 0;
|
||||
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || ap.land_complete) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
@ -284,13 +287,24 @@ static void auto_land_run()
|
||||
return;
|
||||
}
|
||||
|
||||
// process pilot's yaw input
|
||||
float target_yaw_rate = 0;
|
||||
// process pilot's input
|
||||
if (!failsafe.radio) {
|
||||
if (g.land_repositioning) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
}
|
||||
|
||||
// process roll, pitch inputs
|
||||
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
|
||||
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
||||
|
@ -68,12 +68,14 @@ static void land_gps_run()
|
||||
|
||||
// process pilot inputs
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
if (g.land_repositioning) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
@ -122,11 +124,13 @@ static void land_nogps_run()
|
||||
|
||||
// process pilot inputs
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
if (g.land_repositioning) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// get pilot desired lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
// get pilot desired lean angles
|
||||
get_pilot_desired_lean_angles(g.rc_1.control_in, g.rc_2.control_in, target_roll, target_pitch);
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
|
@ -251,6 +251,9 @@ static void rtl_descent_start()
|
||||
// called by rtl_run at 100hz or more
|
||||
static void rtl_descent_run()
|
||||
{
|
||||
int16_t roll_control = 0, pitch_control = 0;
|
||||
float target_yaw_rate = 0;
|
||||
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || !inertial_nav.position_ok()) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
@ -262,21 +265,23 @@ static void rtl_descent_run()
|
||||
}
|
||||
|
||||
// process pilot's input
|
||||
float target_yaw_rate = 0;
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
if (g.land_repositioning) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
} else {
|
||||
// clear out pilot desired acceleration in case radio failsafe event occurs while descending
|
||||
wp_nav.clear_pilot_desired_acceleration();
|
||||
}
|
||||
|
||||
// process roll, pitch inputs
|
||||
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
|
||||
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
||||
@ -311,6 +316,8 @@ static void rtl_land_start()
|
||||
// called by rtl_run at 100hz or more
|
||||
static void rtl_land_run()
|
||||
{
|
||||
int16_t roll_control = 0, pitch_control = 0;
|
||||
float target_yaw_rate = 0;
|
||||
// if not auto armed set throttle to zero and exit immediately
|
||||
if(!ap.auto_armed || !inertial_nav.position_ok()) {
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
@ -321,22 +328,24 @@ static void rtl_land_run()
|
||||
return;
|
||||
}
|
||||
|
||||
// process pilot's yaw input
|
||||
float target_yaw_rate = 0;
|
||||
// process pilot's input
|
||||
if (!failsafe.radio) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
if (g.land_repositioning) {
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
update_simple_mode();
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
wp_nav.set_pilot_desired_acceleration(g.rc_1.control_in, g.rc_2.control_in);
|
||||
// process pilot's roll and pitch input
|
||||
roll_control = g.rc_1.control_in;
|
||||
pitch_control = g.rc_2.control_in;
|
||||
}
|
||||
|
||||
// get pilot's desired yaw rate
|
||||
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in);
|
||||
} else {
|
||||
// clear out pilot desired acceleration in case radio failsafe event occurs while landing
|
||||
wp_nav.clear_pilot_desired_acceleration();
|
||||
}
|
||||
|
||||
// process pilot's roll and pitch input
|
||||
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
|
||||
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user