ardupilot/ArduCopter/mode_acro.cpp

168 lines
6.6 KiB
C++
Raw Normal View History

#include "Copter.h"
#include "mode.h"
2014-01-24 23:00:07 -04:00
#if MODE_ACRO_ENABLED == ENABLED
2014-01-24 23:00:07 -04:00
/*
* Init and run calls for acro flight mode
2014-01-24 23:00:07 -04:00
*/
bool Copter::ModeAcro::init(bool ignore_checks)
2014-01-24 23:00:07 -04:00
{
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors->armed() && ap.land_complete && !copter.flightmode->has_manual_throttle() &&
(get_pilot_desired_throttle(channel_throttle->get_control_in(), copter.g2.acro_thr_mid) > copter.get_non_takeoff_throttle())) {
return false;
}
return true;
2014-01-24 23:00:07 -04:00
}
void Copter::ModeAcro::run()
2014-01-24 23:00:07 -04:00
{
float target_roll, target_pitch, target_yaw;
float pilot_throttle_scaled;
2014-01-24 23:00:07 -04:00
// if not armed set throttle to zero and exit immediately
if (!motors->armed() || ap.throttle_zero || !motors->get_interlock()) {
zero_throttle_and_relax_ac();
return;
}
// clear landing flag
set_land_complete(false);
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
2014-01-24 23:00:07 -04:00
// convert the input to the desired body frame rate
ArduCopter: Fix up after refactoring RC_Channel class Further to refactor of RC_Channel class which included adding get_xx set_xx methods, change reads and writes to the public members to calls to get and set functionsss old public member(int16_t) get function -> int16_t set function (int16_t) (expression where c is an object of type RC_Channel) c.radio_in c.get_radio_in() c.set_radio_in(v) c.control_in c.get_control_in() c.set_control_in(v) c.servo_out c.get_servo_out() c.set_servo_out(v) c.pwm_out c.get_pwm_out() // use existing c.radio_out c.get_radio_out() c.set_radio_out(v) c.radio_max c.get_radio_max() c.set_radio_max(v) c.radio_min c.get_radio_min() c.set_radio_min(v) c.radio_trim c.get_radio_trim() c.set_radio_trim(v); c.min_max_configured() // return true if min and max are configured Because data members of RC_Channels are now private and so cannot be written directly some overloads are provided in the Plane classes to provide the old functionality new overload Plane::stick_mix_channel(RC_Channel *channel) which forwards to the previously existing void stick_mix_channel(RC_Channel *channel, int16_t &servo_out); new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const which forwards to (uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const; Rename functions RC_Channel_aux::set_radio_trim(Aux_servo_function_t function) to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function) RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value) to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value) Rationale: RC_Channel is a complicated class, which combines several functionalities dealing with stick inputs in pwm and logical units, logical and actual actuator outputs, unit conversion etc, etc The intent of this PR is to clarify existing use of the class. At the basic level it should now be possible to grep all places where private variable is set by searching for the set_xx function. (The wider purpose is to provide a more generic and logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
2014-01-24 23:00:07 -04:00
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in(), g2.acro_thr_mid);
// run attitude controller
attitude_control->input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
// output pilot's throttle without angle boost
attitude_control->set_throttle_out(pilot_throttle_scaled, false, copter.g.throttle_filt);
2014-01-24 23:00:07 -04:00
}
// get_pilot_desired_angle_rates - transform pilot's roll pitch and yaw input into a desired lean angle rates
// returns desired angle rates in centi-degrees-per-second
void Copter::ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out)
2014-01-24 23:00:07 -04:00
{
float rate_limit;
2014-01-24 23:00:07 -04:00
Vector3f rate_ef_level, rate_bf_level, rate_bf_request;
2014-11-10 20:07:08 -04:00
// apply circular limit to pitch and roll inputs
float total_in = norm(pitch_in, roll_in);
2014-11-10 20:07:08 -04:00
if (total_in > ROLL_PITCH_YAW_INPUT_MAX) {
float ratio = (float)ROLL_PITCH_YAW_INPUT_MAX / total_in;
2014-11-10 20:07:08 -04:00
roll_in *= ratio;
pitch_in *= ratio;
}
2014-08-12 23:25:59 -03:00
// calculate roll, pitch rate requests
if (g.acro_rp_expo <= 0) {
2014-08-12 23:25:59 -03:00
rate_bf_request.x = roll_in * g.acro_rp_p;
rate_bf_request.y = pitch_in * g.acro_rp_p;
} else {
// expo variables
float rp_in, rp_in3, rp_out;
// range check expo
if (g.acro_rp_expo > 1.0f) {
g.acro_rp_expo = 1.0f;
}
2014-08-12 23:25:59 -03:00
// roll expo
rp_in = float(roll_in)/ROLL_PITCH_YAW_INPUT_MAX;
2014-08-12 23:25:59 -03:00
rp_in3 = rp_in*rp_in*rp_in;
rp_out = (g.acro_rp_expo * rp_in3) + ((1.0f - g.acro_rp_expo) * rp_in);
rate_bf_request.x = ROLL_PITCH_YAW_INPUT_MAX * rp_out * g.acro_rp_p;
2014-08-12 23:25:59 -03:00
// pitch expo
rp_in = float(pitch_in)/ROLL_PITCH_YAW_INPUT_MAX;
2014-08-12 23:25:59 -03:00
rp_in3 = rp_in*rp_in*rp_in;
rp_out = (g.acro_rp_expo * rp_in3) + ((1.0f - g.acro_rp_expo) * rp_in);
rate_bf_request.y = ROLL_PITCH_YAW_INPUT_MAX * rp_out * g.acro_rp_p;
2014-08-12 23:25:59 -03:00
}
// calculate yaw rate request
2016-10-23 03:55:33 -03:00
rate_bf_request.z = get_pilot_desired_yaw_rate(yaw_in);
2014-01-24 23:00:07 -04:00
// calculate earth frame rate corrections to pull the copter back to level while in ACRO mode
if (g.acro_trainer != ACRO_TRAINER_DISABLED) {
// get attitude targets
const Vector3f att_target = attitude_control->get_att_target_euler_cd();
// Calculate trainer mode earth frame rate command for roll
int32_t roll_angle = wrap_180_cd(att_target.x);
rate_ef_level.x = -constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll;
// Calculate trainer mode earth frame rate command for pitch
int32_t pitch_angle = wrap_180_cd(att_target.y);
rate_ef_level.y = -constrain_int32(pitch_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_pitch;
// Calculate trainer mode earth frame rate command for yaw
rate_ef_level.z = 0;
// Calculate angle limiting earth frame rate commands
if (g.acro_trainer == ACRO_TRAINER_LIMITED) {
const float angle_max = copter.aparm.angle_max;
if (roll_angle > angle_max){
rate_ef_level.x -= g.acro_balance_roll*(roll_angle-angle_max);
}else if (roll_angle < -angle_max) {
rate_ef_level.x -= g.acro_balance_roll*(roll_angle+angle_max);
}
if (pitch_angle > angle_max){
rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle-angle_max);
}else if (pitch_angle < -angle_max) {
rate_ef_level.y -= g.acro_balance_pitch*(pitch_angle+angle_max);
}
2014-01-24 23:00:07 -04:00
}
// convert earth-frame level rates to body-frame level rates
attitude_control->euler_rate_to_ang_vel(attitude_control->get_att_target_euler_cd()*radians(0.01f), rate_ef_level, rate_bf_level);
// combine earth frame rate corrections with rate requests
if (g.acro_trainer == ACRO_TRAINER_LIMITED) {
rate_bf_request.x += rate_bf_level.x;
rate_bf_request.y += rate_bf_level.y;
rate_bf_request.z += rate_bf_level.z;
}else{
float acro_level_mix = constrain_float(1-float(MAX(MAX(abs(roll_in), abs(pitch_in)), abs(yaw_in))/4500.0), 0, 1)*ahrs.cos_pitch();
// Scale leveling rates by stick input
rate_bf_level = rate_bf_level*acro_level_mix;
// Calculate rate limit to prevent change of rate through inverted
2015-05-08 15:40:08 -03:00
rate_limit = fabsf(fabsf(rate_bf_request.x)-fabsf(rate_bf_level.x));
rate_bf_request.x += rate_bf_level.x;
rate_bf_request.x = constrain_float(rate_bf_request.x, -rate_limit, rate_limit);
// Calculate rate limit to prevent change of rate through inverted
rate_limit = fabsf(fabsf(rate_bf_request.y)-fabsf(rate_bf_level.y));
rate_bf_request.y += rate_bf_level.y;
rate_bf_request.y = constrain_float(rate_bf_request.y, -rate_limit, rate_limit);
// Calculate rate limit to prevent change of rate through inverted
2015-05-08 15:40:08 -03:00
rate_limit = fabsf(fabsf(rate_bf_request.z)-fabsf(rate_bf_level.z));
rate_bf_request.z += rate_bf_level.z;
rate_bf_request.z = constrain_float(rate_bf_request.z, -rate_limit, rate_limit);
}
2014-01-24 23:00:07 -04:00
}
// hand back rate request
roll_out = rate_bf_request.x;
pitch_out = rate_bf_request.y;
yaw_out = rate_bf_request.z;
}
#endif