mirror of https://github.com/ArduPilot/ardupilot
Plane: Add flight options bitmask
This commit is contained in:
parent
8c962e6f0f
commit
8417bcc7d5
|
@ -350,7 +350,7 @@ void Plane::stabilize_acro(float speed_scaler)
|
|||
/*
|
||||
manual rudder for now
|
||||
*/
|
||||
steering_control.steering = steering_control.rudder = rudder_input;
|
||||
steering_control.steering = steering_control.rudder = rudder_input();
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -450,9 +450,7 @@ void Plane::calc_throttle()
|
|||
void Plane::calc_nav_yaw_coordinated(float speed_scaler)
|
||||
{
|
||||
bool disable_integrator = false;
|
||||
if (control_mode == STABILIZE && rudder_input != 0) {
|
||||
disable_integrator = true;
|
||||
}
|
||||
int16_t rudder_in = rudder_input();
|
||||
|
||||
int16_t commanded_rudder;
|
||||
|
||||
|
@ -462,11 +460,15 @@ void Plane::calc_nav_yaw_coordinated(float speed_scaler)
|
|||
millis() - plane.guided_state.last_forced_rpy_ms.z < 3000) {
|
||||
commanded_rudder = plane.guided_state.forced_rpy_cd.z;
|
||||
} else {
|
||||
if (control_mode == STABILIZE && rudder_in != 0) {
|
||||
disable_integrator = true;
|
||||
}
|
||||
|
||||
commanded_rudder = yawController.get_servo_out(speed_scaler, disable_integrator);
|
||||
|
||||
// add in rudder mixing from roll
|
||||
commanded_rudder += SRV_Channels::get_output_scaled(SRV_Channel::k_aileron) * g.kff_rudder_mix;
|
||||
commanded_rudder += rudder_input;
|
||||
commanded_rudder += rudder_in;
|
||||
}
|
||||
|
||||
steering_control.rudder = constrain_int16(commanded_rudder, -4500, 4500);
|
||||
|
@ -499,11 +501,11 @@ void Plane::calc_nav_yaw_ground(void)
|
|||
// manual rudder control while still
|
||||
steer_state.locked_course = false;
|
||||
steer_state.locked_course_err = 0;
|
||||
steering_control.steering = rudder_input;
|
||||
steering_control.steering = rudder_input();
|
||||
return;
|
||||
}
|
||||
|
||||
float steer_rate = (rudder_input/4500.0f) * g.ground_steer_dps;
|
||||
float steer_rate = (rudder_input()/4500.0f) * g.ground_steer_dps;
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF ||
|
||||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
||||
steer_rate = 0;
|
||||
|
|
|
@ -1177,6 +1177,13 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||
AP_SUBGROUPINFO(gripper, "GRIP_", 12, ParametersG2, AP_Gripper),
|
||||
#endif
|
||||
|
||||
// @Param: FLIGHT_OPTIONS
|
||||
// @DisplayName: Flight mode options
|
||||
// @Description: Flight mode specific options
|
||||
// @Bitmask: 0:Rudder mixing in direct flight modes only (Manual, Stabilize, Acro)
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -544,6 +544,8 @@ public:
|
|||
// Payload Gripper
|
||||
AP_Gripper gripper;
|
||||
#endif
|
||||
|
||||
AP_Int32 flight_options;
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
|
|
@ -590,9 +590,6 @@ private:
|
|||
// The instantaneous desired pitch angle. Hundredths of a degree
|
||||
int32_t nav_pitch_cd;
|
||||
|
||||
// we separate out rudder input to allow for RUDDER_ONLY=1
|
||||
int16_t rudder_input;
|
||||
|
||||
// the aerodymamic load factor. This is calculated from the demanded
|
||||
// roll before the roll is clipped, using 1/sqrt(cos(nav_roll))
|
||||
float aerodynamic_load_factor = 1.0f;
|
||||
|
@ -909,9 +906,10 @@ private:
|
|||
void init_rc_out_aux();
|
||||
void rudder_arm_disarm_check();
|
||||
void read_radio();
|
||||
int16_t rudder_input(void);
|
||||
void control_failsafe();
|
||||
bool trim_radio();
|
||||
bool rc_failsafe_active(void);
|
||||
bool rc_failsafe_active(void) const;
|
||||
void read_rangefinder(void);
|
||||
void read_airspeed(void);
|
||||
void rpm_update(void);
|
||||
|
|
|
@ -197,3 +197,7 @@ enum {
|
|||
USE_REVERSE_THRUST_FBWB = (1<<9),
|
||||
USE_REVERSE_THRUST_GUIDED = (1<<10),
|
||||
};
|
||||
|
||||
enum FlightOptions {
|
||||
DIRECT_RUDDER_ONLY = (1 << 0),
|
||||
};
|
||||
|
|
|
@ -231,7 +231,7 @@ void Plane::update_cruise()
|
|||
{
|
||||
if (!cruise_state.locked_heading &&
|
||||
channel_roll->get_control_in() == 0 &&
|
||||
rudder_input == 0 &&
|
||||
rudder_input() == 0 &&
|
||||
gps.status() >= AP_GPS::GPS_OK_FIX_2D &&
|
||||
gps.ground_speed() >= 3 &&
|
||||
cruise_state.lock_timer_ms == 0) {
|
||||
|
|
|
@ -210,22 +210,33 @@ void Plane::read_radio()
|
|||
|
||||
rudder_arm_disarm_check();
|
||||
|
||||
// potentially swap inputs for tailsitters
|
||||
quadplane.tailsitter_check_input();
|
||||
|
||||
// check for transmitter tuning changes
|
||||
tuning.check_input(control_mode);
|
||||
}
|
||||
|
||||
int16_t Plane::rudder_input(void)
|
||||
{
|
||||
if (g.rudder_only != 0) {
|
||||
// in rudder only mode we discard rudder input and get target
|
||||
// attitude from the roll channel.
|
||||
rudder_input = 0;
|
||||
} else if (stick_mixing_enabled()) {
|
||||
rudder_input = channel_rudder->get_control_in();
|
||||
} else {
|
||||
// no stick mixing
|
||||
rudder_input = 0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
// potentially swap inputs for tailsitters
|
||||
quadplane.tailsitter_check_input();
|
||||
if ((g2.flight_options & FlightOptions::DIRECT_RUDDER_ONLY) &&
|
||||
!(control_mode == MANUAL || control_mode == STABILIZE || control_mode == ACRO)) {
|
||||
// the user does not want any input except in these modes
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (stick_mixing_enabled()) {
|
||||
return channel_rudder->get_control_in();
|
||||
}
|
||||
|
||||
return 0;
|
||||
|
||||
// check for transmitter tuning changes
|
||||
tuning.check_input(control_mode);
|
||||
}
|
||||
|
||||
void Plane::control_failsafe()
|
||||
|
@ -340,7 +351,7 @@ bool Plane::trim_radio()
|
|||
return true if throttle level is below throttle failsafe threshold
|
||||
or RC input is invalid
|
||||
*/
|
||||
bool Plane::rc_failsafe_active(void)
|
||||
bool Plane::rc_failsafe_active(void) const
|
||||
{
|
||||
if (!g.throttle_fs_enabled) {
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue